mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-18 03:52:11 +01:00
Merge remote-tracking branch 'upstream/master' into next
# Conflicts: # ground/gcs/src/plugins/coreplugin/connectionmanager.cpp
This commit is contained in:
commit
33188bd78e
@ -3,6 +3,7 @@ Sergiy Anikeyev
|
||||
David Ankers
|
||||
Fredrik Arvidsson
|
||||
Pedro Assuncao
|
||||
Rafael Bachmann
|
||||
Werner Backes
|
||||
Jose Barros
|
||||
Alex Beck
|
||||
@ -24,6 +25,7 @@ James Cotton
|
||||
Kalyn Doerr
|
||||
Steve Doll
|
||||
James Duley
|
||||
Heikko Ellermaa
|
||||
Piotr Esden-Tempski
|
||||
Steve Evans
|
||||
Peter Farnworth
|
||||
@ -43,6 +45,7 @@ Nuno Guedes
|
||||
Peter Gunnarsson
|
||||
Erik Gustavsson
|
||||
Dean Hall
|
||||
Harold Hankins
|
||||
Joe Hlebasko
|
||||
Andy Honecker
|
||||
Patrick Huebner
|
||||
@ -50,6 +53,7 @@ Ryan Hunt
|
||||
Mark James
|
||||
Paul Jewell
|
||||
Michael Johnston
|
||||
Mateusz Kaduk
|
||||
Stefan Karlsson
|
||||
Ricky King
|
||||
Thorsten Klose
|
||||
@ -68,6 +72,7 @@ Pablo Lema
|
||||
Matt Lipski
|
||||
David Llama
|
||||
Jasper Van Loenen
|
||||
Ákos Máté
|
||||
Ben Matthews
|
||||
Greg Matthews
|
||||
Guy McCaldin
|
||||
@ -79,6 +84,7 @@ Ken Northup
|
||||
Craig Nuttall
|
||||
Bertrand Oresve
|
||||
Angus Peart
|
||||
Pablo Francisco Pérez Hidalgo
|
||||
John Pike
|
||||
Jorge Pombo Marcos
|
||||
Dmytro Poplavskiy
|
||||
@ -116,9 +122,12 @@ Kevin Vertucio
|
||||
Alex Vrubel
|
||||
Mike Walters
|
||||
Sam Wang
|
||||
Tianhe Wang
|
||||
Brian Webb
|
||||
Justin Welander
|
||||
Mat Wellington
|
||||
Kendal Wells
|
||||
David Willis
|
||||
Dmitriy Zaitsev
|
||||
Vladimir Zidar
|
||||
|
||||
|
1
Makefile
1
Makefile
@ -411,6 +411,7 @@ $(FW_DIST_TAR): $(PACKAGE_FW_TARGETS) | $(DIST_DIR)
|
||||
$(V1) tar -c --file="$(FW_DIST_TAR)" --directory=$(FLIGHT_OUT_DIR) \
|
||||
--owner=root --group=root --mtime="`git show -s --format=%ci`" \
|
||||
--transform='s,^,firmware/,' \
|
||||
--force-local \
|
||||
$(foreach fw_targ,$(PACKAGE_FW_TARGETS),$(fw_targ)/$(fw_targ).opfw)
|
||||
|
||||
$(FW_DIST_TAR_GZ): $(FW_DIST_TAR)
|
||||
|
226
WHATSNEW.txt
226
WHATSNEW.txt
@ -1,3 +1,229 @@
|
||||
-- RELEASE-16.09 - Second LibrePilot Release -- Black Rhino
|
||||
This is the second LibrePilot release.
|
||||
|
||||
This release introduces new features and new hardware support like Sparky2 board and improved external mag support.
|
||||
|
||||
New hardware support:
|
||||
Sparky2 board, Auxiliary Magnetometer: I2C and Naza GPS, Revo FlexiIO port usage e.g. PPM+GPS
|
||||
|
||||
New input modes:
|
||||
Jeti Ex.Bus, Graupner Hott, FlySky IBus, PPM up to 16 channels, Revo/Sparky2 as OpenLRS receiver.
|
||||
|
||||
New telemetry protocols:
|
||||
MSP, MAVLink. OSD devices that use those protocols may now be connected directly (e.g.: minimosd with MWOSD).
|
||||
|
||||
New Flight oriented features:
|
||||
AlwaysStabilizeWhenArmed (Airmode) using switch, Measurement based D term gives smoother flight
|
||||
SuperExpo (you may need half expo value compared to rel15.09), Camera tilt compensation,
|
||||
Autotune module (except CC3D).
|
||||
|
||||
GCS improvements:
|
||||
PFD with terrain / OsgEarth improvements
|
||||
Failsafe settings using GUI
|
||||
Vehicle and Transmitter wizard improvements
|
||||
|
||||
Known issues:
|
||||
* [LP-289] - pidcontrol ne and down have nan dz if kp is zero
|
||||
|
||||
The full list of bug fixes and enhancements in this release is available here:
|
||||
https://librepilot.atlassian.net/issues/?filter=10500
|
||||
|
||||
|
||||
Release Notes - LibrePilot - Version REL-16.09
|
||||
|
||||
** Sub-task
|
||||
* [LP-120] - Add Ublox GPS + I2C Mag to Wizard
|
||||
|
||||
** Bug
|
||||
* [LP-59] - Replace openpilot email address in packaging
|
||||
* [LP-83] - Bricking of Revo and Sparky2
|
||||
* [LP-111] - Fix directory hash calculated to only include tracked files
|
||||
* [LP-119] - #if used instead of #ifdef in pios_msheap.c
|
||||
* [LP-139] - Erroneous warning about missing pfd.svg
|
||||
* [LP-143] - Fix the "firmware upload no responding" issue
|
||||
* [LP-145] - CC3D GPS issue
|
||||
* [LP-154] - Fix gitignore - bare config causes all config directories to be ignored.
|
||||
* [LP-160] - Set default AccelTau value
|
||||
* [LP-165] - Acro+ factor range in TxPID
|
||||
* [LP-167] - Stable version checker points to bad url
|
||||
* [LP-171] - Acro+ Link Roll and Pitch affects all banks
|
||||
* [LP-175] - Fix src rpm name
|
||||
* [LP-181] - QT5.5 : PFD parts are broken
|
||||
* [LP-182] - CC3D/Revonano OPlink Telemetry issue @38400
|
||||
* [LP-184] - make: incremental build issues
|
||||
* [LP-185] - Debian dist detection broken
|
||||
* [LP-191] - Make TxWizard more robust
|
||||
* [LP-193] - Remove Libpng warnings
|
||||
* [LP-197] - QT-5.5.1 broken translations
|
||||
* [LP-198] - Cannot detect lost of PPM signal
|
||||
* [LP-204] - Fast_invsqrtf() issue
|
||||
* [LP-205] - Rate trainer wobble at max angle
|
||||
* [LP-206] - AlwaysStabilizeWhenArmed need to be disabled at takeoff/landing
|
||||
* [LP-209] - Oplm link_quality still good with link lost
|
||||
* [LP-215] - OpLink controller Tx should force failsafe if PPM stream fails
|
||||
* [LP-216] - GCS misbehaves on high DPI devices
|
||||
* [LP-218] - msys2 provided opengl library breaks GCS
|
||||
* [LP-221] - Increase Revo System stack size
|
||||
* [LP-222] - Building osg and osgearth fails
|
||||
* [LP-223] - Unit tests build is broken
|
||||
* [LP-228] - CC3D reboot while import config file
|
||||
* [LP-241] - Allow CruiseControl for Rate mode at least
|
||||
* [LP-245] - GCS unsaved data prompt when nothing changed
|
||||
* [LP-249] - Fix bug introduced in LP-235
|
||||
* [LP-251] - UAVObjectGeneratorGCS::process_object uses incorrect param null check
|
||||
* [LP-252] - GPSv9 drops packets
|
||||
* [LP-257] - OSX compile issue introduced by a93f182
|
||||
* [LP-258] - Update flight controller in real time locks to basic tab
|
||||
* [LP-261] - Upgrade GCS map versions
|
||||
* [LP-263] - GCS default config updates
|
||||
* [LP-266] - pitch virtual board rotation in gui is limited to 90 degrees
|
||||
* [LP-273] - Reset Mag alarm when going back to Basic complementary fusion algorithm
|
||||
* [LP-274] - Consistent Attitude board rotation values for all boards
|
||||
* [LP-275] - OSX build errors
|
||||
* [LP-277] - OPMap compilation warning
|
||||
* [LP-281] - PIOS_SENSORS_GetInstanceByType() has incorrect matching operator
|
||||
* [LP-285] - Tx Wizard : Set Accessory neutral to middle range
|
||||
* [LP-289] - pidcontrol ne and down have nan dz if kp is zero
|
||||
* [LP-290] - Windows GCS uninstall is very long
|
||||
* [LP-299] - gcc5 building isnan issue
|
||||
* [LP-305] - GCS crashes shortly after start on OSX - when loading OPMap gadget
|
||||
* [LP-309] - When arming with accessory switch, disarming timeout doesn't work.
|
||||
* [LP-310] - osg: random GCS crashes when switching or closing PFDQml gadgets
|
||||
* [LP-312] - GCS config - attitude - mag tab offers sparky2 i2c port on revo
|
||||
* [LP-313] - using UAVObjectBrowser filter text always enables metadata display
|
||||
* [LP-321] - MSP in ReceiverPort menu for RevoNano
|
||||
* [LP-333] - Sparky2 I2CPort needs GPIO_PuPd_UP instead of NOPULL
|
||||
* [LP-339] - Avoid AutoTakeOff flight mode while already armed
|
||||
* [LP-341] - VCP doesn't work on Windows 10 or 8.1
|
||||
* [LP-362] - GCS crashes when logging to file with -log command line argument
|
||||
* [LP-363] - OPMap missing tiles
|
||||
* [LP-369] - Fix availability condition for VCP
|
||||
* [LP-382] - MSP stack overflow on PID save op.
|
||||
* [LP-387] - Sparky2 analog port mapping
|
||||
* [LP-388] - Wrong AuxMag calibration due to wrong initial settings
|
||||
* [LP-391] - Some CC3D ports cause a boot issue and re-init to defaults.
|
||||
* [LP-392] - Revo attitude settings is missing the "Zero gyro when arming" checkbox
|
||||
* [LP-395] - Raise BoardSteadyMaxVariance to support some boards having higher gyro noise
|
||||
* [LP-400] - Doxygen document build fails with latex errors
|
||||
* [LP-401] - Reboot is required after AutoTune is set in FMS
|
||||
* [LP-406] - Windows driver fails to install
|
||||
* [LP-409] - make fw_dist fails on windows
|
||||
* [LP-421] - GCS setup wizard welcome panel is too big on high dpi screens
|
||||
* [LP-423] - HMC5x83 driver dereferences null pointer
|
||||
* [LP-424] - pios_openlrs.c has incorrect reference to rfm22b_id
|
||||
* [LP-429] - changes to FlightModeSettings do not trigger a configuration check
|
||||
* [LP-444] - I2C alarm
|
||||
* [LP-447] - ESC calibration failure with FVT LitteBee 20A
|
||||
|
||||
|
||||
** Story
|
||||
* [LP-32] - osgearth integration (follow up cleanups)
|
||||
|
||||
** New Feature
|
||||
* [LP-29] - osgearth integration
|
||||
* [LP-149] - Add STM32F427/429/437/439 chip support, preparation for brand new board.
|
||||
* [LP-212] - Support DJI GPS and mag combo uses one port
|
||||
* [LP-214] - Camera tilt compensation
|
||||
* [LP-233] - OneShot42 / MultiShot support
|
||||
* [LP-280] - After firmware boots, start calibration when vehicle is not moving
|
||||
* [LP-286] - Port search field in UAVBrowser from TL
|
||||
* [LP-291] - Port MSP support from dRonin
|
||||
* [LP-298] - Create iBus support for RX
|
||||
* [LP-327] - Wait for board to be steady before calibrating gyro
|
||||
* [LP-364] - Port and improve MavLink support from dRonin
|
||||
* [LP-425] - Add Credits to the About dialog
|
||||
|
||||
** Task
|
||||
* [LP-2] - Upgrade to Qt 5.5
|
||||
* [LP-30] - osg/osgearth/marble build scripts
|
||||
* [LP-40] - Add support for TravisCI
|
||||
* [LP-72] - Sparky 2 support
|
||||
* [LP-73] - External Mags on I2C
|
||||
* [LP-76] - Port Tau Labs Autotune to LP
|
||||
* [LP-88] - Remove OpenPilot branding from .commit-template
|
||||
* [LP-140] - Update Logo files in Artwork
|
||||
* [LP-186] - Add copyright to qml and js files
|
||||
* [LP-187] - Use Msys2
|
||||
* [LP-194] - Hide Yaw Attitude related parameter from Stabilization panel
|
||||
* [LP-195] - Update World Magnetic Model
|
||||
* [LP-200] - Remove Opie
|
||||
* [LP-201] - Update Y6 mixer
|
||||
* [LP-208] - Upgrade to Qt 5.6
|
||||
* [LP-230] - PFD refresh after recent additions
|
||||
* [LP-247] - Add Naza GPS/Mag to Wizard
|
||||
* [LP-267] - Enable more options in the current GUI for fusion algorithm
|
||||
* [LP-292] - Oplink tab cleanup
|
||||
* [LP-306] - Update Ubuntu PPA to build with osgearth
|
||||
* [LP-307] - Set up Tea CI
|
||||
* [LP-315] - Update vehicle templates
|
||||
* [LP-317] - Update RPM packaging for osgearth
|
||||
* [LP-325] - Reduce the threshold for ASWA switch
|
||||
* [LP-328] - Sparky2 reboots constantly with only USB power and unpowered external mag
|
||||
* [LP-330] - Fix copyright symbol in all code, make it consistent
|
||||
* [LP-349] - shut up the plan warning alarm
|
||||
* [LP-373] - Add bitbucket pipelines
|
||||
* [LP-374] - Build x86_64 windows on TeaCI as well.
|
||||
* [LP-394] - Upload build results from Tea-Ci
|
||||
|
||||
** Improvement
|
||||
* [LP-96] - Review CPU idle time counter
|
||||
* [LP-97] - Unify Init process between revo*-cc3d boards
|
||||
* [LP-104] - HOTT SUMD support
|
||||
* [LP-147] - Rc transmitter wizard : Auto detect flight mode number
|
||||
* [LP-150] - Run Attitude calculation on CC/CC3D at slower rate than gyro samples
|
||||
* [LP-151] - Settable OPLink (and FC) Device ID
|
||||
* [LP-164] - change OSX dmg .webloc to point to LP website
|
||||
* [LP-168] - Copy the same content and url list as www.librepilot.org in README.md
|
||||
* [LP-174] - Add current value display to RcInput tab
|
||||
* [LP-176] - Allow overriding of package type
|
||||
* [LP-177] - Make debian package src use pre-compiled firmware
|
||||
* [LP-178] - Add pass through feature for FixedWing
|
||||
* [LP-179] - Highlight stabilization mode currently used
|
||||
* [LP-183] - upgrade GCS uav object generator to Qt 5.5
|
||||
* [LP-190] - Add openLRSng Rx support to OPLink/Revo
|
||||
* [LP-196] - JETI EX Bus communication protocol support
|
||||
* [LP-207] - EventDispatcher: Add "fast" callbacks
|
||||
* [LP-219] - OPLink module should accept more than 8 PPM channels
|
||||
* [LP-232] - Display flight mode alarm while setup
|
||||
* [LP-235] - Make Failsafe settings more user friendly by allowing them to be set in the Configuration tab
|
||||
* [LP-238] - Consolidate CPP firmware requirements within apps/boot-defs.mk
|
||||
* [LP-239] - GPS on Flexi IO on Revo
|
||||
* [LP-240] - Aux Mag setup help and GUI
|
||||
* [LP-254] - Set CruiseControl default CruiseControlMaxThrust to 100
|
||||
* [LP-256] - Sparky2 timers and output banks and PPM
|
||||
* [LP-268] - Add TX and RX packet rates to OPLink stats.
|
||||
* [LP-269] - IoT Stream Service
|
||||
* [LP-272] - Altitude velocity Integral default value is set too high
|
||||
* [LP-276] - Measurement based D term
|
||||
* [LP-293] - Add AlarmString() to alarms library.
|
||||
* [LP-295] - OP-1900 fix autotakeoff/landing to not break fixed wing
|
||||
* [LP-302] - Change motor numbering on config - vehicle tab to directional like NW
|
||||
* [LP-304] - Improvements for performance counters
|
||||
* [LP-311] - GCS jumps back to Basic Stabilization if FC changes anything
|
||||
* [LP-322] - USB Com Bridge functionality on OPLink
|
||||
* [LP-324] - MSP on Sparky2
|
||||
* [LP-326] - supporting 16 channels PPM
|
||||
* [LP-335] - add support for address sanitizer in GCS build system
|
||||
* [LP-338] - upgrade GCS to Qt 5.6.1
|
||||
* [LP-340] - AutoTune fix some time measurement issues in original code
|
||||
* [LP-342] - pios_exti to allow runtime (re)configuration
|
||||
* [LP-343] - PIOS_COM_Available() needs to give out more details about RX and TX availability
|
||||
* [LP-352] - Increase Expo effect for high rates
|
||||
* [LP-354] - Add Ublox AssistNow Autonomous setting
|
||||
* [LP-361] - Led notification improvements
|
||||
* [LP-365] - Cleanup com port setup in pios_board.c for coptercontrol
|
||||
* [LP-366] - Set default velocity and altitude in gcs for new waypoints
|
||||
* [LP-377] - ComBridge Speed settings delete
|
||||
* [LP-379] - Add receiverActivity to RC Input tab
|
||||
* [LP-390] - Fix UAVO telemetry errors
|
||||
* [LP-396] - Yaw AcroPlus controls in GUI
|
||||
* [LP-410] - silence GCS logs
|
||||
* [LP-411] - AutoTune Limit Outer PIDs on Powerful Multicopters - dRonin PR 1283
|
||||
* [LP-417] - Heartbeat LED on OPLink
|
||||
* [LP-428] - Reduce the threshold for arming switch
|
||||
* [LP-441] - Template - Wizard dialog on small screens
|
||||
|
||||
|
||||
-- RELEASE-15.09 - First LibrePilot Release -- Supermoon Eclipse
|
||||
This is the first LibrePilot release.
|
||||
The main focus of this release is to bring back support for CC3D and a general re-branding of the GCS.
|
||||
|
@ -3,7 +3,7 @@ Signature = "$Windows NT$"
|
||||
Class = Ports
|
||||
ClassGuid = {4D36E978-E325-11CE-BFC1-08002BE10318}
|
||||
Provider = %ProviderName%
|
||||
DriverVer=05/25/2016,4.0.0.0
|
||||
DriverVer=11/21/2014,3.0.0.0
|
||||
CatalogFile.NTx86 = OpenPilot-CDC_x86.cat
|
||||
CatalogFile.NTamd64 = OpenPilot-CDC_amd64.cat
|
||||
|
||||
@ -15,14 +15,12 @@ CatalogFile.NTamd64 = OpenPilot-CDC_amd64.cat
|
||||
%Revolution% = DriverInstall,USB\VID_20A0&PID_415e&MI_00
|
||||
%OPLinkMini% = DriverInstall,USB\VID_20A0&PID_415c&MI_00
|
||||
%OPLink1W% = DriverInstall,USB\VID_20A0&PID_4195&MI_00
|
||||
%Sparky2% = DriverInstall,USB\VID_20A0&PID_41d0&MI_00
|
||||
|
||||
[DeviceList.NTamd64]
|
||||
%CopterControl% = DriverInstall,USB\VID_20A0&PID_415b&MI_00
|
||||
%Revolution% = DriverInstall,USB\VID_20A0&PID_415e&MI_00
|
||||
%OPLinkMini% = DriverInstall,USB\VID_20A0&PID_415c&MI_00
|
||||
%OPLink1W% = DriverInstall,USB\VID_20A0&PID_4195&MI_00
|
||||
%Sparky2% = DriverInstall,USB\VID_20A0&PID_41d0&MI_00
|
||||
|
||||
[DriverInstall]
|
||||
include = mdmcpq.inf
|
||||
@ -43,4 +41,3 @@ CopterControl = "CopterControl Virtual COM Port"
|
||||
Revolution = "Revolution Virtual COM Port"
|
||||
OPLinkMini = "OPLinkMini Virtual COM Port"
|
||||
OPLink1W = "OPLink1W Virtual COM Port"
|
||||
Sparky2 = "Sparky2 Virtual COM Port"
|
@ -146,6 +146,7 @@ static bool moduleEnabled;
|
||||
|
||||
// Private functions
|
||||
static void AtNewGyroData(UAVObjEvent *ev);
|
||||
static bool AutoTuneFoundInFMS();
|
||||
static void AutoTuneTask(void *parameters);
|
||||
static void AfInit(float X[AF_NUMX], float P[AF_NUMP]);
|
||||
static void AfPredict(float X[AF_NUMX], float P[AF_NUMP], const float u_in[3], const float gyro[3], const float dT_s, const float t_in);
|
||||
@ -153,6 +154,7 @@ static bool CheckFlightModeSwitchForPidRequest(uint8_t flightMode);
|
||||
static uint8_t CheckSettings();
|
||||
static uint8_t CheckSettingsRaw();
|
||||
static void ComputeStabilizationAndSetPidsFromDampAndNoise(float damp, float noise);
|
||||
static void FlightModeSettingsUpdatedCb(UAVObjEvent *ev);
|
||||
static void InitSystemIdent(bool loadDefaults);
|
||||
static void ProportionPidsSmoothToQuick();
|
||||
static void UpdateSystemIdentState(const float *X, const float *noise, float dT_s, uint32_t predicts, uint32_t spills, float hover_throttle);
|
||||
@ -165,10 +167,15 @@ static void UpdateStabilizationDesired(bool doingIdent);
|
||||
*/
|
||||
int32_t AutoTuneInitialize(void)
|
||||
{
|
||||
// Create a queue, connect to manual control command and flightstatus
|
||||
#ifdef MODULE_AutoTune_BUILTIN
|
||||
// do this here since module can become disabled for several reasons
|
||||
// even for MODULE_AutoTune_BUILTIN
|
||||
FlightModeSettingsInitialize();
|
||||
|
||||
#if defined(MODULE_AutoTune_BUILTIN)
|
||||
moduleEnabled = true;
|
||||
#else
|
||||
// HwSettings is only used right here, so init here
|
||||
HwSettingsInitialize();
|
||||
HwSettingsOptionalModulesData optionalModules;
|
||||
HwSettingsOptionalModulesGet(&optionalModules);
|
||||
if (optionalModules.AutoTune == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
@ -178,29 +185,34 @@ int32_t AutoTuneInitialize(void)
|
||||
// that allows PIDs to be adjusted in flight
|
||||
moduleEnabled = true;
|
||||
} else {
|
||||
// if the user did not enable the autotune module
|
||||
// if the user did not manually enable the autotune module
|
||||
// do it for them if they have autotune on their flight mode switch
|
||||
FlightModeSettingsFlightModePositionOptions fms[FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM];
|
||||
moduleEnabled = false;
|
||||
FlightModeSettingsInitialize();
|
||||
FlightModeSettingsFlightModePositionGet(fms);
|
||||
for (uint8_t i = 0; i < FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM; ++i) {
|
||||
if (fms[i] == FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_AUTOTUNE) {
|
||||
moduleEnabled = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
moduleEnabled = AutoTuneFoundInFMS();
|
||||
}
|
||||
#endif /* ifdef MODULE_AutoTune_BUILTIN */
|
||||
#endif /* defined(MODULE_AutoTune_BUILTIN) */
|
||||
|
||||
if (moduleEnabled) {
|
||||
AccessoryDesiredInitialize();
|
||||
ActuatorDesiredInitialize();
|
||||
FlightStatusInitialize();
|
||||
GyroStateInitialize();
|
||||
ManualControlCommandInitialize();
|
||||
StabilizationBankInitialize();
|
||||
StabilizationSettingsBank1Initialize();
|
||||
StabilizationSettingsBank2Initialize();
|
||||
StabilizationSettingsBank3Initialize();
|
||||
SystemIdentSettingsInitialize();
|
||||
SystemIdentStateInitialize();
|
||||
|
||||
atQueue = xQueueCreate(AT_QUEUE_NUMELEM, sizeof(struct at_queued_data));
|
||||
if (!atQueue) {
|
||||
moduleEnabled = false;
|
||||
}
|
||||
}
|
||||
if (!moduleEnabled) {
|
||||
// only need to watch for enabling AutoTune in FMS if AutoTune module is _not_ running
|
||||
FlightModeSettingsConnectCallback(FlightModeSettingsUpdatedCb);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
@ -560,6 +572,26 @@ static void AutoTuneTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
|
||||
|
||||
// FlightModeSettings callback
|
||||
// determine if autotune is enabled in the flight mode switch
|
||||
static bool AutoTuneFoundInFMS()
|
||||
{
|
||||
bool found = false;
|
||||
FlightModeSettingsFlightModePositionOptions fms[FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM];
|
||||
uint8_t num_flightMode;
|
||||
|
||||
FlightModeSettingsFlightModePositionGet(fms);
|
||||
ManualControlSettingsFlightModeNumberGet(&num_flightMode);
|
||||
for (uint8_t i = 0; i < num_flightMode; ++i) {
|
||||
if (fms[i] == FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_AUTOTUNE) {
|
||||
found = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return found;
|
||||
}
|
||||
|
||||
|
||||
// gyro sensor callback
|
||||
// get gyro data and actuatordesired into a packet
|
||||
// and put it in the queue for later processing
|
||||
@ -607,6 +639,16 @@ static void AtNewGyroData(UAVObjEvent *ev)
|
||||
}
|
||||
|
||||
|
||||
// this callback is only enabled if the AutoTune module is not running
|
||||
// if it sees that AutoTune was added to the FMS it issues BOOT and ? alarms
|
||||
static void FlightModeSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
if (AutoTuneFoundInFMS()) {
|
||||
ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL, SYSTEMALARMS_EXTENDEDALARMSTATUS_REBOOTREQUIRED, 0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// check for the user quickly toggling the flight mode switch
|
||||
// into and out of AutoTune, 3 times
|
||||
// that is a signal that the user wants to try the next PID settings
|
||||
@ -908,11 +950,29 @@ static void ComputeStabilizationAndSetPidsFromDampAndNoise(float dampRate, float
|
||||
// inner loop as a single order lpf. Set the outer loop to be
|
||||
// critically damped;
|
||||
const float zeta_o = 1.3f;
|
||||
const float kp_o = 1.0f / 4.0f / (zeta_o * zeta_o) / (1.0f / wn);
|
||||
const float ki_o = 0.75f * kp_o / (2.0f * M_PI_F * tau * 10.0f);
|
||||
float kp_o = 1.0f / 4.0f / (zeta_o * zeta_o) / (1.0f / wn);
|
||||
|
||||
// Except, if this is very high, we may be slew rate limited and pick
|
||||
// up oscillation that way. Fix it with very soft clamping.
|
||||
// (dRonin) MaximumRate defaults to 350, 6.5 corresponds to where we begin
|
||||
// clamping rate ourselves. ESCs, etc, it depends upon gains
|
||||
// and any pre-emphasis they do. Still give ourselves partial credit
|
||||
// for inner loop bandwidth.
|
||||
|
||||
// In dRonin, MaximumRate defaults to 350 and they begin clamping at outer Kp 6.5
|
||||
// To avoid oscillation, find the minimum rate, calculate the ratio of that to 350,
|
||||
// and scale (linearly) with that. Skip yaw. There is no outer yaw in the GUI.
|
||||
const uint16_t minRate = MIN(stabSettingsBank.MaximumRate.Roll, stabSettingsBank.MaximumRate.Pitch);
|
||||
const float kp_o_clamp = systemIdentSettings.OuterLoopKpSoftClamp * ((float)minRate / 350.0f);
|
||||
if (kp_o > kp_o_clamp) {
|
||||
kp_o = kp_o_clamp - sqrtf(kp_o_clamp) + sqrtf(kp_o);
|
||||
}
|
||||
kp_o *= 0.95f; // Pick up some margin.
|
||||
// Add a zero at 1/15th the innermost bandwidth.
|
||||
const float ki_o = 0.75f * kp_o / (2.0f * M_PI_F * tau * 15.0f);
|
||||
|
||||
float kpMax = 0.0f;
|
||||
float betaMinLn = 1000.0f;
|
||||
float betaMinLn = 1000.0f;
|
||||
StabilizationBankRollRatePIDData volatile *rollPitchPid = NULL; // satisfy compiler warning only
|
||||
|
||||
for (int i = 0; i < ((systemIdentSettings.CalculateYaw != SYSTEMIDENTSETTINGS_CALCULATEYAW_FALSE) ? 3 : 2); i++) {
|
||||
|
@ -41,7 +41,7 @@
|
||||
#endif
|
||||
|
||||
// Private constants
|
||||
#define ARMED_THRESHOLD 0.50f
|
||||
#define ARMED_THRESHOLD 0.20f
|
||||
#define GROUND_LOW_THROTTLE 0.01f
|
||||
|
||||
// Private types
|
||||
|
@ -129,14 +129,15 @@ static void SettingsUpdatedCb(UAVObjEvent *ev);
|
||||
*/
|
||||
int32_t ManualControlStart()
|
||||
{
|
||||
// Run this initially to make sure the configuration is checked
|
||||
configuration_check();
|
||||
|
||||
// Whenever the configuration changes, make sure it is safe to fly
|
||||
SystemSettingsConnectCallback(configurationUpdatedCb);
|
||||
ManualControlSettingsConnectCallback(configurationUpdatedCb);
|
||||
FlightModeSettingsConnectCallback(configurationUpdatedCb);
|
||||
ManualControlCommandConnectCallback(commandUpdatedCb);
|
||||
|
||||
// Run this initially to make sure the configuration is checked
|
||||
configuration_check();
|
||||
|
||||
// clear alarms
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_MANUALCONTROL);
|
||||
|
||||
|
@ -138,11 +138,6 @@ static void systemTask(__attribute__((unused)) void *parameters)
|
||||
|
||||
// Main system loop
|
||||
while (1) {
|
||||
// Flash the heartbeat LED
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
|
||||
// Update the OPLinkStatus UAVO
|
||||
OPLinkStatusData oplinkStatus;
|
||||
OPLinkStatusGet(&oplinkStatus);
|
||||
@ -192,10 +187,11 @@ static void systemTask(__attribute__((unused)) void *parameters)
|
||||
oplinkStatus.LinkState = radio_stats.link_state;
|
||||
}
|
||||
|
||||
// Turn on the link/heartbeat ID if we're connected, otherwise flash it.
|
||||
if (radio_stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED) {
|
||||
LINK_LED_ON;
|
||||
} else {
|
||||
LINK_LED_OFF;
|
||||
LINK_LED_TOGGLE;
|
||||
}
|
||||
|
||||
// Update the object
|
||||
|
@ -118,11 +118,17 @@ static void callbackSchedulerForEachCallback(int16_t callback_id, const struct p
|
||||
static void updateStats();
|
||||
static void updateSystemAlarms();
|
||||
static void systemTask(void *parameters);
|
||||
#ifdef DIAG_I2C_WDG_STATS
|
||||
static void updateI2Cstats();
|
||||
#ifdef DIAG_I2C_WDG_STATS
|
||||
static void updateWDGstats();
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
#define I2C_ERROR_ACTIVITY_TIMEOUT_SECONDS 2
|
||||
#define I2C_ERROR_ACTIVITY_TIMEOUT (I2C_ERROR_ACTIVITY_TIMEOUT_SECONDS * 1000 / SYSTEM_UPDATE_PERIOD_MS)
|
||||
static uint8_t i2c_error_activity[PIOS_I2C_ERROR_COUNT_NUMELEM];
|
||||
#endif
|
||||
|
||||
extern uintptr_t pios_uavo_settings_fs_id;
|
||||
extern uintptr_t pios_user_fs_id;
|
||||
|
||||
@ -234,10 +240,13 @@ static void systemTask(__attribute__((unused)) void *parameters)
|
||||
NotificationUpdateStatus();
|
||||
// Update the system statistics
|
||||
updateStats();
|
||||
|
||||
// Update I2C stats
|
||||
updateI2Cstats();
|
||||
|
||||
// Update the system alarms
|
||||
updateSystemAlarms();
|
||||
#ifdef DIAG_I2C_WDG_STATS
|
||||
updateI2Cstats();
|
||||
updateWDGstats();
|
||||
#endif
|
||||
|
||||
@ -480,17 +489,36 @@ static void callbackSchedulerForEachCallback(int16_t callback_id, const struct p
|
||||
#endif /* ifdef DIAG_TASKS */
|
||||
|
||||
/**
|
||||
* Called periodically to update the I2C statistics
|
||||
* Called periodically (every SYSTEM_UPDATE_PERIOD_MS milliseconds) to update the I2C statistics
|
||||
*/
|
||||
#ifdef DIAG_I2C_WDG_STATS
|
||||
static void updateI2Cstats()
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
static uint8_t previous_error_counts[PIOS_I2C_ERROR_COUNT_NUMELEM];
|
||||
|
||||
struct pios_i2c_fault_history history;
|
||||
uint8_t error_counts[PIOS_I2C_ERROR_COUNT_NUMELEM];
|
||||
|
||||
PIOS_I2C_GetDiagnostics(&history, error_counts);
|
||||
|
||||
// every time a counter changes, set activity timeout counter to ( I2C_ERROR_ACTIVITY_TIMEOUT ).
|
||||
// every time a counter does not change, decrease activity counter.
|
||||
|
||||
for (uint8_t i = 0; i < PIOS_I2C_ERROR_COUNT_NUMELEM; i++) {
|
||||
if (error_counts[i] != previous_error_counts[i]) {
|
||||
i2c_error_activity[i] = I2C_ERROR_ACTIVITY_TIMEOUT;
|
||||
} else if (i2c_error_activity[i] > 0) {
|
||||
i2c_error_activity[i]--;
|
||||
}
|
||||
|
||||
previous_error_counts[i] = error_counts[i];
|
||||
}
|
||||
|
||||
#ifdef DIAG_I2C_WDG_STATS
|
||||
I2CStatsData i2cStats;
|
||||
I2CStatsGet(&i2cStats);
|
||||
|
||||
struct pios_i2c_fault_history history;
|
||||
PIOS_I2C_GetDiagnostics(&history, &i2cStats.event_errors);
|
||||
memcpy(&i2cStats.event_errors, &error_counts, sizeof(error_counts));
|
||||
|
||||
for (uint8_t i = 0; (i < I2C_LOG_DEPTH) && (i < I2CSTATS_EVENT_LOG_NUMELEM); i++) {
|
||||
i2cStats.evirq_log[i] = history.evirq[i];
|
||||
@ -500,9 +528,11 @@ static void updateI2Cstats()
|
||||
}
|
||||
i2cStats.last_error_type = history.type;
|
||||
I2CStatsSet(&i2cStats);
|
||||
#endif
|
||||
#endif /* DIAG_I2C_WDG_STATS */
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
}
|
||||
|
||||
#ifdef DIAG_I2C_WDG_STATS
|
||||
static void updateWDGstats()
|
||||
{
|
||||
WatchdogStatusData watchdogStatus;
|
||||
@ -663,6 +693,28 @@ static void updateSystemAlarms()
|
||||
sysStats.ObjectManagerQueueID = objStats.lastQueueErrorID;
|
||||
SystemStatsSet(&sysStats);
|
||||
}
|
||||
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
if (AlarmsGet(SYSTEMALARMS_ALARM_I2C) != SYSTEMALARMS_ALARM_UNINITIALISED) {
|
||||
static const SystemAlarmsAlarmOptions i2c_alarm_by_error[] = {
|
||||
[PIOS_I2C_BAD_EVENT_COUNTER] = SYSTEMALARMS_ALARM_ERROR,
|
||||
[PIOS_I2C_FSM_FAULT_COUNT] = SYSTEMALARMS_ALARM_ERROR,
|
||||
[PIOS_I2C_ERROR_INTERRUPT_COUNTER] = SYSTEMALARMS_ALARM_ERROR,
|
||||
[PIOS_I2C_NACK_COUNTER] = SYSTEMALARMS_ALARM_CRITICAL,
|
||||
[PIOS_I2C_TIMEOUT_COUNTER] = SYSTEMALARMS_ALARM_ERROR,
|
||||
};
|
||||
|
||||
SystemAlarmsAlarmOptions i2c_alarm = SYSTEMALARMS_ALARM_OK;
|
||||
|
||||
for (uint8_t i = 0; i < PIOS_I2C_ERROR_COUNT_NUMELEM; i++) {
|
||||
if ((i2c_error_activity[i] > 0) && (i2c_alarm < i2c_alarm_by_error[i])) {
|
||||
i2c_alarm = i2c_alarm_by_error[i];
|
||||
}
|
||||
}
|
||||
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_I2C, i2c_alarm);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -112,7 +112,7 @@ static void PIOS_COM_UnblockTx(struct pios_com_dev *com_dev, bool *need_yield);
|
||||
* \param[in] id
|
||||
* \return < 0 if initialisation failed
|
||||
*/
|
||||
int32_t PIOS_COM_Init(uint32_t *com_id, const struct pios_com_driver *driver, uint32_t lower_id, uint8_t *rx_buffer, size_t rx_buffer_len, uint8_t *tx_buffer, size_t tx_buffer_len)
|
||||
int32_t PIOS_COM_Init(uint32_t *com_id, const struct pios_com_driver *driver, uint32_t lower_id, uint8_t *rx_buffer, uint16_t rx_buffer_len, uint8_t *tx_buffer, uint16_t tx_buffer_len)
|
||||
{
|
||||
PIOS_Assert(com_id);
|
||||
PIOS_Assert(driver);
|
||||
|
@ -539,6 +539,9 @@ int32_t PIOS_HMC5x83_Test(pios_hmc5x83_dev_t handler)
|
||||
*/
|
||||
bool PIOS_HMC5x83_IRQHandler(pios_hmc5x83_dev_t handler)
|
||||
{
|
||||
if (!handler) { // handler is not set on first call
|
||||
return false;
|
||||
}
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
|
||||
dev->data_ready = true;
|
||||
|
@ -1130,9 +1130,9 @@ static void pios_openlrs_task(void *parameters);
|
||||
static struct pios_openlrs_dev *g_openlrs_dev;
|
||||
|
||||
/**
|
||||
* Initialise an RFM22B device
|
||||
* Initialise an OPENLRS device
|
||||
*
|
||||
* @param[out] rfm22b_id A pointer to store the device ID in.
|
||||
* @param[out] openlrs_id A pointer to store the device ID in.
|
||||
* @param[in] spi_id The SPI bus index.
|
||||
* @param[in] slave_num The SPI bus slave number.
|
||||
* @param[in] cfg The device configuration.
|
||||
@ -1141,7 +1141,7 @@ int32_t PIOS_OpenLRS_Init(uint32_t *openlrs_id, uint32_t spi_id,
|
||||
uint32_t slave_num,
|
||||
const struct pios_openlrs_cfg *cfg)
|
||||
{
|
||||
PIOS_DEBUG_Assert(rfm22b_id);
|
||||
PIOS_DEBUG_Assert(openlrs_id);
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
|
||||
// Allocate the device structure.
|
||||
|
@ -59,7 +59,7 @@ struct pios_com_driver {
|
||||
#define COM_CTRL_LINE_RTS_MASK 0x02
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_COM_Init(uint32_t *com_id, const struct pios_com_driver *driver, uint32_t lower_id, uint8_t *rx_buffer, size_t rx_buffer_len, uint8_t *tx_buffer, size_t tx_buffer_len);
|
||||
extern int32_t PIOS_COM_Init(uint32_t *com_id, const struct pios_com_driver *driver, uint32_t lower_id, uint8_t *rx_buffer, uint16_t rx_buffer_len, uint8_t *tx_buffer, uint16_t tx_buffer_len);
|
||||
extern int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud);
|
||||
extern int32_t PIOS_COM_SetCtrlLine(uint32_t com_id, uint32_t mask, uint32_t state);
|
||||
extern int32_t PIOS_COM_RegisterCtrlLineCallback(uint32_t usart_id, pios_com_callback_ctrl_line ctrl_line_cb, uint32_t context);
|
||||
|
@ -63,6 +63,16 @@ struct pios_i2c_fault_history {
|
||||
uint8_t state[I2C_LOG_DEPTH];
|
||||
};
|
||||
|
||||
enum pios_i2c_error_count {
|
||||
PIOS_I2C_BAD_EVENT_COUNTER,
|
||||
PIOS_I2C_FSM_FAULT_COUNT,
|
||||
PIOS_I2C_ERROR_INTERRUPT_COUNTER,
|
||||
PIOS_I2C_NACK_COUNTER,
|
||||
PIOS_I2C_TIMEOUT_COUNTER,
|
||||
|
||||
PIOS_I2C_ERROR_COUNT_NUMELEM,
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns);
|
||||
extern int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, void *callback);
|
||||
|
@ -118,7 +118,7 @@ static void PIOS_COM_UnblockTx(struct pios_com_dev *com_dev, bool *need_yield);
|
||||
* \param[in] id
|
||||
* \return < 0 if initialisation failed
|
||||
*/
|
||||
int32_t PIOS_COM_Init(uint32_t *com_id, const struct pios_com_driver *driver, uint32_t lower_id, uint8_t *rx_buffer, size_t rx_buffer_len, uint8_t *tx_buffer, size_t tx_buffer_len)
|
||||
int32_t PIOS_COM_Init(uint32_t *com_id, const struct pios_com_driver *driver, uint32_t lower_id, uint8_t *rx_buffer, uint16_t rx_buffer_len, uint8_t *tx_buffer, uint16_t tx_buffer_len)
|
||||
{
|
||||
PIOS_Assert(com_id);
|
||||
PIOS_Assert(driver);
|
||||
|
@ -458,17 +458,17 @@ void PIOS_I2C_GetDiagnostics(struct pios_i2c_fault_history *data, uint8_t *count
|
||||
{
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
memcpy(data, &i2c_adapter_fault_history, sizeof(i2c_adapter_fault_history));
|
||||
counts[0] = i2c_bad_event_counter;
|
||||
counts[1] = i2c_fsm_fault_count;
|
||||
counts[2] = i2c_error_interrupt_counter;
|
||||
counts[3] = i2c_nack_counter;
|
||||
counts[4] = i2c_timeout_counter;
|
||||
counts[PIOS_I2C_BAD_EVENT_COUNTER] = i2c_bad_event_counter;
|
||||
counts[PIOS_I2C_FSM_FAULT_COUNT] = i2c_fsm_fault_count;
|
||||
counts[PIOS_I2C_ERROR_INTERRUPT_COUNTER] = i2c_error_interrupt_counter;
|
||||
counts[PIOS_I2C_NACK_COUNTER] = i2c_nack_counter;
|
||||
counts[PIOS_I2C_TIMEOUT_COUNTER] = i2c_timeout_counter;
|
||||
#else
|
||||
struct pios_i2c_fault_history i2c_adapter_fault_history;
|
||||
i2c_adapter_fault_history.type = PIOS_I2C_ERROR_EVENT;
|
||||
i2c_adapter_fault_history.type = PIOS_I2C_ERROR_EVENT;
|
||||
|
||||
memcpy(data, &i2c_adapter_fault_history, sizeof(i2c_adapter_fault_history));
|
||||
counts[0] = counts[1] = counts[2] = 0;
|
||||
memset(counts, 0, sizeof(*counts) * PIOS_I2C_ERROR_COUNT_NUMELEM);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -857,17 +857,17 @@ void PIOS_I2C_GetDiagnostics(struct pios_i2c_fault_history *data, uint8_t *count
|
||||
{
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
memcpy(data, &i2c_adapter_fault_history, sizeof(i2c_adapter_fault_history));
|
||||
counts[0] = i2c_bad_event_counter;
|
||||
counts[1] = i2c_fsm_fault_count;
|
||||
counts[2] = i2c_error_interrupt_counter;
|
||||
counts[3] = i2c_nack_counter;
|
||||
counts[4] = i2c_timeout_counter;
|
||||
counts[PIOS_I2C_BAD_EVENT_COUNTER] = i2c_bad_event_counter;
|
||||
counts[PIOS_I2C_FSM_FAULT_COUNT] = i2c_fsm_fault_count;
|
||||
counts[PIOS_I2C_ERROR_INTERRUPT_COUNTER] = i2c_error_interrupt_counter;
|
||||
counts[PIOS_I2C_NACK_COUNTER] = i2c_nack_counter;
|
||||
counts[PIOS_I2C_TIMEOUT_COUNTER] = i2c_timeout_counter;
|
||||
#else
|
||||
struct pios_i2c_fault_history i2c_adapter_fault_history;
|
||||
i2c_adapter_fault_history.type = PIOS_I2C_ERROR_EVENT;
|
||||
i2c_adapter_fault_history.type = PIOS_I2C_ERROR_EVENT;
|
||||
|
||||
memcpy(data, &i2c_adapter_fault_history, sizeof(i2c_adapter_fault_history));
|
||||
counts[0] = counts[1] = counts[2] = 0;
|
||||
memset(counts, 0, sizeof(*counts) * PIOS_I2C_ERROR_COUNT_NUMELEM);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -952,17 +952,17 @@ void PIOS_I2C_GetDiagnostics(struct pios_i2c_fault_history *data, uint8_t *count
|
||||
{
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
memcpy(data, &i2c_adapter_fault_history, sizeof(i2c_adapter_fault_history));
|
||||
counts[0] = i2c_bad_event_counter;
|
||||
counts[1] = i2c_fsm_fault_count;
|
||||
counts[2] = i2c_error_interrupt_counter;
|
||||
counts[3] = i2c_nack_counter;
|
||||
counts[4] = i2c_timeout_counter;
|
||||
counts[PIOS_I2C_BAD_EVENT_COUNTER] = i2c_bad_event_counter;
|
||||
counts[PIOS_I2C_FSM_FAULT_COUNT] = i2c_fsm_fault_count;
|
||||
counts[PIOS_I2C_ERROR_INTERRUPT_COUNTER] = i2c_error_interrupt_counter;
|
||||
counts[PIOS_I2C_NACK_COUNTER] = i2c_nack_counter;
|
||||
counts[PIOS_I2C_TIMEOUT_COUNTER] = i2c_timeout_counter;
|
||||
#else
|
||||
struct pios_i2c_fault_history i2c_adapter_fault_history;
|
||||
i2c_adapter_fault_history.type = PIOS_I2C_ERROR_EVENT;
|
||||
i2c_adapter_fault_history.type = PIOS_I2C_ERROR_EVENT;
|
||||
|
||||
memcpy(data, &i2c_adapter_fault_history, sizeof(i2c_adapter_fault_history));
|
||||
counts[0] = counts[1] = counts[2] = 0;
|
||||
memset(counts, 0, sizeof(*counts) * PIOS_I2C_ERROR_COUNT_NUMELEM);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -101,11 +101,11 @@ uintptr_t pios_user_fs_id = 0;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes.
|
||||
* tx size <= 0 make the port rx only
|
||||
* rx size <= 0 make the port tx only
|
||||
* having both tx and rx size <= 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
* tx size = 0 make the port rx only
|
||||
* rx size = 0 make the port tx only
|
||||
* having both tx and rx size = 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
*/
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len,
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, uint16_t rx_buf_len, uint16_t tx_buf_len,
|
||||
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
|
||||
{
|
||||
uint32_t pios_usart_id;
|
||||
|
@ -1143,7 +1143,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
@ -1153,7 +1153,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
|
@ -279,11 +279,11 @@ uintptr_t pios_user_fs_id;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes.
|
||||
* tx size <= 0 make the port rx only
|
||||
* rx size <= 0 make the port tx only
|
||||
* having both tx and rx size <= 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
* tx size = 0 make the port rx only
|
||||
* rx size = 0 make the port tx only
|
||||
* having both tx and rx size = 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
*/
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len,
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, uint16_t rx_buf_len, uint16_t tx_buf_len,
|
||||
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
|
||||
{
|
||||
uint32_t pios_usart_id;
|
||||
|
@ -86,11 +86,11 @@ uint8_t servo_count = 0;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes.
|
||||
* tx size of -1 make the port rx only
|
||||
* rx size of -1 make the port tx only
|
||||
* having both tx and rx size of -1 is not valid and will fail further down in PIOS_COM_Init()
|
||||
* tx size of 0 make the port rx only
|
||||
* rx size of 0 make the port tx only
|
||||
* having both tx and rx size of 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
*/
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len,
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, uint16_t rx_buf_len, uint16_t tx_buf_len,
|
||||
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
|
||||
{
|
||||
uint32_t pios_usart_id;
|
||||
|
@ -407,7 +407,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
@ -417,7 +417,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
|
@ -1524,7 +1524,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
@ -1534,7 +1534,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
|
@ -286,11 +286,11 @@ uintptr_t pios_user_fs_id;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes.
|
||||
* tx size <= 0 make the port rx only
|
||||
* rx size <= 0 make the port tx only
|
||||
* having both tx and rx size <= 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
* tx size = 0 make the port rx only
|
||||
* rx size = 0 make the port tx only
|
||||
* having both tx and rx size = 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
*/
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len,
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, uint16_t rx_buf_len, uint16_t tx_buf_len,
|
||||
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
|
||||
{
|
||||
uint32_t pios_usart_id;
|
||||
|
@ -929,7 +929,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
@ -939,7 +939,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
|
@ -233,11 +233,11 @@ uintptr_t pios_user_fs_id;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes.
|
||||
* tx size <= 0 make the port rx only
|
||||
* rx size <= 0 make the port tx only
|
||||
* having both tx and rx size <= 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
* tx size = 0 make the port rx only
|
||||
* rx size = 0 make the port tx only
|
||||
* having both tx and rx size = 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
*/
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len,
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, uint16_t rx_buf_len, uint16_t tx_buf_len,
|
||||
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
|
||||
{
|
||||
uint32_t pios_usart_id;
|
||||
|
@ -1288,7 +1288,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
@ -1298,7 +1298,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
|
@ -348,9 +348,9 @@ uintptr_t pios_user_fs_id;
|
||||
uint32_t pios_com_vcp_id = 0;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes. tx size <= 0 make the port rx only
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes. tx size = 0 make the port rx only
|
||||
*/
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len,
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, uint16_t rx_buf_len, uint16_t tx_buf_len,
|
||||
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
|
||||
{
|
||||
uint32_t pios_usart_id;
|
||||
|
@ -79,9 +79,9 @@ uintptr_t pios_uavo_settings_fs_id;
|
||||
uintptr_t pios_user_fs_id;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes. tx size <= 0 make the port rx only
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes. tx size = 0 make the port rx only
|
||||
*/
|
||||
static void PIOS_Board_configure_com(const struct pios_udp_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len,
|
||||
static void PIOS_Board_configure_com(const struct pios_udp_cfg *usart_port_cfg, uint16_t rx_buf_len, uint16_t tx_buf_len,
|
||||
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
|
||||
{
|
||||
uint32_t pios_usart_id;
|
||||
@ -180,7 +180,7 @@ void PIOS_Board_Init(void)
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_GPSPORT_GPS:
|
||||
PIOS_Board_configure_com(&pios_udp_gps_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_udp_com_driver, &pios_com_gps_id);
|
||||
PIOS_Board_configure_com(&pios_udp_gps_cfg, PIOS_COM_GPS_RX_BUF_LEN, 0, &pios_udp_com_driver, &pios_com_gps_id);
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RV_GPSPORT_COMAUX:
|
||||
|
@ -1322,7 +1322,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_mag_pressure_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
@ -1332,7 +1332,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_mag_pressure_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
@ -1394,7 +1394,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
@ -1404,7 +1404,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
|
@ -238,11 +238,11 @@ uintptr_t pios_user_fs_id;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes.
|
||||
* tx size <= 0 make the port rx only
|
||||
* rx size <= 0 make the port tx only
|
||||
* having both tx and rx size <= 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
* tx size = 0 make the port rx only
|
||||
* rx size = 0 make the port tx only
|
||||
* having both tx and rx size = 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
*/
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len,
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, uint16_t rx_buf_len, uint16_t tx_buf_len,
|
||||
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
|
||||
{
|
||||
uint32_t pios_usart_id;
|
||||
|
@ -45,7 +45,7 @@ GCSSplashScreen::GCSSplashScreen() :
|
||||
m_painter->setFont(font);
|
||||
|
||||
m_painter->drawText(405, 170, QString(CopyrightSymbol) +
|
||||
QString(" ") + VersionInfo::year() +
|
||||
QString(" 2015-") + VersionInfo::year() +
|
||||
QString(tr(" The %1 Project - All Rights Reserved").arg(ORG_BIG_NAME)));
|
||||
|
||||
m_painter->drawText(405, 182, QString(CopyrightSymbol) +
|
||||
|
@ -97,7 +97,7 @@ public:
|
||||
void updateClearColor()
|
||||
{
|
||||
if (!camera.valid()) {
|
||||
qDebug() << "OSGCamera::updateClearColor - invalid camera";
|
||||
qWarning() << "OSGCamera::updateClearColor - invalid camera";
|
||||
return;
|
||||
}
|
||||
// qDebug() << "OSGCamera::updateClearColor" << clearColor;
|
||||
@ -107,11 +107,11 @@ public:
|
||||
void updateFieldOfView()
|
||||
{
|
||||
if (!camera.valid()) {
|
||||
qDebug() << "OSGCamera::updateFieldOfView - invalid camera";
|
||||
qWarning() << "OSGCamera::updateFieldOfView - invalid camera";
|
||||
return;
|
||||
}
|
||||
|
||||
qDebug() << "OSGCamera::updateFieldOfView" << fieldOfView;
|
||||
// qDebug() << "OSGCamera::updateFieldOfView" << fieldOfView;
|
||||
|
||||
double fovy, ar, zn, zf;
|
||||
camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf);
|
||||
@ -122,18 +122,18 @@ public:
|
||||
void updateAspectRatio()
|
||||
{
|
||||
if (!camera.valid()) {
|
||||
qDebug() << "OSGCamera::updateAspectRatio - invalid camera";
|
||||
qWarning() << "OSGCamera::updateAspectRatio - invalid camera";
|
||||
return;
|
||||
}
|
||||
osg::Viewport *viewport = camera->getViewport();
|
||||
if (!viewport) {
|
||||
qDebug() << "OSGCamera::updateAspectRatio - no viewport" << viewport;
|
||||
qWarning() << "OSGCamera::updateAspectRatio - no viewport" << viewport;
|
||||
return;
|
||||
}
|
||||
|
||||
double aspectRatio = static_cast<double>(viewport->width()) / static_cast<double>(viewport->height());
|
||||
|
||||
qDebug() << "OSGCamera::updateAspectRatio" << aspectRatio;
|
||||
// qDebug() << "OSGCamera::updateAspectRatio" << aspectRatio;
|
||||
|
||||
double fovy, ar, zn, zf;
|
||||
camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf);
|
||||
@ -152,12 +152,12 @@ public:
|
||||
#ifdef USE_OSGEARTH
|
||||
// install log depth buffer if requested
|
||||
if (logDepthBufferEnabled && !logDepthBuffer) {
|
||||
qDebug() << "OSGCamera::updateLogDepthBuffer - installing logarithmic depth buffer";
|
||||
// qDebug() << "OSGCamera::updateLogDepthBuffer - installing logarithmic depth buffer";
|
||||
logDepthBuffer = new osgEarth::Util::LogarithmicDepthBuffer();
|
||||
logDepthBuffer->setUseFragDepth(true);
|
||||
logDepthBuffer->install(camera);
|
||||
} else if (!logDepthBufferEnabled && logDepthBuffer) {
|
||||
qDebug() << "OSGCamera::updateLogDepthBuffer - uninstalling logarithmic depth buffer";
|
||||
// qDebug() << "OSGCamera::updateLogDepthBuffer - uninstalling logarithmic depth buffer";
|
||||
logDepthBuffer->uninstall(camera);
|
||||
delete logDepthBuffer;
|
||||
logDepthBuffer = NULL;
|
||||
@ -168,11 +168,11 @@ public:
|
||||
void setGraphicsContext(osg::GraphicsContext *gc)
|
||||
{
|
||||
if (!camera.valid()) {
|
||||
qDebug() << "OSGCamera::setGraphicsContext - invalid camera";
|
||||
qWarning() << "OSGCamera::setGraphicsContext - invalid camera";
|
||||
return;
|
||||
}
|
||||
|
||||
qDebug() << "OSGCamera::setGraphicsContext" << gc;
|
||||
// qDebug() << "OSGCamera::setGraphicsContext" << gc;
|
||||
|
||||
camera->setGraphicsContext(gc);
|
||||
camera->setViewport(0, 0, gc->getTraits()->width, gc->getTraits()->height);
|
||||
|
@ -90,7 +90,7 @@ public:
|
||||
|
||||
void updateSource()
|
||||
{
|
||||
qDebug() << "OSGFileNode::updateNode" << source;
|
||||
// qDebug() << "OSGFileNode::updateNode" << source;
|
||||
if (!source.isValid()) {
|
||||
self->setNode(NULL);
|
||||
if (!source.isEmpty()) {
|
||||
|
@ -72,7 +72,7 @@ public:
|
||||
|
||||
bool acceptSceneNode(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGGeoTransformNode::acceptSceneNode" << node;
|
||||
// qDebug() << "OSGGeoTransformNode::acceptSceneNode" << node;
|
||||
if (sceneNode == node) {
|
||||
return false;
|
||||
}
|
||||
@ -92,7 +92,7 @@ public:
|
||||
|
||||
void updateSceneNode()
|
||||
{
|
||||
qDebug() << "OSGGeoTransformNode::updateSceneNode" << sceneNode;
|
||||
// qDebug() << "OSGGeoTransformNode::updateSceneNode" << sceneNode;
|
||||
if (sceneNode && sceneNode->node()) {
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneNode->node());
|
||||
if (mapNode) {
|
||||
@ -148,7 +148,7 @@ public:
|
||||
private slots:
|
||||
void onSceneNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGGeoTransformNode::onSceneNodeChanged" << node;
|
||||
// qDebug() << "OSGGeoTransformNode::onSceneNodeChanged" << node;
|
||||
updateSceneNode();
|
||||
updatePosition();
|
||||
}
|
||||
|
@ -88,9 +88,10 @@ public:
|
||||
|
||||
void updateChildren()
|
||||
{
|
||||
qDebug() << "OSGGroup::updateChildren";
|
||||
// qDebug() << "OSGGroup::updateChildren";
|
||||
|
||||
osg::Group *group = static_cast<osg::Group *>(self->node());
|
||||
|
||||
if (!group) {
|
||||
qWarning() << "OSGGroup::updateChildren - null group";
|
||||
return;
|
||||
|
@ -70,7 +70,7 @@ public:
|
||||
|
||||
bool acceptSceneNode(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGSkyNode::acceptSceneNode" << node;
|
||||
// qDebug() << "OSGSkyNode::acceptSceneNode" << node;
|
||||
if (sceneNode == node) {
|
||||
return false;
|
||||
}
|
||||
@ -95,7 +95,7 @@ public:
|
||||
self->setNode(NULL);
|
||||
return;
|
||||
}
|
||||
qDebug() << "OSGSkyNode::updateScene - scene node" << sceneNode->node();
|
||||
// qDebug() << "OSGSkyNode::updateScene - scene node" << sceneNode->node();
|
||||
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneNode->node());
|
||||
if (!mapNode) {
|
||||
qWarning() << "OSGSkyNode::updateScene - scene node does not contain a map node";
|
||||
@ -151,12 +151,12 @@ public:
|
||||
|
||||
void updateViewport()
|
||||
{
|
||||
qDebug() << "OSGSkyNode::updateViewport" << skyNode;
|
||||
// qDebug() << "OSGSkyNode::updateViewport" << skyNode;
|
||||
if (!skyNode.valid()) {
|
||||
qWarning() << "OSGSkyNode::updateViewport - invalid sky node" << skyNode;
|
||||
return;
|
||||
}
|
||||
qDebug() << "OSGSkyNode::updateViewport - attaching to" << viewport->asView();
|
||||
// qDebug() << "OSGSkyNode::updateViewport - attaching to" << viewport->asView();
|
||||
skyNode->attach(viewport->asView());
|
||||
}
|
||||
|
||||
@ -216,7 +216,7 @@ public:
|
||||
private slots:
|
||||
void onSceneNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGSkyNode::onSceneNodeChanged" << node;
|
||||
// qDebug() << "OSGSkyNode::onSceneNodeChanged" << node;
|
||||
updateScene();
|
||||
}
|
||||
};
|
||||
|
@ -271,7 +271,7 @@ private slots:
|
||||
public:
|
||||
bool acceptSceneNode(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGViewport::acceptSceneNode" << node;
|
||||
// qDebug() << "OSGViewport::acceptSceneNode" << node;
|
||||
if (sceneNode == node) {
|
||||
return true;
|
||||
}
|
||||
@ -291,7 +291,7 @@ public:
|
||||
|
||||
bool acceptCameraNode(OSGCamera *node)
|
||||
{
|
||||
qDebug() << "OSGViewport::acceptCameraNode" << node;
|
||||
// qDebug() << "OSGViewport::acceptCameraNode" << node;
|
||||
if (cameraNode == node) {
|
||||
return true;
|
||||
}
|
||||
@ -311,7 +311,7 @@ public:
|
||||
|
||||
bool acceptManipulator(OSGCameraManipulator *m)
|
||||
{
|
||||
qDebug() << "OSGViewport::acceptManipulator" << manipulator;
|
||||
// qDebug() << "OSGViewport::acceptManipulator" << manipulator;
|
||||
if (manipulator == m) {
|
||||
return true;
|
||||
}
|
||||
@ -370,7 +370,7 @@ private:
|
||||
|
||||
void onAboutToBeDestroyed()
|
||||
{
|
||||
qDebug() << "OSGViewport::Hidden::onAboutToBeDestroyed";
|
||||
// qDebug() << "OSGViewport::Hidden::onAboutToBeDestroyed";
|
||||
osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "OSGViewport::Hidden::onAboutToBeDestroyed");
|
||||
// context is not current and don't know how to make it current...
|
||||
}
|
||||
|
@ -69,7 +69,7 @@ public:
|
||||
|
||||
bool acceptSceneNode(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGCameraManipulator::acceptSceneNode" << node;
|
||||
// qDebug() << "OSGCameraManipulator::acceptSceneNode" << node;
|
||||
if (sceneNode == node) {
|
||||
return true;
|
||||
}
|
||||
@ -93,14 +93,14 @@ public:
|
||||
qWarning() << "OSGCameraManipulator::updateSceneNode - no scene node";
|
||||
return;
|
||||
}
|
||||
qDebug() << "OSGCameraManipulator::updateSceneNode" << sceneNode;
|
||||
// qDebug() << "OSGCameraManipulator::updateSceneNode" << sceneNode;
|
||||
manipulator->setNode(sceneNode->node());
|
||||
}
|
||||
|
||||
private slots:
|
||||
void onSceneNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGCameraManipulator::onSceneNodeChanged" << node;
|
||||
// qDebug() << "OSGCameraManipulator::onSceneNodeChanged" << node;
|
||||
updateSceneNode();
|
||||
}
|
||||
};
|
||||
@ -150,7 +150,7 @@ void OSGCameraManipulator::classBegin()
|
||||
|
||||
void OSGCameraManipulator::componentComplete()
|
||||
{
|
||||
qDebug() << "OSGCameraManipulator::componentComplete" << this;
|
||||
// qDebug() << "OSGCameraManipulator::componentComplete" << this;
|
||||
update();
|
||||
clearDirty();
|
||||
}
|
||||
|
@ -65,7 +65,7 @@ public:
|
||||
|
||||
bool acceptTrackNode(OSGNode *node)
|
||||
{
|
||||
qDebug() << "OSGNodeTrackerManipulator::acceptTrackNode" << node;
|
||||
// qDebug() << "OSGNodeTrackerManipulator::acceptTrackNode" << node;
|
||||
if (trackNode == node) {
|
||||
return false;
|
||||
}
|
||||
@ -89,7 +89,7 @@ public:
|
||||
qWarning() << "OSGNodeTrackerManipulator::updateTrackNode - no track node";
|
||||
return;
|
||||
}
|
||||
qDebug() << "OSGNodeTrackerManipulator::updateTrackNode" << trackNode->node();
|
||||
// qDebug() << "OSGNodeTrackerManipulator::updateTrackNode" << trackNode->node();
|
||||
manipulator->setTrackNode(trackNode->node());
|
||||
}
|
||||
|
||||
@ -117,7 +117,7 @@ public:
|
||||
private slots:
|
||||
void onTrackNodeChanged(osg::Node *node)
|
||||
{
|
||||
qDebug() << "OSGNodeTrackerManipulator::onTrackNodeChanged" << node;
|
||||
// qDebug() << "OSGNodeTrackerManipulator::onTrackNodeChanged" << node;
|
||||
qWarning() << "OSGNodeTrackerManipulator::onTrackNodeChanged - needs to be implemented";
|
||||
}
|
||||
};
|
||||
|
@ -89,7 +89,7 @@ void AntennaTrackGadget::loadConfiguration(IUAVGadgetConfiguration *config)
|
||||
}
|
||||
}
|
||||
m_widget->dataStreamGroupBox->setHidden(false);
|
||||
qDebug() << "Using Telemetry parser";
|
||||
|
||||
parser = new TelemetryParser();
|
||||
|
||||
connect(parser, SIGNAL(position(double, double, double)), m_widget, SLOT(setPosition(double, double, double)));
|
||||
|
@ -218,7 +218,7 @@
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="airframeHelp">
|
||||
<widget class="QPushButton" name="helpButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -250,26 +250,35 @@
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:help</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveAircraftToRAM">
|
||||
<widget class="QPushButton" name="applyButton">
|
||||
<property name="toolTip">
|
||||
<string>Send to board, but don't save permanently (flash or SD).</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveAircraftToSD">
|
||||
<widget class="QPushButton" name="saveButton">
|
||||
<property name="toolTip">
|
||||
<string>Applies and Saves all settings to flash or SD depending on board.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
@ -287,9 +296,9 @@
|
||||
<tabstops>
|
||||
<tabstop>nameEdit</tabstop>
|
||||
<tabstop>vehicleSetupWizardButton</tabstop>
|
||||
<tabstop>airframeHelp</tabstop>
|
||||
<tabstop>saveAircraftToRAM</tabstop>
|
||||
<tabstop>saveAircraftToSD</tabstop>
|
||||
<tabstop>helpButton</tabstop>
|
||||
<tabstop>applyButton</tabstop>
|
||||
<tabstop>saveButton</tabstop>
|
||||
</tabstops>
|
||||
<resources>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
|
@ -23,7 +23,16 @@
|
||||
<property name="spacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -36,11 +45,38 @@
|
||||
<string>Pre-Autotune</string>
|
||||
</attribute>
|
||||
<layout class="QGridLayout" name="gridLayout_5">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item row="3" column="0" colspan="3">
|
||||
<widget class="QTextEdit" name="textEdit">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
@ -51,9 +87,9 @@
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:20pt; font-weight:600; color:#ff0000;">WARNING:</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Lucida Grande'; font-size:13pt;"></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Lucida Grande'; font-size:13pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;"><br /></span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;"><br /></span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">This is an experimental plugin for the GCS that is going to make your aircraft shake, etc, so test with lots of space and be </span><span style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:600;">very very wary</span><span style=" font-family:'Lucida Grande'; font-size:13pt;"> for it creating bad tuning values. Basically there is no reason to think this will work at all.<br /><br />To use autotuning, here are the steps:<br /></span></p>
|
||||
@ -99,7 +135,16 @@ p, li { white-space: pre-wrap; }
|
||||
<string>Autotune Setup</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -182,8 +227,8 @@ p, li { white-space: pre-wrap; }
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>709</width>
|
||||
<height>605</height>
|
||||
<width>526</width>
|
||||
<height>510</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
@ -199,7 +244,16 @@ p, li { white-space: pre-wrap; }
|
||||
<property name="spacing">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -231,7 +285,7 @@ p, li { white-space: pre-wrap; }
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:RelayTuningSettings</string>
|
||||
<string>fieldname:RateGain</string>
|
||||
<string>scale:0.01</string>
|
||||
@ -249,7 +303,7 @@ p, li { white-space: pre-wrap; }
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:RelayTuningSettings</string>
|
||||
<string>fieldname:AttitudeGain</string>
|
||||
<string>scale:0.01</string>
|
||||
@ -283,7 +337,7 @@ p, li { white-space: pre-wrap; }
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:RelayTuning</string>
|
||||
<string>fieldname:Period</string>
|
||||
<string>element:Roll</string>
|
||||
@ -300,7 +354,7 @@ p, li { white-space: pre-wrap; }
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:RelayTuning</string>
|
||||
<string>fieldname:Gain</string>
|
||||
<string>element:Roll</string>
|
||||
@ -338,7 +392,7 @@ p, li { white-space: pre-wrap; }
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:RelayTuning</string>
|
||||
<string>fieldname:Period</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -355,7 +409,7 @@ p, li { white-space: pre-wrap; }
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:RelayTuning</string>
|
||||
<string>fieldname:Gain</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -507,7 +561,7 @@ p, li { white-space: pre-wrap; }
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:RelayTuningSettings</string>
|
||||
<string>fieldname:Amplitude</string>
|
||||
<string>scale:0.01</string>
|
||||
@ -601,7 +655,45 @@ will alter settings for the next autotuning flight</string>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="stabilizationReloadBoardData_6">
|
||||
<widget class="QPushButton" name="helpButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../coreplugin/core.qrc">
|
||||
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:help</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="reloadButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -619,7 +711,7 @@ Useful if you have accidentally changed some settings.</string>
|
||||
<string>Reload Board Data</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>button:reload</string>
|
||||
<string>buttongroup:10</string>
|
||||
</stringlist>
|
||||
@ -627,7 +719,7 @@ Useful if you have accidentally changed some settings.</string>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveStabilizationToRAM_6">
|
||||
<widget class="QPushButton" name="applyButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -644,14 +736,14 @@ Useful if you have accidentally changed some settings.</string>
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>button:apply</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveStabilizationToSD_6">
|
||||
<widget class="QPushButton" name="saveButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -668,7 +760,7 @@ Useful if you have accidentally changed some settings.</string>
|
||||
<string>Save</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>button:save</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
@ -678,6 +770,8 @@ Useful if you have accidentally changed some settings.</string>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
<resources>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
||||
|
@ -72,7 +72,7 @@
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>-103</y>
|
||||
<y>0</y>
|
||||
<width>748</width>
|
||||
<height>811</height>
|
||||
</rect>
|
||||
@ -143,7 +143,7 @@ have to define channel output range using Output configuration tab.</string>
|
||||
<number>20</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:OutputRange</string>
|
||||
<string>element:Yaw</string>
|
||||
@ -172,7 +172,7 @@ have to define channel output range using Output configuration tab.</string>
|
||||
<number>20</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:OutputRange</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -201,7 +201,7 @@ have to define channel output range using Output configuration tab.</string>
|
||||
<number>20</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:OutputRange</string>
|
||||
<string>element:Roll</string>
|
||||
@ -429,7 +429,7 @@ font:bold;</string>
|
||||
Don't forget to map this channel using Input configuration tab.</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:Input</string>
|
||||
<string>element:Yaw</string>
|
||||
@ -454,7 +454,7 @@ Don't forget to map this channel using Input configuration tab.</string>
|
||||
Don't forget to map this channel using Input configuration tab.</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:Input</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -479,7 +479,7 @@ Don't forget to map this channel using Input configuration tab.</string>
|
||||
Don't forget to map this channel using Input configuration tab.</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:Input</string>
|
||||
<string>element:Roll</string>
|
||||
@ -512,7 +512,7 @@ Attitude: camera tracks level for the axis. Input controls the deflection.
|
||||
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:StabilizationMode</string>
|
||||
<string>element:Yaw</string>
|
||||
@ -541,7 +541,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
|
||||
<number>20</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:InputRange</string>
|
||||
<string>element:Yaw</string>
|
||||
@ -567,7 +567,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:InputRate</string>
|
||||
<string>element:Yaw</string>
|
||||
@ -590,7 +590,7 @@ Attitude: camera tracks level for the axis. Input controls the deflection.
|
||||
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:StabilizationMode</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -619,7 +619,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
|
||||
<number>20</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:InputRange</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -645,7 +645,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:InputRate</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -668,7 +668,7 @@ Attitude: camera tracks level for the axis. Input controls the deflection.
|
||||
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:StabilizationMode</string>
|
||||
<string>element:Roll</string>
|
||||
@ -697,7 +697,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
|
||||
<number>20</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:InputRange</string>
|
||||
<string>element:Roll</string>
|
||||
@ -723,7 +723,7 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:InputRate</string>
|
||||
<string>element:Roll</string>
|
||||
@ -794,7 +794,7 @@ value.</string>
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:MaxAxisLockRate</string>
|
||||
<string>haslimits:no</string>
|
||||
@ -902,7 +902,7 @@ Smoothes estimated airframe attitude used by camera stabilization.</string>
|
||||
<number>250</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:ResponseTime</string>
|
||||
<string>element:Roll</string>
|
||||
@ -924,7 +924,7 @@ Smoothes estimated airframe attitude used by camera stabilization.</string>
|
||||
<number>250</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:ResponseTime</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -946,7 +946,7 @@ Smoothes estimated airframe attitude used by camera stabilization.</string>
|
||||
<number>250</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:ResponseTime</string>
|
||||
<string>element:Yaw</string>
|
||||
@ -976,7 +976,7 @@ Too high value may burn your servo!</string>
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:FeedForward</string>
|
||||
<string>element:Roll</string>
|
||||
@ -1001,7 +1001,7 @@ Too high value may burn your servo!</string>
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:FeedForward</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -1026,7 +1026,7 @@ Too high value may burn your servo!</string>
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:FeedForward</string>
|
||||
<string>element:Yaw</string>
|
||||
@ -1058,7 +1058,7 @@ Range: 0-50ms, default is 5.</string>
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:AccelTime</string>
|
||||
<string>element:Roll</string>
|
||||
@ -1081,7 +1081,7 @@ Range: 0-50ms, default is 5.</string>
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:AccelTime</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -1104,7 +1104,7 @@ Range: 0-50ms, default is 5.</string>
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:AccelTime</string>
|
||||
<string>element:Yaw</string>
|
||||
@ -1134,7 +1134,7 @@ Range: 0-50ms, default is 5.</string>
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:DecelTime</string>
|
||||
<string>element:Roll</string>
|
||||
@ -1157,7 +1157,7 @@ Range: 0-50ms, default is 5.</string>
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:DecelTime</string>
|
||||
<string>element:Pitch</string>
|
||||
@ -1180,7 +1180,7 @@ Range: 0-50ms, default is 5.</string>
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:DecelTime</string>
|
||||
<string>element:Yaw</string>
|
||||
@ -1208,7 +1208,7 @@ Used to limit feed forward acceleration at extreme angles.
|
||||
Generic type provides no limit.</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:GimbalType</string>
|
||||
<string>buttongroup:1</string>
|
||||
@ -1244,7 +1244,7 @@ The same value is used for all axes.</string>
|
||||
<number>500</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:MaxAccel</string>
|
||||
<string>buttongroup:1</string>
|
||||
@ -1321,7 +1321,7 @@ The same value is used for all axes.</string>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QPushButton" name="camerastabilizationHelp">
|
||||
<widget class="QPushButton" name="helpButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -1362,14 +1362,14 @@ The same value is used for all axes.</string>
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>button:help</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QPushButton" name="camerastabilizationResetToDefaults">
|
||||
<widget class="QPushButton" name="defaultButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -1392,7 +1392,7 @@ Apply or Save button afterwards.</string>
|
||||
<string>Reset To Defaults</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>button:default</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
@ -1400,7 +1400,7 @@ Apply or Save button afterwards.</string>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QPushButton" name="pushButton">
|
||||
<widget class="QPushButton" name="reloadButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -1425,7 +1425,7 @@ Apply or Save button afterwards.</string>
|
||||
<string>Reload Board Data</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>button:reload</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
@ -1433,7 +1433,7 @@ Apply or Save button afterwards.</string>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QPushButton" name="camerastabilizationSaveRAM">
|
||||
<widget class="QPushButton" name="applyButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -1453,14 +1453,14 @@ Apply or Save button afterwards.</string>
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>button:apply</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="5">
|
||||
<widget class="QPushButton" name="camerastabilizationSaveSD">
|
||||
<widget class="QPushButton" name="saveButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -1483,7 +1483,7 @@ Apply or Save button afterwards.</string>
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<stringlist notr="true">
|
||||
<string>button:save</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
@ -1528,10 +1528,10 @@ Apply or Save button afterwards.</string>
|
||||
<tabstop>yawDecelTime</tabstop>
|
||||
<tabstop>gimbalType</tabstop>
|
||||
<tabstop>maxAccel</tabstop>
|
||||
<tabstop>camerastabilizationResetToDefaults</tabstop>
|
||||
<tabstop>pushButton</tabstop>
|
||||
<tabstop>camerastabilizationSaveRAM</tabstop>
|
||||
<tabstop>camerastabilizationSaveSD</tabstop>
|
||||
<tabstop>defaultButton</tabstop>
|
||||
<tabstop>reloadButton</tabstop>
|
||||
<tabstop>applyButton</tabstop>
|
||||
<tabstop>saveButton</tabstop>
|
||||
</tabstops>
|
||||
<resources>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
|
@ -456,7 +456,7 @@
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="cchwHelp">
|
||||
<widget class="QPushButton" name="helpButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -494,10 +494,13 @@
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:help</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToRAM">
|
||||
<widget class="QPushButton" name="applyButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -596,10 +599,13 @@ Beware of not locking yourself out!</string>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToSD">
|
||||
<widget class="QPushButton" name="saveButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -625,6 +631,9 @@ Beware of not locking yourself out!</string>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
|
@ -117,7 +117,7 @@
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>758</width>
|
||||
<height>486</height>
|
||||
<height>480</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
@ -550,7 +550,7 @@ A setting of 0.00 disables the filter.</string>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="ccAttitudeHelp">
|
||||
<widget class="QPushButton" name="helpButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -582,6 +582,9 @@ A setting of 0.00 disables the filter.</string>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:help</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
@ -595,6 +598,9 @@ A setting of 0.00 disables the filter.</string>
|
||||
<property name="text">
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
@ -611,6 +617,9 @@ A setting of 0.00 disables the filter.</string>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
|
@ -1,3653 +0,0 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>ccpmWidget</class>
|
||||
<widget class="QWidget" name="ccpmWidget">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>850</width>
|
||||
<height>572</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>300</width>
|
||||
<height>300</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_17">
|
||||
<item row="0" column="0">
|
||||
<layout class="QGridLayout" name="gridLayout_13">
|
||||
<item row="0" column="0">
|
||||
<layout class="QFormLayout" name="formLayout_6">
|
||||
<property name="fieldGrowthPolicy">
|
||||
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Swashplate config:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QComboBox" name="ccpmType">
|
||||
<property name="toolTip">
|
||||
<string>Select aircraft type here</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QTabWidget" name="TabObject">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>300</width>
|
||||
<height>300</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">#SwashplateBox,#SwashplateBox_2,#SwashplateBox_3,#SwashplateBox_4,#ccpmSwashImageBox,#SwashLvlInstructionsBox,#SwashLvlccpmSwashImageBox,#SwashLvlccpmSliderBox,#SwashLvlStatusBox,#ThrottleCurveBox,#PitchCurveBox{
|
||||
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255));
|
||||
border: 1px outset #999;
|
||||
border-radius: 3;
|
||||
font:bold;
|
||||
}
|
||||
|
||||
QGroupBox::title {
|
||||
subcontrol-origin: margin;
|
||||
subcontrol-position: top center; /* position at the top center */
|
||||
padding: 0 3px;
|
||||
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1,
|
||||
stop: 0 #FFOECE, stop: 1 #FFFFFF);
|
||||
top: 5px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="currentIndex">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<widget class="QWidget" name="BasicTab">
|
||||
<attribute name="title">
|
||||
<string>Basic settings</string>
|
||||
</attribute>
|
||||
<layout class="QGridLayout" name="gridLayout_6">
|
||||
<property name="leftMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<layout class="QVBoxLayout" name="ccpmSettingsBox" stretch="0,1,1,0,0">
|
||||
<item>
|
||||
<widget class="QGroupBox" name="SwashplateBox_2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Maximum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>190</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Motor outputs</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_18">
|
||||
<property name="horizontalSpacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="verticalSpacing">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="ccpmTailChannel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="ccpmEngineChannel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="ccpmTailLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Tail Rotor</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="ccpmEngineLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Engine</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<spacer name="verticalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="SwashplateBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Maximum" vsizetype="Maximum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>190</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Swashplate outputs</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_19">
|
||||
<property name="horizontalSpacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="verticalSpacing">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="ccpmServoWLabel">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Servo W</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="ccpmServoWChannel">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="ccpmServoXChannel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<widget class="QComboBox" name="ccpmServoYChannel">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="ccpmServoXLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Servo X</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QComboBox" name="ccpmSingleServo">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Front</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Right</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Rear</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Left</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="ccpmServoZLabel_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>1st Servo</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QComboBox" name="ccpmServoZChannel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="ccpmServoZLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Servo Z</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="ccpmServoYLabel">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Servo Y</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<spacer name="verticalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="SwashplateBox_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Maximum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>190</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Swashplate Servo Angles</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_20">
|
||||
<property name="horizontalSpacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="verticalSpacing">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="1" column="1">
|
||||
<widget class="QDoubleSpinBox" name="ccpmAngleW">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>360.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>15.000000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="ccpmServoWLabel_2">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Angle W</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="ccpmServoXLabel_2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Angle X</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="ccpmServoYLabel_2">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Angle Y</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="ccpmServoZLabel_2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Angle Z</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="label_10">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>80</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Correction Angle</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QDoubleSpinBox" name="ccpmAngleX">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>360.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>15.000000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QDoubleSpinBox" name="ccpmCorrectionAngle">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>360.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>15.000000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QDoubleSpinBox" name="ccpmAngleZ">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>360.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>15.000000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QDoubleSpinBox" name="ccpmAngleY">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>360.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>15.000000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<spacer name="verticalSpacer_7">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="SwashplateBox_4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Maximum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>190</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>CCPM Options</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_21">
|
||||
<property name="horizontalSpacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="verticalSpacing">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="2" column="0">
|
||||
<widget class="QCheckBox" name="ccpmCollectivePassthrough">
|
||||
<property name="text">
|
||||
<string>Collective Pass through</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QCheckBox" name="ccpmLinkRoll">
|
||||
<property name="text">
|
||||
<string>Link Roll/Pitch</string>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QCheckBox" name="ccpmLinkCyclic">
|
||||
<property name="text">
|
||||
<string>Link Cyclic/Collective</string>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<spacer name="verticalSpacer_8">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="0" column="10">
|
||||
<layout class="QVBoxLayout" name="ccpmSwashImageBox_2">
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="ccpmSwashImageBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>600</width>
|
||||
<height>600</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="sizeIncrement">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="baseSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<italic>false</italic>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Swashplate Layout</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignHCenter|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_10">
|
||||
<property name="horizontalSpacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="1" column="0">
|
||||
<widget class="QSplitter" name="splitter_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<widget class="QGraphicsView" name="SwashplateImage">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>1000</width>
|
||||
<height>1000</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="sizeIncrement">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="baseSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::Box</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Plain</enum>
|
||||
</property>
|
||||
<property name="lineWidth">
|
||||
<number>1</number>
|
||||
</property>
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="backgroundBrush">
|
||||
<brush brushstyle="DiagCrossPattern">
|
||||
<color alpha="50">
|
||||
<red>112</red>
|
||||
<green>184</green>
|
||||
<blue>138</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</property>
|
||||
<property name="foregroundBrush">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>127</red>
|
||||
<green>127</green>
|
||||
<blue>127</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</property>
|
||||
<property name="sceneRect">
|
||||
<rectf>
|
||||
<x>0.000000000000000</x>
|
||||
<y>0.000000000000000</y>
|
||||
<width>400.000000000000000</width>
|
||||
<height>400.000000000000000</height>
|
||||
</rectf>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<property name="resizeAnchor">
|
||||
<enum>QGraphicsView::AnchorViewCenter</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<spacer name="verticalSpacer_9">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_10">
|
||||
<property name="sizeConstraint">
|
||||
<enum>QLayout::SetNoConstraint</enum>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="ccpmRevoMixingBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>600</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QGroupBox::title {
|
||||
background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>REVO</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_10">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>7</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_14">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>7</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>100%</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="ccpmRevoSlider">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_13">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>7</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>0%</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSpinBox" name="ccpmREVOspinBox"/>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="ccpmPitchMixingBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>60</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>600</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QGroupBox::title {
|
||||
background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>CCPM</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_4">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_11">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>7</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_15">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>7</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Collective</string>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="ccpmCollectiveSlider">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_16">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>7</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Cyclic</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSpinBox" name="ccpmCollectivespinBox">
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="ccpmCollectiveScalingBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>600</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QGroupBox::title {
|
||||
background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Collective</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_12">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_12">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>7</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_11">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_15">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="ccpmCollectiveScale">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_16">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSpinBox" name="ccpmCollectiveScaleBox">
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="ccpmCyclicScalingBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>600</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QGroupBox::title {
|
||||
background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Cyclic</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_7">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_13">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>7</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_7">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_9">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="ccpmCyclicScale">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_10">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSpinBox" name="ccpmCyclicScaleBox">
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="ccpmPitchScalingBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>600</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QGroupBox::title {
|
||||
background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_13">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_14">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>7</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_12">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_17">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="ccpmPitchScale">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_18">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSpinBox" name="ccpmPitchScaleBox">
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="ccpmRollScalingBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>600</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QGroupBox::title {
|
||||
background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_10">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_15">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>7</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_8">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_11">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="ccpmRollScale">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_12">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSpinBox" name="ccpmRollScaleBox">
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<widget class="QWidget" name="SwashPlateLevel">
|
||||
<attribute name="title">
|
||||
<string>Swashplate Levelling</string>
|
||||
</attribute>
|
||||
<layout class="QGridLayout" name="gridLayout_8">
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_8">
|
||||
<property name="leftMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="SwashLvlInstructionsBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Maximum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>228</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Commands</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_16">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_9">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QPushButton" name="SwashLvlStartButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Start</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="SwashLvlNextButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>85</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Next</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QTextEdit" name="SwashLvlStepInstruction">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>150</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>220</width>
|
||||
<height>450</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<item row="0" column="0">
|
||||
<widget class="QPushButton" name="SwashLvlCancelButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>170</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>170</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Cancel</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QPushButton" name="SwashLvlFinishButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>170</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>170</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Finish</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="SwashLvlStatusBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Maximum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Status</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_22">
|
||||
<property name="horizontalSpacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="verticalSpacing">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="1" column="0">
|
||||
<widget class="QListWidget" name="SwashLvlStepList">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>220</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>190</width>
|
||||
<height>125</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="editTriggers">
|
||||
<set>QAbstractItemView::NoEditTriggers</set>
|
||||
</property>
|
||||
<property name="alternatingRowColors">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="selectionMode">
|
||||
<enum>QAbstractItemView::NoSelection</enum>
|
||||
</property>
|
||||
<property name="selectionBehavior">
|
||||
<enum>QAbstractItemView::SelectRows</enum>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Neutral</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset>
|
||||
<normaloff>:/configgadget/images/none.png</normaloff>
|
||||
<normalon>:/configgadget/images/ok.png</normalon>:/configgadget/images/none.png</iconset>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Max</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset>
|
||||
<normaloff>:/configgadget/images/none.png</normaloff>
|
||||
<normalon>:/configgadget/images/ok.png</normalon>:/configgadget/images/none.png</iconset>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Min</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset>
|
||||
<normaloff>:/configgadget/images/none.png</normaloff>
|
||||
<normalon>:/configgadget/images/ok.png</normalon>:/configgadget/images/none.png</iconset>
|
||||
</property>
|
||||
<property name="flags">
|
||||
<set>ItemIsSelectable|ItemIsEnabled</set>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Verify</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset>
|
||||
<normaloff>:/configgadget/images/none.png</normaloff>
|
||||
<normalon>:/configgadget/images/ok.png</normalon>:/configgadget/images/none.png</iconset>
|
||||
</property>
|
||||
<property name="flags">
|
||||
<set>ItemIsEnabled</set>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<spacer name="verticalSpacer_19">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::MinimumExpanding</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QGroupBox" name="SwashLvlccpmSliderBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>600</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Position</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_18">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_17">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Max</string>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_4">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_7">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="SwashLvlPositionSlider">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_8">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_18">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Min</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSpinBox" name="SwashLvlPositionSpinBox">
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QGroupBox" name="SwashLvlccpmSwashImageBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>600</width>
|
||||
<height>600</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="sizeIncrement">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="baseSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Swashplate Adjustment</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignHCenter|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_11">
|
||||
<property name="horizontalSpacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="1" column="0">
|
||||
<widget class="QSplitter" name="splitter_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<widget class="QGraphicsView" name="SwashLvlSwashplateImage">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>1000</width>
|
||||
<height>1000</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="sizeIncrement">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="baseSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::Box</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Plain</enum>
|
||||
</property>
|
||||
<property name="lineWidth">
|
||||
<number>1</number>
|
||||
</property>
|
||||
<property name="midLineWidth">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="backgroundBrush">
|
||||
<brush brushstyle="DiagCrossPattern">
|
||||
<color alpha="25">
|
||||
<red>126</red>
|
||||
<green>176</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</property>
|
||||
<property name="foregroundBrush">
|
||||
<brush brushstyle="NoBrush">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</property>
|
||||
<property name="sceneRect">
|
||||
<rectf>
|
||||
<x>0.000000000000000</x>
|
||||
<y>0.000000000000000</y>
|
||||
<width>400.000000000000000</width>
|
||||
<height>400.000000000000000</height>
|
||||
</rectf>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<property name="resizeAnchor">
|
||||
<enum>QGraphicsView::AnchorViewCenter</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<spacer name="verticalSpacer_17">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<widget class="QWidget" name="CurveTab">
|
||||
<attribute name="title">
|
||||
<string>Curve settings</string>
|
||||
</attribute>
|
||||
<layout class="QGridLayout" name="gridLayout_7">
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_6"/>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_3">
|
||||
<property name="spacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="ThrottleCurveBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="sizeIncrement">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="baseSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<property name="margin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="MixerCurve" name="ThrottleCurve" native="true">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>50</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>1000</width>
|
||||
<height>1000</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="sizeIncrement">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="baseSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="PitchCurveBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="sizeIncrement">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="baseSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string/>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_5">
|
||||
<property name="margin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="MixerCurve" name="PitchCurve" native="true">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>50</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>1000</width>
|
||||
<height>1000</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="sizeIncrement">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="baseSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<spacer name="verticalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Preferred</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<widget class="QWidget" name="AdvancedTab">
|
||||
<attribute name="title">
|
||||
<string>Advanced settings</string>
|
||||
</attribute>
|
||||
<layout class="QGridLayout" name="gridLayout_4">
|
||||
<property name="margin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="QTableWidget" name="ccpmAdvancedSettingsTable">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>1000</width>
|
||||
<height>300</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="autoScroll">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="alternatingRowColors">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="selectionMode">
|
||||
<enum>QAbstractItemView::NoSelection</enum>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="cornerButtonEnabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<attribute name="horizontalHeaderDefaultSectionSize">
|
||||
<number>75</number>
|
||||
</attribute>
|
||||
<attribute name="horizontalHeaderMinimumSectionSize">
|
||||
<number>20</number>
|
||||
</attribute>
|
||||
<row>
|
||||
<property name="text">
|
||||
<string>Engine</string>
|
||||
</property>
|
||||
</row>
|
||||
<row>
|
||||
<property name="text">
|
||||
<string>Tail Rotor</string>
|
||||
</property>
|
||||
</row>
|
||||
<row>
|
||||
<property name="text">
|
||||
<string>Servo W</string>
|
||||
</property>
|
||||
</row>
|
||||
<row>
|
||||
<property name="text">
|
||||
<string>Servo X</string>
|
||||
</property>
|
||||
</row>
|
||||
<row>
|
||||
<property name="text">
|
||||
<string>Servo Y</string>
|
||||
</property>
|
||||
</row>
|
||||
<row>
|
||||
<property name="text">
|
||||
<string>Servo Z</string>
|
||||
</property>
|
||||
</row>
|
||||
<column>
|
||||
<property name="text">
|
||||
<string>Channel</string>
|
||||
</property>
|
||||
</column>
|
||||
<column>
|
||||
<property name="text">
|
||||
<string>Curve 1</string>
|
||||
</property>
|
||||
</column>
|
||||
<column>
|
||||
<property name="text">
|
||||
<string>Curve 2</string>
|
||||
</property>
|
||||
</column>
|
||||
<column>
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
</column>
|
||||
<column>
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
</column>
|
||||
<column>
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
</column>
|
||||
<item row="0" column="0">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="0" column="5">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="3" column="5">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="4" column="2">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="4" column="3">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="4" column="4">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="4" column="5">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="5" column="2">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="5" column="3">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="5" column="4">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
<item row="5" column="5">
|
||||
<property name="text">
|
||||
<string>-</string>
|
||||
</property>
|
||||
<property name="textAlignment">
|
||||
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::MinimumExpanding</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<customwidgets>
|
||||
<customwidget>
|
||||
<class>MixerCurve</class>
|
||||
<extends>QWidget</extends>
|
||||
<header location="global">mixercurve.h</header>
|
||||
<container>1</container>
|
||||
</customwidget>
|
||||
</customwidgets>
|
||||
<tabstops>
|
||||
<tabstop>ccpmType</tabstop>
|
||||
<tabstop>TabObject</tabstop>
|
||||
<tabstop>ccpmEngineChannel</tabstop>
|
||||
<tabstop>ccpmTailChannel</tabstop>
|
||||
<tabstop>ccpmServoWChannel</tabstop>
|
||||
<tabstop>ccpmServoXChannel</tabstop>
|
||||
<tabstop>ccpmServoYChannel</tabstop>
|
||||
<tabstop>ccpmServoZChannel</tabstop>
|
||||
<tabstop>ccpmSingleServo</tabstop>
|
||||
<tabstop>ccpmAngleW</tabstop>
|
||||
<tabstop>ccpmAngleX</tabstop>
|
||||
<tabstop>ccpmAngleY</tabstop>
|
||||
<tabstop>ccpmAngleZ</tabstop>
|
||||
<tabstop>ccpmCorrectionAngle</tabstop>
|
||||
<tabstop>ccpmRevoSlider</tabstop>
|
||||
<tabstop>ccpmREVOspinBox</tabstop>
|
||||
<tabstop>ccpmCollectiveSlider</tabstop>
|
||||
<tabstop>ccpmCollectivespinBox</tabstop>
|
||||
<tabstop>SwashplateImage</tabstop>
|
||||
<tabstop>SwashLvlStartButton</tabstop>
|
||||
<tabstop>SwashLvlNextButton</tabstop>
|
||||
<tabstop>SwashLvlStepInstruction</tabstop>
|
||||
<tabstop>SwashLvlCancelButton</tabstop>
|
||||
<tabstop>SwashLvlFinishButton</tabstop>
|
||||
<tabstop>SwashLvlStepList</tabstop>
|
||||
<tabstop>SwashLvlPositionSlider</tabstop>
|
||||
<tabstop>SwashLvlPositionSpinBox</tabstop>
|
||||
<tabstop>SwashLvlSwashplateImage</tabstop>
|
||||
<tabstop>ccpmAdvancedSettingsTable</tabstop>
|
||||
</tabstops>
|
||||
<resources/>
|
||||
<connections>
|
||||
<connection>
|
||||
<sender>ccpmCollectiveSlider</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmCollectivespinBox</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>261</x>
|
||||
<y>496</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>269</x>
|
||||
<y>546</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmCollectivespinBox</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmCollectiveSlider</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>269</x>
|
||||
<y>546</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>261</x>
|
||||
<y>511</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmREVOspinBox</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmRevoSlider</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>216</x>
|
||||
<y>546</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>208</x>
|
||||
<y>511</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmRevoSlider</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmREVOspinBox</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>208</x>
|
||||
<y>412</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>216</x>
|
||||
<y>546</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>SwashLvlPositionSlider</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>SwashLvlPositionSpinBox</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>276</x>
|
||||
<y>486</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>270</x>
|
||||
<y>537</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>SwashLvlPositionSpinBox</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>SwashLvlPositionSlider</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>301</x>
|
||||
<y>546</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>277</x>
|
||||
<y>401</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmCollectiveScaleBox</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmCollectiveScale</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>296</x>
|
||||
<y>534</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>306</x>
|
||||
<y>480</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmCollectiveScale</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmCollectiveScaleBox</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>308</x>
|
||||
<y>328</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>292</x>
|
||||
<y>534</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmCyclicScale</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmCyclicScaleBox</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>358</x>
|
||||
<y>306</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>355</x>
|
||||
<y>538</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmCyclicScaleBox</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmCyclicScale</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>341</x>
|
||||
<y>538</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>351</x>
|
||||
<y>376</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmPitchScale</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmPitchScaleBox</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>417</x>
|
||||
<y>306</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>406</x>
|
||||
<y>531</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmPitchScaleBox</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmPitchScale</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>394</x>
|
||||
<y>531</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>408</x>
|
||||
<y>302</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmRollScaleBox</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmRollScale</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>455</x>
|
||||
<y>529</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>458</x>
|
||||
<y>466</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>ccpmRollScale</sender>
|
||||
<signal>valueChanged(int)</signal>
|
||||
<receiver>ccpmRollScaleBox</receiver>
|
||||
<slot>setValue(int)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>461</x>
|
||||
<y>388</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>474</x>
|
||||
<y>533</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
</connections>
|
||||
</ui>
|
@ -29,6 +29,9 @@
|
||||
|
||||
#include "ui_airframe_ccpm.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <uavobjectutilmanager.h>
|
||||
|
||||
#include "mixersettings.h"
|
||||
#include "systemsettings.h"
|
||||
#include "actuatorcommand.h"
|
||||
@ -124,8 +127,9 @@ QStringList ConfigCcpmWidget::getChannelDescriptions()
|
||||
}
|
||||
|
||||
ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) :
|
||||
VehicleConfig(parent), m_aircraft(new Ui_CcpmConfigWidget())
|
||||
VehicleConfig(parent)
|
||||
{
|
||||
m_aircraft = new Ui_CcpmConfigWidget();
|
||||
m_aircraft->setupUi(this);
|
||||
|
||||
SwashLvlConfigurationInProgress = 0;
|
||||
@ -1070,23 +1074,6 @@ void ConfigCcpmWidget::setMixer()
|
||||
updatingToHardware = false;
|
||||
}
|
||||
|
||||
/**
|
||||
Send ccpm type to the board and request saving to SD card
|
||||
*/
|
||||
void ConfigCcpmWidget::saveccpmUpdate()
|
||||
{
|
||||
if (SwashLvlConfigurationInProgress) {
|
||||
return;
|
||||
}
|
||||
ShowDisclaimer(0);
|
||||
// Send update so that the latest value is saved
|
||||
// sendccpmUpdate();
|
||||
setMixer();
|
||||
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(obj);
|
||||
saveObjectToSD(obj);
|
||||
}
|
||||
|
||||
void ConfigCcpmWidget::resizeEvent(QResizeEvent *event)
|
||||
{
|
||||
Q_UNUSED(event);
|
||||
@ -1416,6 +1403,16 @@ void ConfigCcpmWidget::SwashLvlFinishButtonPressed()
|
||||
ccpmSwashplateUpdate();
|
||||
}
|
||||
|
||||
void ConfigCcpmWidget::saveObjectToSD(UAVObject *obj)
|
||||
{
|
||||
// saveObjectToSD is now handled by the UAVUtils plugin in one
|
||||
// central place (and one central queue)
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
|
||||
utilMngr->saveObjectToSD(obj);
|
||||
}
|
||||
|
||||
int ConfigCcpmWidget::ShowDisclaimer(int messageID)
|
||||
{
|
||||
QMessageBox msgBox;
|
||||
|
@ -31,8 +31,7 @@
|
||||
#include "cfg_vehicletypes/vehicleconfig.h"
|
||||
|
||||
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
#include "uavobject.h"
|
||||
|
||||
class Ui_CcpmConfigWidget;
|
||||
@ -69,7 +68,6 @@ public:
|
||||
public slots:
|
||||
void getMixer();
|
||||
void setMixer();
|
||||
void saveccpmUpdate();
|
||||
|
||||
protected:
|
||||
void showEvent(QShowEvent *event);
|
||||
@ -112,6 +110,8 @@ private:
|
||||
|
||||
QString updateConfigObjects();
|
||||
|
||||
void saveObjectToSD(UAVObject *obj);
|
||||
|
||||
private slots:
|
||||
virtual void setupUI(QString airframeType);
|
||||
virtual bool throwConfigError(int typeInt);
|
||||
|
@ -149,9 +149,11 @@ QStringList ConfigCustomWidget::getChannelDescriptions()
|
||||
}
|
||||
|
||||
ConfigCustomWidget::ConfigCustomWidget(QWidget *parent) :
|
||||
VehicleConfig(parent), m_aircraft(new Ui_CustomConfigWidget())
|
||||
VehicleConfig(parent)
|
||||
{
|
||||
m_aircraft = new Ui_CustomConfigWidget();
|
||||
m_aircraft->setupUi(this);
|
||||
|
||||
m_aircraft->customMixerTable->setEditTriggers(QAbstractItemView::NoEditTriggers);
|
||||
|
||||
// Put combo boxes in line one of the custom mixer table:
|
||||
@ -190,6 +192,7 @@ void ConfigCustomWidget::registerWidgets(ConfigTaskWidget &parent)
|
||||
parent.addWidget(m_aircraft->customThrottle1Curve);
|
||||
parent.addWidget(m_aircraft->customThrottle2Curve->getCurveWidget());
|
||||
parent.addWidget(m_aircraft->customThrottle2Curve);
|
||||
// TODO why is curve2SourceCombo registered twice ?
|
||||
parent.addWidgetBinding("MixerSettings", "Curve2Source", m_aircraft->curve2SourceCombo);
|
||||
parent.addWidget(m_aircraft->curve2SourceCombo);
|
||||
}
|
||||
|
@ -109,8 +109,9 @@ QStringList ConfigFixedWingWidget::getChannelDescriptions()
|
||||
}
|
||||
|
||||
ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) :
|
||||
VehicleConfig(parent), m_aircraft(new Ui_FixedWingConfigWidget())
|
||||
VehicleConfig(parent)
|
||||
{
|
||||
m_aircraft = new Ui_FixedWingConfigWidget();
|
||||
m_aircraft->setupUi(this);
|
||||
|
||||
populateChannelComboBoxes();
|
||||
|
@ -73,8 +73,9 @@ QStringList ConfigGroundVehicleWidget::getChannelDescriptions()
|
||||
}
|
||||
|
||||
ConfigGroundVehicleWidget::ConfigGroundVehicleWidget(QWidget *parent) :
|
||||
VehicleConfig(parent), m_aircraft(new Ui_GroundConfigWidget())
|
||||
VehicleConfig(parent)
|
||||
{
|
||||
m_aircraft = new Ui_GroundConfigWidget();
|
||||
m_aircraft->setupUi(this);
|
||||
|
||||
populateChannelComboBoxes();
|
||||
|
@ -132,8 +132,9 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions()
|
||||
}
|
||||
|
||||
ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) :
|
||||
VehicleConfig(parent), m_aircraft(new Ui_MultiRotorConfigWidget()), invertMotors(false)
|
||||
VehicleConfig(parent), invertMotors(false)
|
||||
{
|
||||
m_aircraft = new Ui_MultiRotorConfigWidget();
|
||||
m_aircraft->setupUi(this);
|
||||
|
||||
populateChannelComboBoxes();
|
||||
@ -176,8 +177,6 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) :
|
||||
|
||||
m_aircraft->multiThrottleCurve->setXAxisLabel(tr("Input"));
|
||||
m_aircraft->multiThrottleCurve->setYAxisLabel(tr("Output"));
|
||||
|
||||
updateEnableControls();
|
||||
}
|
||||
|
||||
ConfigMultiRotorWidget::~ConfigMultiRotorWidget()
|
||||
@ -874,9 +873,10 @@ void ConfigMultiRotorWidget::reverseMultirotorMotor()
|
||||
|
||||
void ConfigMultiRotorWidget::updateAirframe(QString frameType)
|
||||
{
|
||||
qDebug() << "ConfigMultiRotorWidget::updateAirframe - frame type" << frameType;
|
||||
// qDebug() << "ConfigMultiRotorWidget::updateAirframe - frame type" << frameType;
|
||||
|
||||
QString elementId;
|
||||
|
||||
if (frameType == "Tri" || frameType == "Tricopter Y") {
|
||||
elementId = "tri";
|
||||
} else if (frameType == "QuadX" || frameType == "Quad X") {
|
||||
|
@ -120,12 +120,12 @@ QString VehicleConfig::updateConfigObjectsFromWidgets()
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void VehicleConfig::refreshWidgetsValues(UAVObject *o)
|
||||
void VehicleConfig::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
Q_UNUSED(o);
|
||||
Q_UNUSED(obj);
|
||||
}
|
||||
|
||||
void VehicleConfig::updateObjectsFromWidgets()
|
||||
void VehicleConfig::updateObjectsFromWidgetsImpl()
|
||||
{}
|
||||
|
||||
void VehicleConfig::resetActuators(GUIConfigDataUnion *configData)
|
||||
|
@ -162,8 +162,13 @@ class ConfigTaskWidget;
|
||||
/*
|
||||
* This class handles vehicle specific configuration UI and associated logic.
|
||||
*
|
||||
* This class derives from ConfigTaskWidget and overrides its the default "binding" mechanism.
|
||||
* It does not use the "dirty" state management directlyand registers its relevant widgets with ConfigTaskWidget to do so.
|
||||
* VehicleConfig derives from ConfigTaskWidget but is not a top level ConfigTaskWidget.
|
||||
* VehicleConfig objects are nested within the ConfigVehicleConfigWidget and have particularities:
|
||||
* - bindings are added to the parent (i.e. ConfigVehicleConfigWidget)
|
||||
* - auto bindings are not supported
|
||||
* - as a consequence things like dirty state management are bypassed and delegated to the parent class.
|
||||
*
|
||||
* It does not use the "dirty" state management directly and registers its relevant widgets with ConfigTaskWidget to do so.
|
||||
*/
|
||||
class VehicleConfig : public ConfigTaskWidget {
|
||||
Q_OBJECT
|
||||
@ -244,9 +249,8 @@ protected:
|
||||
double getCurveMin(QList<double> *curve);
|
||||
double getCurveMax(QList<double> *curve);
|
||||
|
||||
protected slots:
|
||||
virtual void refreshWidgetsValues(UAVObject *o = NULL);
|
||||
virtual void updateObjectsFromWidgets();
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private:
|
||||
static UAVObjectManager *getUAVObjectManager();
|
||||
|
@ -4,6 +4,12 @@ DEFINES += CONFIG_LIBRARY
|
||||
|
||||
QT += widgets svg opengl qml quick
|
||||
|
||||
# silence eigen warnings
|
||||
QMAKE_CXXFLAGS_WARN_ON += -Wno-deprecated-declarations
|
||||
win32 {
|
||||
QMAKE_CXXFLAGS_WARN_ON += -Wno-ignored-attributes
|
||||
}
|
||||
|
||||
include(config_dependencies.pri)
|
||||
|
||||
INCLUDEPATH += ../../libs/eigen
|
||||
@ -21,8 +27,7 @@ HEADERS += \
|
||||
configccattitudewidget.h \
|
||||
configstabilizationwidget.h \
|
||||
assertions.h \
|
||||
defaultattitudewidget.h \
|
||||
defaulthwsettingswidget.h \
|
||||
defaultconfigwidget.h \
|
||||
channelform.h \
|
||||
inputchannelform.h \
|
||||
configcamerastabilizationwidget.h \
|
||||
@ -70,8 +75,7 @@ SOURCES += \
|
||||
config_cc_hw_widget.cpp \
|
||||
configccattitudewidget.cpp \
|
||||
configstabilizationwidget.cpp \
|
||||
defaultattitudewidget.cpp \
|
||||
defaulthwsettingswidget.cpp \
|
||||
defaultconfigwidget.cpp \
|
||||
channelform.cpp \
|
||||
inputchannelform.cpp \
|
||||
configcamerastabilizationwidget.cpp \
|
||||
@ -114,8 +118,7 @@ FORMS += \
|
||||
input_wizard.ui \
|
||||
output.ui \
|
||||
ccattitude.ui \
|
||||
defaultattitude.ui \
|
||||
defaulthwsettings.ui \
|
||||
defaultconfig.ui \
|
||||
inputchannelform.ui \
|
||||
camerastabilization.ui \
|
||||
outputchannelform.ui \
|
||||
|
@ -1,14 +1,14 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configtelemetrywidget.h
|
||||
* @file config_cc_hw_widget.cpp
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief The Configuration Gadget used to update settings in the firmware
|
||||
* @brief The Configuration Gadget used to update hardware settings in the firmware
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
@ -31,34 +31,28 @@
|
||||
#include "ui_cc_hw_settings.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include <uavobjectutilmanager.h>
|
||||
|
||||
#include "hwsettings.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QStringList>
|
||||
#include <QWidget>
|
||||
#include <QTextEdit>
|
||||
#include <QVBoxLayout>
|
||||
#include <QPushButton>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <QSvgRenderer>
|
||||
|
||||
ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_telemetry = new Ui_CC_HW_Widget();
|
||||
m_telemetry->setupUi(this);
|
||||
|
||||
// must be done before auto binding !
|
||||
setWikiURL("CC+Hardware+Configuration");
|
||||
|
||||
addAutoBindings();
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_telemetry->saveTelemetryToRAM->setVisible(false);
|
||||
}
|
||||
|
||||
|
||||
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
int id = utilMngr->getBoardModel();
|
||||
|
||||
switch (id) {
|
||||
case 0x0101:
|
||||
m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0101.svg"));
|
||||
@ -79,7 +73,7 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
m_telemetry->label_2->setPixmap(QPixmap(":/configgadget/images/coptercontrol.svg"));
|
||||
break;
|
||||
}
|
||||
addApplySaveButtons(m_telemetry->saveTelemetryToRAM, m_telemetry->saveTelemetryToSD);
|
||||
|
||||
addWidgetBinding("HwSettings", "CC_FlexiPort", m_telemetry->cbFlexi);
|
||||
addWidgetBinding("HwSettings", "CC_MainPort", m_telemetry->cbTele);
|
||||
addWidgetBinding("HwSettings", "CC_RcvrPort", m_telemetry->cbRcvr);
|
||||
@ -90,20 +84,13 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
// Add Gps protocol configuration
|
||||
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
|
||||
if (hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_GPS] != HwSettings::OPTIONALMODULES_ENABLED) {
|
||||
if (hwSettings->getOptionalModules(HwSettings::OPTIONALMODULES_GPS) != HwSettings::OPTIONALMODULES_ENABLED) {
|
||||
m_telemetry->gpsProtocol->setEnabled(false);
|
||||
m_telemetry->gpsProtocol->setToolTip(tr("Enable GPS module and reboot the board to be able to select GPS protocol"));
|
||||
} else {
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_telemetry->gpsProtocol);
|
||||
}
|
||||
|
||||
connect(m_telemetry->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
enableSaveButtons(false);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
forceConnectedState();
|
||||
}
|
||||
|
||||
ConfigCCHWWidget::~ConfigCCHWWidget()
|
||||
@ -146,17 +133,6 @@ void ConfigCCHWWidget::widgetsContentsChanged()
|
||||
|
||||
void ConfigCCHWWidget::enableSaveButtons(bool enable)
|
||||
{
|
||||
m_telemetry->saveTelemetryToRAM->setEnabled(enable);
|
||||
m_telemetry->saveTelemetryToSD->setEnabled(enable);
|
||||
m_telemetry->applyButton->setEnabled(enable);
|
||||
m_telemetry->saveButton->setEnabled(enable);
|
||||
}
|
||||
|
||||
void ConfigCCHWWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("CC+Hardware+Configuration"),
|
||||
QUrl::StrictMode));
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
@ -1,13 +1,14 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configtelemetrytwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @file config_cc_hw_widget.h
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Telemetry configuration panel
|
||||
* @brief The Configuration Gadget used to update hardware settings in the firmware
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
@ -28,16 +29,10 @@
|
||||
#define CONFIGCCHWWIDGET_H
|
||||
|
||||
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavobject.h"
|
||||
#include "smartsavebutton.h"
|
||||
|
||||
#include <QWidget>
|
||||
#include <QList>
|
||||
#include <QSvgRenderer>
|
||||
|
||||
class Ui_CC_HW_Widget;
|
||||
class QWidget;
|
||||
class QSvgRenderer;
|
||||
|
||||
class ConfigCCHWWidget : public ConfigTaskWidget {
|
||||
Q_OBJECT
|
||||
@ -46,7 +41,6 @@ public:
|
||||
ConfigCCHWWidget(QWidget *parent = 0);
|
||||
~ConfigCCHWWidget();
|
||||
private slots:
|
||||
void openHelp();
|
||||
void refreshValues();
|
||||
void widgetsContentsChanged();
|
||||
void enableSaveButtons(bool enable);
|
||||
|
@ -23,8 +23,11 @@ ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) :
|
||||
m_autotune = new Ui_AutotuneWidget();
|
||||
m_autotune->setupUi(this);
|
||||
|
||||
// Connect automatic signals
|
||||
autoLoadWidgets();
|
||||
// must be done before auto binding !
|
||||
// setWikiURL("");
|
||||
|
||||
addAutoBindings();
|
||||
|
||||
disableMouseWheelEvents();
|
||||
|
||||
// Whenever any value changes compute new potential stabilization settings
|
||||
@ -148,26 +151,23 @@ void ConfigAutotuneWidget::recomputeStabilization()
|
||||
m_autotune->pitchAttitudeKp->setText(QString().number(stabSettings.PitchPI[StabilizationSettings::PITCHPI_KP]));
|
||||
m_autotune->pitchAttitudeKi->setText(QString().number(stabSettings.PitchPI[StabilizationSettings::PITCHPI_KI]));
|
||||
}
|
||||
void ConfigAutotuneWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
|
||||
void ConfigAutotuneWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
|
||||
if (obj == hwSettings) {
|
||||
bool dirtyBack = isDirty();
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
m_autotune->enableAutoTune->setChecked(
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_AUTOTUNE] == HwSettings::OPTIONALMODULES_ENABLED);
|
||||
setDirty(dirtyBack);
|
||||
bool enabled = (hwSettings->getOptionalModules(HwSettings::OPTIONALMODULES_AUTOTUNE) == HwSettings::OPTIONALMODULES_ENABLED);
|
||||
m_autotune->enableAutoTune->setChecked(enabled);
|
||||
}
|
||||
ConfigTaskWidget::refreshWidgetsValues(obj);
|
||||
}
|
||||
void ConfigAutotuneWidget::updateObjectsFromWidgets()
|
||||
|
||||
void ConfigAutotuneWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_AUTOTUNE] =
|
||||
m_autotune->enableAutoTune->isChecked() ? HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED;
|
||||
hwSettings->setData(hwSettingsData);
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
quint8 enableModule = (m_autotune->enableAutoTune->isChecked()) ? HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED;
|
||||
|
||||
hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_AUTOTUNE, enableModule);
|
||||
;
|
||||
}
|
||||
|
@ -50,11 +50,10 @@ private:
|
||||
Ui_AutotuneWidget *m_autotune;
|
||||
StabilizationSettings::DataFields stabSettings;
|
||||
|
||||
signals:
|
||||
protected:
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
public slots:
|
||||
void refreshWidgetsValues(UAVObject *obj);
|
||||
void updateObjectsFromWidgets();
|
||||
private slots:
|
||||
void recomputeStabilization();
|
||||
void saveStabilization();
|
||||
|
@ -38,9 +38,6 @@
|
||||
|
||||
#include "ui_camerastabilization.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
|
||||
#include "camerastabsettings.h"
|
||||
#include "hwsettings.h"
|
||||
#include "mixersettings.h"
|
||||
@ -51,22 +48,16 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent
|
||||
ui = new Ui_CameraStabilizationWidget();
|
||||
ui->setupUi(this);
|
||||
|
||||
addApplySaveButtons(ui->camerastabilizationSaveRAM, ui->camerastabilizationSaveSD);
|
||||
// must be done before auto binding !
|
||||
setWikiURL("Camera+Stabilisation+Configuration");
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
ui->camerastabilizationSaveRAM->setVisible(false);
|
||||
}
|
||||
addAutoBindings();
|
||||
|
||||
disableMouseWheelEvents();
|
||||
|
||||
// These widgets don't have direct relation to UAVObjects
|
||||
// and need special processing
|
||||
QComboBox *outputs[] = {
|
||||
ui->rollChannel,
|
||||
ui->pitchChannel,
|
||||
ui->yawChannel,
|
||||
};
|
||||
QComboBox *outputs[] = { ui->rollChannel, ui->pitchChannel, ui->yawChannel, };
|
||||
const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]);
|
||||
|
||||
// Populate widgets with channel numbers
|
||||
@ -78,11 +69,6 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent
|
||||
}
|
||||
}
|
||||
|
||||
setWikiURL("Camera+Stabilisation+Configuration");
|
||||
// Load UAVObjects to widget relations from UI file
|
||||
// using objrelation dynamic property
|
||||
autoLoadWidgets();
|
||||
|
||||
// Add some widgets to track their UI dirty state and handle smartsave
|
||||
addWidget(ui->enableCameraStabilization);
|
||||
addWidget(ui->rollChannel);
|
||||
@ -101,9 +87,6 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent
|
||||
|
||||
// To set special widgets to defaults when requested
|
||||
connect(this, SIGNAL(defaultRequested(int)), this, SLOT(defaultRequestedSlot(int)));
|
||||
|
||||
disableMouseWheelEvents();
|
||||
updateEnableControls();
|
||||
}
|
||||
|
||||
ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget()
|
||||
@ -114,21 +97,19 @@ ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget()
|
||||
/*
|
||||
* This overridden function refreshes widgets which have no direct relation
|
||||
* to any of UAVObjects. It saves their dirty state first because update comes
|
||||
* from UAVObjects, and then restores it. Aftewards it calls base class
|
||||
* function to take care of other widgets which were dynamically added.
|
||||
* from UAVObjects, and then restores it.
|
||||
*/
|
||||
void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
void ConfigCameraStabilizationWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
bool dirty = isDirty();
|
||||
Q_UNUSED(obj);
|
||||
|
||||
// Set module enable checkbox from OptionalModules UAVObject item.
|
||||
// It needs special processing because ConfigTaskWidget uses TRUE/FALSE
|
||||
// for QCheckBox, but OptionalModules uses Enabled/Disabled enum values.
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
|
||||
ui->enableCameraStabilization->setChecked(
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED);
|
||||
hwSettings->getOptionalModules(HwSettings::OPTIONALMODULES_CAMERASTAB) == HwSettings::OPTIONALMODULES_ENABLED);
|
||||
|
||||
// Load mixer outputs which are mapped to camera controls
|
||||
MixerSettings *mixerSettings = MixerSettings::GetInstance(getObjectManager());
|
||||
@ -168,22 +149,16 @@ void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
setDirty(dirty);
|
||||
|
||||
ConfigTaskWidget::refreshWidgetsValues(obj);
|
||||
}
|
||||
|
||||
/*
|
||||
* This overridden function updates UAVObjects which have no direct relation
|
||||
* to any of widgets. Aftewards it calls base class function to take care of
|
||||
* other object to widget relations which were dynamically added.
|
||||
* to any of widgets.
|
||||
*/
|
||||
void ConfigCameraStabilizationWidget::updateObjectsFromWidgets()
|
||||
void ConfigCameraStabilizationWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
// Save state of the module enable checkbox first.
|
||||
// Do not use setData() member on whole object, if possible, since it triggers
|
||||
// unnessesary UAVObect update.
|
||||
// Do not use setData() member on whole object, if possible, since it triggers unnecessary UAVObect update.
|
||||
quint8 enableModule = ui->enableCameraStabilization->isChecked() ?
|
||||
HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED;
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
@ -257,8 +232,6 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets()
|
||||
// FIXME: Should not use setData() to prevent double updates.
|
||||
// It should be refactored after the reformatting of MixerSettings UAVObject.
|
||||
mixerSettings->setData(mixerSettingsData);
|
||||
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
}
|
||||
|
||||
/*
|
||||
@ -269,18 +242,6 @@ void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group)
|
||||
{
|
||||
Q_UNUSED(group);
|
||||
|
||||
// Here is the example of how to reset the state of QCheckBox. It is
|
||||
// commented out because we normally don't want to reset the module
|
||||
// enable state to default "disabled" (or we don't care about values at all).
|
||||
// But if you want, you could use the dirtyClone() function to get default
|
||||
// values of an object and then use them to set a widget state.
|
||||
//
|
||||
// HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
// HwSettings *hwSettingsDefault=(HwSettings*)hwSettings->dirtyClone();
|
||||
// HwSettings::DataFields hwSettingsData = hwSettingsDefault->getData();
|
||||
// m_camerastabilization->enableCameraStabilization->setChecked(
|
||||
// hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED);
|
||||
|
||||
// For outputs we set them all to none, so don't use any UAVObject to get defaults
|
||||
QComboBox *outputs[] = {
|
||||
ui->rollChannel,
|
||||
|
@ -28,8 +28,7 @@
|
||||
#define CONFIGCAMERASTABILIZATIONWIDGET_H
|
||||
|
||||
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
#include "uavobject.h"
|
||||
|
||||
#include "camerastabsettings.h"
|
||||
@ -43,10 +42,12 @@ public:
|
||||
ConfigCameraStabilizationWidget(QWidget *parent = 0);
|
||||
~ConfigCameraStabilizationWidget();
|
||||
|
||||
protected:
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private:
|
||||
Ui_CameraStabilizationWidget *ui;
|
||||
void refreshWidgetsValues(UAVObject *obj);
|
||||
void updateObjectsFromWidgets();
|
||||
|
||||
private slots:
|
||||
void defaultRequestedSlot(int group);
|
||||
|
@ -29,9 +29,7 @@
|
||||
|
||||
#include "ui_ccattitude.h"
|
||||
|
||||
#include "utils/coordinateconversions.h"
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include <utils/coordinateconversions.h>
|
||||
#include <calibration/calibrationutils.h>
|
||||
|
||||
#include "attitudesettings.h"
|
||||
@ -39,32 +37,23 @@
|
||||
#include "accelgyrosettings.h"
|
||||
#include "gyrostate.h"
|
||||
|
||||
#include <QMutexLocker>
|
||||
#include <QMessageBox>
|
||||
#include <QDebug>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
|
||||
ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
|
||||
ConfigTaskWidget(parent),
|
||||
ui(new Ui_ccattitude)
|
||||
ConfigTaskWidget(parent), accelUpdates(0), gyroUpdates(0)
|
||||
{
|
||||
ui = new Ui_ccattitude(),
|
||||
ui->setupUi(this);
|
||||
connect(ui->zeroBias, SIGNAL(clicked()), this, SLOT(startAccelCalibration()));
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
ui->applyButton->setVisible(false);
|
||||
}
|
||||
// must be done before auto binding !
|
||||
setWikiURL("CC+Attitude+Configuration");
|
||||
|
||||
addAutoBindings();
|
||||
|
||||
addApplySaveButtons(ui->applyButton, ui->saveButton);
|
||||
addUAVObject("AttitudeSettings");
|
||||
addUAVObject("AccelGyroSettings");
|
||||
|
||||
// Connect the help button
|
||||
connect(ui->ccAttitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
addWidgetBinding("AttitudeSettings", "ZeroDuringArming", ui->zeroGyroBiasOnArming);
|
||||
addWidgetBinding("AttitudeSettings", "InitialZeroWhenBoardSteady", ui->initGyroWhenBoardSteady);
|
||||
|
||||
@ -74,9 +63,8 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->pitchBias, AttitudeSettings::BOARDROTATION_PITCH);
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->yawBias, AttitudeSettings::BOARDROTATION_YAW);
|
||||
addWidget(ui->zeroBias);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
forceConnectedState();
|
||||
|
||||
connect(ui->zeroBias, SIGNAL(clicked()), this, SLOT(startAccelCalibration()));
|
||||
}
|
||||
|
||||
ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget()
|
||||
@ -144,7 +132,8 @@ void ConfigCCAttitudeWidget::sensorsUpdated(UAVObject *obj)
|
||||
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE;
|
||||
AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData);
|
||||
AccelGyroSettings::GetInstance(getObjectManager())->setData(accelGyroSettingsData);
|
||||
this->setDirty(true);
|
||||
|
||||
setDirty(true);
|
||||
|
||||
// reenable controls
|
||||
enableControls(true);
|
||||
@ -220,12 +209,6 @@ void ConfigCCAttitudeWidget::startAccelCalibration()
|
||||
connect(&timer, SIGNAL(timeout()), this, SLOT(timeout()));
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("CC+Attitude+Configuration"),
|
||||
QUrl::StrictMode));
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::setAccelFiltering(bool active)
|
||||
{
|
||||
Q_UNUSED(active);
|
||||
@ -241,9 +224,7 @@ void ConfigCCAttitudeWidget::enableControls(bool enable)
|
||||
ConfigTaskWidget::enableControls(enable);
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::updateObjectsFromWidgets()
|
||||
void ConfigCCAttitudeWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
|
||||
ui->zeroBiasProgress->setValue(0);
|
||||
}
|
||||
|
@ -28,8 +28,7 @@
|
||||
#define CCATTITUDEWIDGET_H
|
||||
|
||||
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
#include "uavobject.h"
|
||||
|
||||
#include <QWidget>
|
||||
@ -44,13 +43,13 @@ public:
|
||||
explicit ConfigCCAttitudeWidget(QWidget *parent = 0);
|
||||
~ConfigCCAttitudeWidget();
|
||||
|
||||
virtual void updateObjectsFromWidgets();
|
||||
protected:
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private slots:
|
||||
void sensorsUpdated(UAVObject *obj);
|
||||
void timeout();
|
||||
void startAccelCalibration();
|
||||
void openHelp();
|
||||
void setAccelFiltering(bool active);
|
||||
|
||||
private:
|
||||
@ -66,6 +65,7 @@ private:
|
||||
QList<double> x_gyro_accum, y_gyro_accum, z_gyro_accum;
|
||||
|
||||
static const int NUM_SENSOR_UPDATES = 300;
|
||||
|
||||
protected:
|
||||
virtual void enableControls(bool enable);
|
||||
};
|
||||
|
@ -2,7 +2,8 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configgadget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
@ -25,8 +26,11 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "configgadget.h"
|
||||
|
||||
#include "configgadgetwidget.h"
|
||||
|
||||
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||
|
||||
ConfigGadget::ConfigGadget(QString classId, ConfigGadgetWidget *widget, QWidget *parent) :
|
||||
IUAVGadget(classId, parent), m_widget(widget)
|
||||
{}
|
||||
@ -40,3 +44,13 @@ void ConfigGadget::loadConfiguration(IUAVGadgetConfiguration *config)
|
||||
{
|
||||
Q_UNUSED(config);
|
||||
}
|
||||
|
||||
void ConfigGadget::saveState(QSettings *settings)
|
||||
{
|
||||
m_widget->saveState(settings);
|
||||
}
|
||||
|
||||
void ConfigGadget::restoreState(QSettings *settings)
|
||||
{
|
||||
m_widget->restoreState(settings);
|
||||
}
|
||||
|
@ -2,7 +2,8 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configgadget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
@ -28,14 +29,10 @@
|
||||
#define CONFIGGADGET_H
|
||||
|
||||
#include <coreplugin/iuavgadget.h>
|
||||
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||
|
||||
class IUAVGadget;
|
||||
// class QList<int>;
|
||||
class QWidget;
|
||||
class QString;
|
||||
class ConfigGadgetWidget;
|
||||
class Ui_ConfigGadget;
|
||||
|
||||
using namespace Core;
|
||||
|
||||
@ -49,8 +46,12 @@ public:
|
||||
{
|
||||
return (QWidget *)m_widget;
|
||||
}
|
||||
|
||||
void loadConfiguration(IUAVGadgetConfiguration *config);
|
||||
|
||||
void saveState(QSettings *settings);
|
||||
void restoreState(QSettings *settings);
|
||||
|
||||
private:
|
||||
ConfigGadgetWidget *m_widget;
|
||||
};
|
||||
|
@ -41,18 +41,22 @@
|
||||
#include "configrevowidget.h"
|
||||
#include "configrevonanohwwidget.h"
|
||||
#include "configsparky2hwwidget.h"
|
||||
#include "defaultattitudewidget.h"
|
||||
#include "defaulthwsettingswidget.h"
|
||||
#include "uavobjectutilmanager.h"
|
||||
#include "defaultconfigwidget.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <uavobjectutilmanager.h>
|
||||
#include <uavtalk/telemetrymanager.h>
|
||||
#include <uavtalk/oplinkmanager.h>
|
||||
|
||||
#include "utils/mytabbedstackwidget.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QStringList>
|
||||
#include <QWidget>
|
||||
#include <QTextEdit>
|
||||
#include <QVBoxLayout>
|
||||
#include <QPushButton>
|
||||
#include <QMessageBox>
|
||||
#include <QSettings>
|
||||
#include <QDebug>
|
||||
|
||||
#define OPLINK_TIMEOUT 2000
|
||||
|
||||
ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
{
|
||||
@ -66,85 +70,93 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
layout->addWidget(stackWidget);
|
||||
setLayout(layout);
|
||||
|
||||
QWidget *qwd;
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
|
||||
QIcon *icon = new QIcon();
|
||||
QWidget *widget;
|
||||
QIcon *icon;
|
||||
|
||||
icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
qwd = new DefaultHwSettingsWidget(this);
|
||||
stackWidget->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
|
||||
widget = new DefaultConfigWidget(this, tr("Hardware"));
|
||||
stackWidget->insertTab(ConfigGadgetWidget::Hardware, widget, *icon, QString("Hardware"));
|
||||
|
||||
icon = new QIcon();
|
||||
icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/vehicle_normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/vehicle_selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
qwd = new ConfigVehicleTypeWidget(this);
|
||||
stackWidget->insertTab(ConfigGadgetWidget::aircraft, qwd, *icon, QString("Vehicle"));
|
||||
widget = new ConfigVehicleTypeWidget(this);
|
||||
static_cast<ConfigTaskWidget *>(widget)->bind();
|
||||
stackWidget->insertTab(ConfigGadgetWidget::Aircraft, widget, *icon, QString("Vehicle"));
|
||||
|
||||
icon = new QIcon();
|
||||
icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/input_normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/input_selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
qwd = new ConfigInputWidget(this);
|
||||
stackWidget->insertTab(ConfigGadgetWidget::input, qwd, *icon, QString("Input"));
|
||||
widget = new ConfigInputWidget(this);
|
||||
static_cast<ConfigTaskWidget *>(widget)->bind();
|
||||
stackWidget->insertTab(ConfigGadgetWidget::Input, widget, *icon, QString("Input"));
|
||||
|
||||
icon = new QIcon();
|
||||
icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/output_normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/output_selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
qwd = new ConfigOutputWidget(this);
|
||||
stackWidget->insertTab(ConfigGadgetWidget::output, qwd, *icon, QString("Output"));
|
||||
widget = new ConfigOutputWidget(this);
|
||||
static_cast<ConfigTaskWidget *>(widget)->bind();
|
||||
stackWidget->insertTab(ConfigGadgetWidget::Output, widget, *icon, QString("Output"));
|
||||
|
||||
icon = new QIcon();
|
||||
icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
qwd = new DefaultAttitudeWidget(this);
|
||||
stackWidget->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
|
||||
widget = new DefaultConfigWidget(this, tr("Attitude"));
|
||||
stackWidget->insertTab(ConfigGadgetWidget::Sensors, widget, *icon, QString("Attitude"));
|
||||
|
||||
icon = new QIcon();
|
||||
icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/stabilization_selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
qwd = new ConfigStabilizationWidget(this);
|
||||
stackWidget->insertTab(ConfigGadgetWidget::stabilization, qwd, *icon, QString("Stabilization"));
|
||||
widget = new ConfigStabilizationWidget(this);
|
||||
static_cast<ConfigTaskWidget *>(widget)->bind();
|
||||
stackWidget->insertTab(ConfigGadgetWidget::Stabilization, widget, *icon, QString("Stabilization"));
|
||||
|
||||
icon = new QIcon();
|
||||
icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
qwd = new ConfigCameraStabilizationWidget(this);
|
||||
stackWidget->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Gimbal"));
|
||||
widget = new ConfigCameraStabilizationWidget(this);
|
||||
static_cast<ConfigTaskWidget *>(widget)->bind();
|
||||
stackWidget->insertTab(ConfigGadgetWidget::CameraStabilization, widget, *icon, QString("Gimbal"));
|
||||
|
||||
icon = new QIcon();
|
||||
icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/txpid_selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
qwd = new ConfigTxPIDWidget(this);
|
||||
stackWidget->insertTab(ConfigGadgetWidget::txpid, qwd, *icon, QString("TxPID"));
|
||||
widget = new ConfigTxPIDWidget(this);
|
||||
static_cast<ConfigTaskWidget *>(widget)->bind();
|
||||
stackWidget->insertTab(ConfigGadgetWidget::TxPid, widget, *icon, QString("TxPID"));
|
||||
|
||||
stackWidget->setCurrentIndex(ConfigGadgetWidget::hardware);
|
||||
icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/pipx-normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/pipx-selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
widget = new DefaultConfigWidget(this, tr("OPLink Configuration"));
|
||||
stackWidget->insertTab(ConfigGadgetWidget::OPLink, widget, *icon, QString("OPLink"));
|
||||
|
||||
// Listen to autopilot connection events
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
TelemetryManager *telMngr = pm->getObject<TelemetryManager>();
|
||||
connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()));
|
||||
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()));
|
||||
stackWidget->setCurrentIndex(ConfigGadgetWidget::Hardware);
|
||||
|
||||
// And check whether by any chance we are not already connected
|
||||
if (telMngr->isConnected()) {
|
||||
// connect to autopilot connection events
|
||||
TelemetryManager *tm = pm->getObject<TelemetryManager>();
|
||||
connect(tm, SIGNAL(connected()), this, SLOT(onAutopilotConnect()));
|
||||
connect(tm, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()));
|
||||
// check if we are already connected
|
||||
if (tm->isConnected()) {
|
||||
onAutopilotConnect();
|
||||
}
|
||||
|
||||
// connect to oplink manager
|
||||
OPLinkManager *om = pm->getObject<OPLinkManager>();
|
||||
connect(om, SIGNAL(connected()), this, SLOT(onOPLinkConnect()));
|
||||
connect(om, SIGNAL(disconnected()), this, SLOT(onOPLinkDisconnect()));
|
||||
// check if we are already connected
|
||||
if (om->isConnected()) {
|
||||
onOPLinkConnect();
|
||||
}
|
||||
|
||||
help = 0;
|
||||
connect(stackWidget, SIGNAL(currentAboutToShow(int, bool *)), this, SLOT(tabAboutToChange(int, bool *)));
|
||||
|
||||
// Connect to the OPLinkStatus object updates
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
oplinkStatusObj = dynamic_cast<UAVDataObject *>(objManager->getObject("OPLinkStatus"));
|
||||
if (oplinkStatusObj != NULL) {
|
||||
connect(oplinkStatusObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateOPLinkStatus(UAVObject *)));
|
||||
} else {
|
||||
qDebug() << "Error: Object is unknown (OPLinkStatus).";
|
||||
}
|
||||
|
||||
// Create the timer that is used to timeout the connection to the OPLink.
|
||||
oplinkTimeout = new QTimer(this);
|
||||
connect(oplinkTimeout, SIGNAL(timeout()), this, SLOT(onOPLinkDisconnect()));
|
||||
oplinkConnected = false;
|
||||
}
|
||||
|
||||
ConfigGadgetWidget::~ConfigGadgetWidget()
|
||||
@ -154,79 +166,118 @@ ConfigGadgetWidget::~ConfigGadgetWidget()
|
||||
|
||||
void ConfigGadgetWidget::startInputWizard()
|
||||
{
|
||||
stackWidget->setCurrentIndex(ConfigGadgetWidget::input);
|
||||
ConfigInputWidget *inputWidget = dynamic_cast<ConfigInputWidget *>(stackWidget->getWidget(ConfigGadgetWidget::input));
|
||||
stackWidget->setCurrentIndex(ConfigGadgetWidget::Input);
|
||||
ConfigInputWidget *inputWidget = dynamic_cast<ConfigInputWidget *>(stackWidget->getWidget(ConfigGadgetWidget::Input));
|
||||
Q_ASSERT(inputWidget);
|
||||
inputWidget->startInputWizard();
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::saveState(QSettings *settings)
|
||||
{
|
||||
settings->setValue("currentIndex", stackWidget->currentIndex());
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::restoreState(QSettings *settings)
|
||||
{
|
||||
int index = settings->value("currentIndex", 0).toInt();
|
||||
|
||||
stackWidget->setCurrentIndex(index);
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::resizeEvent(QResizeEvent *event)
|
||||
{
|
||||
QWidget::resizeEvent(event);
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::onAutopilotDisconnect()
|
||||
{
|
||||
QWidget *qwd = new DefaultAttitudeWidget(this);
|
||||
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd);
|
||||
|
||||
qwd = new DefaultHwSettingsWidget(this);
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::hardware, qwd);
|
||||
|
||||
emit autopilotDisconnected();
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::onAutopilotConnect()
|
||||
{
|
||||
qDebug() << "ConfigGadgetWidget onAutopilotConnect";
|
||||
// First of all, check what Board type we are talking to, and
|
||||
// if necessary, remove/add tabs in the config gadget:
|
||||
// qDebug() << "ConfigGadgetWidget::onAutopilotConnect";
|
||||
|
||||
// Check what Board type we are talking to, and if necessary, remove/add tabs in the config gadget
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
|
||||
if (utilMngr) {
|
||||
int board = utilMngr->getBoardModel();
|
||||
if ((board & 0xff00) == 0x0400) {
|
||||
// CopterControl family
|
||||
QWidget *qwd = new ConfigCCAttitudeWidget(this);
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd);
|
||||
qwd = new ConfigCCHWWidget(this);
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::hardware, qwd);
|
||||
ConfigTaskWidget *widget;
|
||||
widget = new ConfigCCAttitudeWidget(this);
|
||||
widget->bind();
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::Sensors, widget);
|
||||
widget = new ConfigCCHWWidget(this);
|
||||
widget->bind();
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::Hardware, widget);
|
||||
} else if ((board & 0xff00) == 0x0900) {
|
||||
// Revolution family
|
||||
QWidget *qwd = new ConfigRevoWidget(this);
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd);
|
||||
ConfigTaskWidget *widget;
|
||||
widget = new ConfigRevoWidget(this);
|
||||
widget->bind();
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::Sensors, widget);
|
||||
if (board == 0x0903 || board == 0x0904) {
|
||||
qwd = new ConfigRevoHWWidget(this);
|
||||
widget = new ConfigRevoHWWidget(this);
|
||||
} else if (board == 0x0905) {
|
||||
qwd = new ConfigRevoNanoHWWidget(this);
|
||||
widget = new ConfigRevoNanoHWWidget(this);
|
||||
}
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::hardware, qwd);
|
||||
widget->bind();
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::Hardware, widget);
|
||||
} else if ((board & 0xff00) == 0x9200) {
|
||||
// Sparky2
|
||||
QWidget *qwd = new ConfigRevoWidget(this);
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd);
|
||||
qwd = new ConfigSparky2HWWidget(this);
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::hardware, qwd);
|
||||
ConfigTaskWidget *widget;
|
||||
widget = new ConfigRevoWidget(this);
|
||||
widget->bind();
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::Sensors, widget);
|
||||
widget = new ConfigSparky2HWWidget(this);
|
||||
widget->bind();
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::Hardware, widget);
|
||||
} else {
|
||||
// Unknown board
|
||||
qDebug() << "Unknown board " << board;
|
||||
qWarning() << "Unknown board " << board;
|
||||
}
|
||||
}
|
||||
|
||||
emit autopilotConnected();
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::tabAboutToChange(int i, bool *proceed)
|
||||
void ConfigGadgetWidget::onAutopilotDisconnect()
|
||||
{
|
||||
Q_UNUSED(i);
|
||||
// qDebug() << "ConfigGadgetWidget::onAutopilotDiconnect";
|
||||
QWidget *widget;
|
||||
|
||||
widget = new DefaultConfigWidget(this, tr("Attitude"));
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::Sensors, widget);
|
||||
|
||||
widget = new DefaultConfigWidget(this, tr("Hardware"));
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::Hardware, widget);
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::onOPLinkConnect()
|
||||
{
|
||||
// qDebug() << "ConfigGadgetWidget::onOPLinkConnect";
|
||||
|
||||
ConfigTaskWidget *widget = new ConfigOPLinkWidget(this);
|
||||
|
||||
widget->bind();
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::OPLink, widget);
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::onOPLinkDisconnect()
|
||||
{
|
||||
// qDebug() << "ConfigGadgetWidget::onOPLinkDisconnect";
|
||||
|
||||
QWidget *widget = new DefaultConfigWidget(this, tr("OPLink Configuration"));
|
||||
|
||||
stackWidget->replaceTab(ConfigGadgetWidget::OPLink, widget);
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::tabAboutToChange(int index, bool *proceed)
|
||||
{
|
||||
Q_UNUSED(index);
|
||||
*proceed = true;
|
||||
ConfigTaskWidget *wid = qobject_cast<ConfigTaskWidget *>(stackWidget->currentWidget());
|
||||
if (!wid) {
|
||||
return;
|
||||
}
|
||||
if (wid->isDirty()) {
|
||||
int ans = QMessageBox::warning(this, tr("Unsaved changes"), tr("The tab you are leaving has unsaved changes,"
|
||||
int ans = QMessageBox::warning(this, tr("Unsaved changes"), tr("The tab you are leaving has unsaved changes, "
|
||||
"if you proceed they will be lost.\n"
|
||||
"Do you still want to proceed?"), QMessageBox::Yes, QMessageBox::No);
|
||||
if (ans == QMessageBox::No) {
|
||||
@ -236,35 +287,3 @@ void ConfigGadgetWidget::tabAboutToChange(int i, bool *proceed)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*!
|
||||
\brief Called by updates to @OPLinkStatus
|
||||
*/
|
||||
void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *)
|
||||
{
|
||||
// Restart the disconnection timer.
|
||||
oplinkTimeout->start(5000);
|
||||
if (!oplinkConnected) {
|
||||
qDebug() << "ConfigGadgetWidget onOPLinkConnect";
|
||||
|
||||
QIcon *icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/pipx-normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/pipx-selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
|
||||
QWidget *qwd = new ConfigOPLinkWidget(this);
|
||||
stackWidget->insertTab(ConfigGadgetWidget::oplink, qwd, *icon, QString("OPLink"));
|
||||
oplinkConnected = true;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::onOPLinkDisconnect()
|
||||
{
|
||||
qDebug() << "ConfigGadgetWidget onOPLinkDisconnect";
|
||||
oplinkTimeout->stop();
|
||||
oplinkConnected = false;
|
||||
|
||||
if (stackWidget->currentIndex() == ConfigGadgetWidget::oplink) {
|
||||
stackWidget->setCurrentIndex(0);
|
||||
}
|
||||
stackWidget->removeTab(ConfigGadgetWidget::oplink);
|
||||
}
|
||||
|
@ -2,7 +2,8 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configgadgetwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
@ -27,53 +28,39 @@
|
||||
#ifndef CONFIGGADGETWIDGET_H
|
||||
#define CONFIGGADGETWIDGET_H
|
||||
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavobject.h"
|
||||
#include "objectpersistence.h"
|
||||
#include "utils/pathutils.h"
|
||||
#include "utils/mytabbedstackwidget.h"
|
||||
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||
|
||||
#include <QWidget>
|
||||
#include <QList>
|
||||
#include <QTextBrowser>
|
||||
#include <QMessageBox>
|
||||
|
||||
class QTextBrowser;
|
||||
class QSettings;
|
||||
class MyTabbedStackWidget;
|
||||
|
||||
class ConfigGadgetWidget : public QWidget {
|
||||
Q_OBJECT
|
||||
QTextBrowser *help;
|
||||
|
||||
public:
|
||||
enum WidgetTabs { Hardware = 0, Aircraft, Input, Output, Sensors, Stabilization, CameraStabilization, TxPid, OPLink };
|
||||
|
||||
ConfigGadgetWidget(QWidget *parent = 0);
|
||||
~ConfigGadgetWidget();
|
||||
enum widgetTabs { hardware = 0, aircraft, input, output, sensors, stabilization, camerastabilization, txpid, oplink };
|
||||
|
||||
void startInputWizard();
|
||||
|
||||
public slots:
|
||||
void onAutopilotConnect();
|
||||
void onAutopilotDisconnect();
|
||||
void tabAboutToChange(int i, bool *);
|
||||
void updateOPLinkStatus(UAVObject *object);
|
||||
void onOPLinkDisconnect();
|
||||
|
||||
signals:
|
||||
void autopilotConnected();
|
||||
void autopilotDisconnected();
|
||||
void oplinkConnect();
|
||||
void oplinkDisconnect();
|
||||
void saveState(QSettings *settings);
|
||||
void restoreState(QSettings *settings);
|
||||
|
||||
protected:
|
||||
void resizeEvent(QResizeEvent *event);
|
||||
|
||||
private slots:
|
||||
void onAutopilotConnect();
|
||||
void onAutopilotDisconnect();
|
||||
void onOPLinkConnect();
|
||||
void onOPLinkDisconnect();
|
||||
void tabAboutToChange(int index, bool *proceed);
|
||||
|
||||
private:
|
||||
UAVDataObject *oplinkStatusObj;
|
||||
|
||||
// A timer that timesout the connction to the OPLink.
|
||||
QTimer *oplinkTimeout;
|
||||
bool oplinkConnected;
|
||||
|
||||
MyTabbedStackWidget *stackWidget;
|
||||
QTextBrowser *help;
|
||||
};
|
||||
|
||||
#endif // CONFIGGADGETWIDGET_H
|
||||
|
@ -8,7 +8,7 @@
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Servo input/output configuration panel for the config gadget
|
||||
* @brief Servo input configuration panel for the config gadget
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
@ -28,11 +28,6 @@
|
||||
|
||||
#include "configinputwidget.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include <utils/stylehelper.h>
|
||||
#include <uavobjecthelper.h>
|
||||
|
||||
#include "ui_input.h"
|
||||
#include "ui_input_wizard.h"
|
||||
|
||||
@ -42,18 +37,15 @@
|
||||
#include "failsafechannelform.h"
|
||||
#include "ui_failsafechannelform.h"
|
||||
|
||||
#include <uavobjectmanager.h>
|
||||
#include <uavobjecthelper.h>
|
||||
#include <utils/stylehelper.h>
|
||||
|
||||
#include <systemalarms.h>
|
||||
|
||||
#include <QDebug>
|
||||
#include <QStringList>
|
||||
#include <QWidget>
|
||||
#include <QTextEdit>
|
||||
#include <QVBoxLayout>
|
||||
#include <QPushButton>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <QMessageBox>
|
||||
#include <QEventLoop>
|
||||
#include <QGraphicsSvgItem>
|
||||
#include <QSvgRenderer>
|
||||
|
||||
@ -86,6 +78,16 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
accessoryDesiredObj3(NULL),
|
||||
rssiDesiredObj4(NULL)
|
||||
{
|
||||
ui = new Ui_InputWidget();
|
||||
ui->setupUi(this);
|
||||
|
||||
// must be done before auto binding !
|
||||
setWikiURL("Input+Configuration");
|
||||
|
||||
addAutoBindings();
|
||||
|
||||
connect(this, SIGNAL(enableControlsChanged(bool)), this, SLOT(enableControlsChanged(bool)));
|
||||
|
||||
manualCommandObj = ManualControlCommand::GetInstance(getObjectManager());
|
||||
manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager());
|
||||
flightModeSettingsObj = FlightModeSettings::GetInstance(getObjectManager());
|
||||
@ -103,22 +105,6 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
// The other instances are populated lazily.
|
||||
Q_ASSERT(accessoryDesiredObj0);
|
||||
|
||||
ui = new Ui_InputWidget();
|
||||
ui->setupUi(this);
|
||||
|
||||
wizardUi = new Ui_InputWizardWidget();
|
||||
wizardUi->setupUi(ui->wizard);
|
||||
|
||||
addApplySaveButtons(ui->saveRCInputToRAM, ui->saveRCInputToSD);
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
ui->saveRCInputToRAM->setVisible(false);
|
||||
}
|
||||
|
||||
addApplySaveButtons(ui->saveRCInputToRAM, ui->saveRCInputToSD);
|
||||
|
||||
// Generate the rows of buttons in the input channel form GUI
|
||||
quint32 index = 0;
|
||||
quint32 indexRT = 0;
|
||||
@ -213,10 +199,6 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
connect(ui->stackedWidget, SIGNAL(currentChanged(int)), this, SLOT(disableWizardButton(int)));
|
||||
connect(ui->runCalibration, SIGNAL(toggled(bool)), this, SLOT(simpleCalibration(bool)));
|
||||
|
||||
connect(wizardUi->wzNext, SIGNAL(clicked()), this, SLOT(wzNext()));
|
||||
connect(wizardUi->wzCancel, SIGNAL(clicked()), this, SLOT(wzCancel()));
|
||||
connect(wizardUi->wzBack, SIGNAL(clicked()), this, SLOT(wzBack()));
|
||||
|
||||
connect(ReceiverActivity::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateReceiverActivityStatus()));
|
||||
ui->receiverActivityStatus->setStyleSheet("QLabel { background-color: darkGreen; color: rgb(255, 255, 255); \
|
||||
border: 1px solid grey; border-radius: 5; margin:1px; font:bold;}");
|
||||
@ -268,19 +250,17 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
connect(ui->failsafeFlightMode, SIGNAL(currentIndexChanged(int)), this, SLOT(failsafeFlightModeChanged(int)));
|
||||
connect(ui->failsafeFlightModeCb, SIGNAL(toggled(bool)), this, SLOT(failsafeFlightModeCbToggled(bool)));
|
||||
|
||||
connect(this, SIGNAL(enableControlsChanged(bool)), this, SLOT(enableControlsChanged(bool)));
|
||||
|
||||
addWidget(ui->configurationWizard);
|
||||
addWidget(ui->runCalibration);
|
||||
addWidget(ui->failsafeFlightModeCb);
|
||||
|
||||
autoLoadWidgets();
|
||||
// Wizard
|
||||
wizardUi = new Ui_InputWizardWidget();
|
||||
wizardUi->setupUi(ui->wizard);
|
||||
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
|
||||
// Connect the help button
|
||||
connect(ui->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
connect(wizardUi->wzNext, SIGNAL(clicked()), this, SLOT(wzNext()));
|
||||
connect(wizardUi->wzCancel, SIGNAL(clicked()), this, SLOT(wzCancel()));
|
||||
connect(wizardUi->wzBack, SIGNAL(clicked()), this, SLOT(wzBack()));
|
||||
|
||||
wizardUi->graphicsView->setScene(new QGraphicsScene(this));
|
||||
wizardUi->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
|
||||
@ -461,8 +441,6 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
groundChannelOrder << ManualControlSettings::CHANNELGROUPS_THROTTLE <<
|
||||
ManualControlSettings::CHANNELGROUPS_YAW <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY0;
|
||||
|
||||
updateEnableControls();
|
||||
}
|
||||
|
||||
void ConfigInputWidget::buildOptionComboBox(QComboBox *combo, UAVObjectField *field, int index, bool applyLimits)
|
||||
@ -514,12 +492,6 @@ void ConfigInputWidget::resizeEvent(QResizeEvent *event)
|
||||
wizardUi->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Input+Configuration"),
|
||||
QUrl::StrictMode));
|
||||
}
|
||||
|
||||
void ConfigInputWidget::goToWizard()
|
||||
{
|
||||
QMessageBox msgBox;
|
||||
@ -1975,8 +1947,8 @@ void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
ui->configurationWizard->setEnabled(false);
|
||||
ui->saveRCInputToRAM->setEnabled(false);
|
||||
ui->saveRCInputToSD->setEnabled(false);
|
||||
ui->applyButton->setEnabled(false);
|
||||
ui->saveButton->setEnabled(false);
|
||||
ui->runCalibration->setText(tr("Stop Manual Calibration"));
|
||||
throttleError = false;
|
||||
|
||||
@ -2053,8 +2025,8 @@ void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
actuatorSettingsObj->setData(memento.actuatorSettingsData);
|
||||
|
||||
ui->configurationWizard->setEnabled(true);
|
||||
ui->saveRCInputToRAM->setEnabled(true);
|
||||
ui->saveRCInputToSD->setEnabled(true);
|
||||
ui->applyButton->setEnabled(true);
|
||||
ui->saveButton->setEnabled(true);
|
||||
ui->runCalibration->setText(tr("Start Manual Calibration"));
|
||||
|
||||
disconnect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject *)), this, SLOT(updateCalibration()));
|
||||
@ -2210,5 +2182,5 @@ void ConfigInputWidget::failsafeFlightModeCbToggled(bool checked)
|
||||
|
||||
void ConfigInputWidget::enableControlsChanged(bool enabled)
|
||||
{
|
||||
ui->failsafeFlightMode->setEnabled(enabled && ui->failsafeFlightMode->currentIndex() != -1);
|
||||
ui->failsafeFlightMode->setEnabled(enabled && (ui->failsafeFlightMode->currentIndex() != -1));
|
||||
}
|
||||
|
@ -8,7 +8,7 @@
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Servo input/output configuration panel for the config gadget
|
||||
* @brief Servo input configuration panel for the config gadget
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
@ -29,8 +29,7 @@
|
||||
#define CONFIGINPUTWIDGET_H
|
||||
|
||||
#include "uavobjectwidgetutils/configtaskwidget.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
#include "uavobject.h"
|
||||
|
||||
#include "manualcontrolcommand.h"
|
||||
@ -213,7 +212,6 @@ private slots:
|
||||
void wzCancel();
|
||||
void goToWizard();
|
||||
void disableWizardButton(int);
|
||||
void openHelp();
|
||||
void identifyControls();
|
||||
void identifyLimits();
|
||||
void moveTxControls();
|
||||
|
@ -8,7 +8,7 @@
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief The Configuration Gadget used to configure the OPLink and Revo modem
|
||||
* @brief The Configuration Gadget used to configure the OPLink, Revo and Sparky2 modems
|
||||
***************************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
@ -30,14 +30,13 @@
|
||||
|
||||
#include "ui_oplink.h"
|
||||
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include <uavobjectmanager.h>
|
||||
#include <uavobjectutilmanager.h>
|
||||
|
||||
#include <oplinksettings.h>
|
||||
#include <oplinkstatus.h>
|
||||
|
||||
#include <QMessageBox>
|
||||
#include <QDateTime>
|
||||
#include <QDebug>
|
||||
|
||||
// Channel range and Frequency display
|
||||
static const int MAX_CHANNEL_NUM = 250;
|
||||
@ -45,40 +44,45 @@ static const int MIN_CHANNEL_RANGE = 10;
|
||||
static const float FIRST_FREQUENCY = 430.000;
|
||||
static const float FREQUENCY_STEP = 0.040;
|
||||
|
||||
ConfigOPLinkWidget::ConfigOPLinkWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
ConfigOPLinkWidget::ConfigOPLinkWidget(QWidget *parent) : ConfigTaskWidget(parent, false), statusUpdated(false)
|
||||
{
|
||||
m_oplink = new Ui_OPLinkWidget();
|
||||
m_oplink->setupUi(this);
|
||||
|
||||
// Connect to the OPLinkStatus object updates
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
oplinkStatusObj = dynamic_cast<UAVDataObject *>(objManager->getObject("OPLinkStatus"));
|
||||
// must be done before auto binding !
|
||||
setWikiURL("OPLink+Configuration");
|
||||
|
||||
addAutoBindings();
|
||||
|
||||
disableMouseWheelEvents();
|
||||
|
||||
connect(this, SIGNAL(connected()), this, SLOT(connected()));
|
||||
|
||||
oplinkStatusObj = dynamic_cast<OPLinkStatus *>(getObject("OPLinkStatus"));
|
||||
Q_ASSERT(oplinkStatusObj);
|
||||
connect(oplinkStatusObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateStatus(UAVObject *)));
|
||||
|
||||
// Connect to the OPLinkSettings object updates
|
||||
oplinkSettingsObj = dynamic_cast<OPLinkSettings *>(objManager->getObject("OPLinkSettings"));
|
||||
oplinkSettingsObj = dynamic_cast<OPLinkSettings *>(getObject("OPLinkSettings"));
|
||||
Q_ASSERT(oplinkSettingsObj);
|
||||
connect(oplinkSettingsObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateSettings(UAVObject *)));
|
||||
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_oplink->Apply->setVisible(false);
|
||||
}
|
||||
addApplySaveButtons(m_oplink->Apply, m_oplink->Save);
|
||||
addWidget(m_oplink->FirmwareVersion);
|
||||
addWidget(m_oplink->SerialNumber);
|
||||
addWidget(m_oplink->MinFreq);
|
||||
addWidget(m_oplink->MaxFreq);
|
||||
addWidget(m_oplink->UnbindButton);
|
||||
addWidget(m_oplink->PairSignalStrengthBar1);
|
||||
addWidget(m_oplink->PairSignalStrengthLabel1);
|
||||
|
||||
addWidgetBinding("OPLinkSettings", "Protocol", m_oplink->Protocol);
|
||||
addWidgetBinding("OPLinkSettings", "LinkType", m_oplink->LinkType);
|
||||
addWidgetBinding("OPLinkSettings", "CoordID", m_oplink->CoordID);
|
||||
addWidgetBinding("OPLinkSettings", "CustomDeviceID", m_oplink->CustomDeviceID);
|
||||
addWidgetBinding("OPLinkSettings", "MinChannel", m_oplink->MinimumChannel);
|
||||
addWidgetBinding("OPLinkSettings", "MaxChannel", m_oplink->MaximumChannel);
|
||||
addWidgetBinding("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
|
||||
addWidgetBinding("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
|
||||
addWidgetBinding("OPLinkSettings", "MainPort", m_oplink->MainPort);
|
||||
addWidgetBinding("OPLinkSettings", "FlexiPort", m_oplink->FlexiPort);
|
||||
addWidgetBinding("OPLinkSettings", "VCPPort", m_oplink->VCPPort);
|
||||
addWidgetBinding("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
|
||||
addWidgetBinding("OPLinkSettings", "MinChannel", m_oplink->MinimumChannel);
|
||||
addWidgetBinding("OPLinkSettings", "MaxChannel", m_oplink->MaximumChannel);
|
||||
addWidgetBinding("OPLinkSettings", "CoordID", m_oplink->CoordID);
|
||||
addWidgetBinding("OPLinkSettings", "Protocol", m_oplink->Protocol);
|
||||
addWidgetBinding("OPLinkSettings", "LinkType", m_oplink->LinkType);
|
||||
addWidgetBinding("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
|
||||
addWidgetBinding("OPLinkSettings", "CustomDeviceID", m_oplink->CustomDeviceID);
|
||||
|
||||
addWidgetBinding("OPLinkStatus", "DeviceID", m_oplink->DeviceID);
|
||||
addWidgetBinding("OPLinkStatus", "RxGood", m_oplink->Good);
|
||||
@ -101,12 +105,14 @@ ConfigOPLinkWidget::ConfigOPLinkWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
addWidgetBinding("OPLinkStatus", "RXPacketRate", m_oplink->RXPacketRate);
|
||||
addWidgetBinding("OPLinkStatus", "TXPacketRate", m_oplink->TXPacketRate);
|
||||
|
||||
// initially hide port combo boxes
|
||||
setPortsVisible(false);
|
||||
|
||||
// Connect the selection changed signals.
|
||||
connect(m_oplink->Protocol, SIGNAL(currentIndexChanged(int)), this, SLOT(protocolChanged()));
|
||||
connect(m_oplink->LinkType, SIGNAL(currentIndexChanged(int)), this, SLOT(linkTypeChanged()));
|
||||
connect(m_oplink->MinimumChannel, SIGNAL(valueChanged(int)), this, SLOT(minChannelChanged()));
|
||||
connect(m_oplink->MaximumChannel, SIGNAL(valueChanged(int)), this, SLOT(maxChannelChanged()));
|
||||
connect(m_oplink->CustomDeviceID, SIGNAL(editingFinished()), this, SLOT(updateCustomDeviceID()));
|
||||
connect(m_oplink->MainPort, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged()));
|
||||
connect(m_oplink->FlexiPort, SIGNAL(currentIndexChanged(int)), this, SLOT(flexiPortChanged()));
|
||||
connect(m_oplink->VCPPort, SIGNAL(currentIndexChanged(int)), this, SLOT(vcpPortChanged()));
|
||||
@ -114,164 +120,144 @@ ConfigOPLinkWidget::ConfigOPLinkWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
// Connect the Unbind button
|
||||
connect(m_oplink->UnbindButton, SIGNAL(released()), this, SLOT(unbind()));
|
||||
|
||||
m_oplink->CustomDeviceID->setInputMask("HHHHHHHH");
|
||||
m_oplink->CoordID->setInputMask("HHHHHHHH");
|
||||
// all upper case hex
|
||||
m_oplink->CustomDeviceID->setInputMask(">HHHHHHHH");
|
||||
m_oplink->CustomDeviceID->setPlaceholderText("AutoGen");
|
||||
|
||||
m_oplink->CoordID->setInputMask(">HHHHHHHH");
|
||||
|
||||
m_oplink->MinimumChannel->setKeyboardTracking(false);
|
||||
m_oplink->MaximumChannel->setKeyboardTracking(false);
|
||||
|
||||
m_oplink->MaximumChannel->setMaximum(MAX_CHANNEL_NUM);
|
||||
m_oplink->MinimumChannel->setMaximum(MAX_CHANNEL_NUM - MIN_CHANNEL_RANGE);
|
||||
|
||||
// Request and update of the setting object.
|
||||
settingsUpdated = false;
|
||||
setWikiURL("OPLink+Configuration");
|
||||
autoLoadWidgets();
|
||||
disableMouseWheelEvents();
|
||||
updateEnableControls();
|
||||
}
|
||||
|
||||
ConfigOPLinkWidget::~ConfigOPLinkWidget()
|
||||
{}
|
||||
|
||||
/*!
|
||||
\brief Called by updates to @OPLinkStatus
|
||||
*/
|
||||
void ConfigOPLinkWidget::updateStatus(UAVObject *object)
|
||||
void ConfigOPLinkWidget::connected()
|
||||
{
|
||||
// qDebug() << "ConfigOPLinkWidget::connected()";
|
||||
statusUpdated = false;
|
||||
|
||||
// Request and update of the setting object if we haven't received it yet.
|
||||
if (!settingsUpdated) {
|
||||
oplinkSettingsObj->requestUpdate();
|
||||
// this is only really needed for OPLM
|
||||
oplinkSettingsObj->requestUpdate();
|
||||
|
||||
updateSettings();
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
// qDebug() << "ConfigOPLinkWidget::refreshWidgetsValuesImpl()" << obj;
|
||||
if (obj == oplinkStatusObj) {
|
||||
updateStatus();
|
||||
} else if (obj == oplinkSettingsObj) {
|
||||
updateSettings();
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::updateStatus()
|
||||
{
|
||||
// qDebug() << "ConfigOPLinkWidget::updateStatus";
|
||||
|
||||
// Update the link state
|
||||
UAVObjectField *linkField = object->getField("LinkState");
|
||||
UAVObjectField *linkField = oplinkStatusObj->getField("LinkState");
|
||||
|
||||
m_oplink->LinkState->setText(linkField->getValue().toString());
|
||||
bool linkConnected = (linkField->getValue() == linkField->getOptions().at(OPLinkStatus::LINKSTATE_CONNECTED));
|
||||
bool linkConnected = (oplinkStatusObj->linkState() == OPLinkStatus_LinkState::Connected);
|
||||
|
||||
m_oplink->PairSignalStrengthBar1->setValue(linkConnected ? m_oplink->RSSI->text().toInt() : -127);
|
||||
m_oplink->PairSignalStrengthLabel1->setText(QString("%1dB").arg(m_oplink->PairSignalStrengthBar1->value()));
|
||||
|
||||
// Enable components based on the board type connected.
|
||||
switch (oplinkStatusObj->boardType()) {
|
||||
case 0x09: // Revolution, DiscoveryF4Bare, RevoNano, RevoProto
|
||||
case 0x92: // Sparky2
|
||||
setPortsVisible(false);
|
||||
break;
|
||||
case 0x03: // OPLinkMini
|
||||
setPortsVisible(true);
|
||||
break;
|
||||
default:
|
||||
// This shouldn't happen.
|
||||
break;
|
||||
}
|
||||
|
||||
if (!statusUpdated) {
|
||||
statusUpdated = true;
|
||||
// update static info
|
||||
updateInfo();
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::setPortsVisible(bool visible)
|
||||
{
|
||||
m_oplink->MainPort->setVisible(visible);
|
||||
m_oplink->MainPortLabel->setVisible(visible);
|
||||
m_oplink->FlexiPort->setVisible(visible);
|
||||
m_oplink->FlexiPortLabel->setVisible(visible);
|
||||
m_oplink->VCPPort->setVisible(visible);
|
||||
m_oplink->VCPPortLabel->setVisible(visible);
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::updateInfo()
|
||||
{
|
||||
// qDebug() << "ConfigOPLinkWidget::updateInfo";
|
||||
|
||||
// Update the Description field
|
||||
// TODO use UAVObjectUtilManager::descriptionToStructure()
|
||||
UAVObjectField *descField = object->getField("Description");
|
||||
if (descField->getValue(0) != QChar(255)) {
|
||||
/*
|
||||
* This looks like a binary with a description at the end:
|
||||
* 4 bytes: header: "OpFw".
|
||||
* 4 bytes: GIT commit tag (short version of SHA1).
|
||||
* 4 bytes: Unix timestamp of compile time.
|
||||
* 2 bytes: target platform. Should follow same rule as BOARD_TYPE and BOARD_REVISION in board define files.
|
||||
* 26 bytes: commit tag if it is there, otherwise branch name. '-dirty' may be added if needed. Zero-padded.
|
||||
* 20 bytes: SHA1 sum of the firmware.
|
||||
* 20 bytes: SHA1 sum of the uavo definitions.
|
||||
* 20 bytes: free for now.
|
||||
*/
|
||||
char buf[OPLinkStatus::DESCRIPTION_NUMELEM];
|
||||
for (unsigned int i = 0; i < 26; ++i) {
|
||||
buf[i] = descField->getValue(i + 14).toChar().toLatin1();
|
||||
}
|
||||
buf[26] = '\0';
|
||||
QString descstr(buf);
|
||||
quint32 gitDate = descField->getValue(11).toChar().toLatin1() & 0xFF;
|
||||
for (int i = 1; i < 4; i++) {
|
||||
gitDate = gitDate << 8;
|
||||
gitDate += descField->getValue(11 - i).toChar().toLatin1() & 0xFF;
|
||||
}
|
||||
QString date = QDateTime::fromTime_t(gitDate).toUTC().toString("yyyy-MM-dd HH:mm");
|
||||
m_oplink->FirmwareVersion->setText(descstr + " " + date);
|
||||
|
||||
// extract desc into byte array
|
||||
OPLinkStatus::DataFields oplinkStatusData = oplinkStatusObj->getData();
|
||||
quint8 *desc = oplinkStatusData.Description;
|
||||
QByteArray ba;
|
||||
|
||||
for (unsigned int i = 0; i < OPLinkStatus::DESCRIPTION_NUMELEM; i++) {
|
||||
ba.append(desc[i]);
|
||||
}
|
||||
|
||||
// parse byte array into device descriptor
|
||||
deviceDescriptorStruct dds;
|
||||
UAVObjectUtilManager::descriptionToStructure(ba, dds);
|
||||
|
||||
// update UI
|
||||
if (!dds.gitTag.isEmpty()) {
|
||||
m_oplink->FirmwareVersion->setText(dds.gitTag + " " + dds.gitDate);
|
||||
} else {
|
||||
m_oplink->FirmwareVersion->setText(tr("Unknown"));
|
||||
}
|
||||
|
||||
// Update the serial number field
|
||||
UAVObjectField *serialField = object->getField("CPUSerial");
|
||||
char buf[OPLinkStatus::CPUSERIAL_NUMELEM * 2 + 1];
|
||||
for (unsigned int i = 0; i < OPLinkStatus::CPUSERIAL_NUMELEM; ++i) {
|
||||
unsigned char val = serialField->getValue(i).toUInt() >> 4;
|
||||
unsigned char val = oplinkStatusObj->cpuSerial(i) >> 4;
|
||||
buf[i * 2] = ((val < 10) ? '0' : '7') + val;
|
||||
val = serialField->getValue(i).toUInt() & 0xf;
|
||||
val = oplinkStatusObj->cpuSerial(i) & 0xf;
|
||||
buf[i * 2 + 1] = ((val < 10) ? '0' : '7') + val;
|
||||
}
|
||||
buf[OPLinkStatus::CPUSERIAL_NUMELEM * 2] = '\0';
|
||||
m_oplink->SerialNumber->setText(buf);
|
||||
|
||||
updateEnableControls();
|
||||
}
|
||||
|
||||
/*!
|
||||
\brief Called by updates to @OPLinkSettings
|
||||
*/
|
||||
void ConfigOPLinkWidget::updateSettings(UAVObject *object)
|
||||
void ConfigOPLinkWidget::updateSettings()
|
||||
{
|
||||
Q_UNUSED(object);
|
||||
// qDebug() << "ConfigOPLinkWidget::updateSettings";
|
||||
|
||||
if (!settingsUpdated) {
|
||||
settingsUpdated = true;
|
||||
// Enable components based on the board type connected.
|
||||
UAVObjectField *board_type_field = oplinkStatusObj->getField("BoardType");
|
||||
switch (board_type_field->getValue().toInt()) {
|
||||
case 0x09: // Revolution, DiscoveryF4Bare, RevoNano, RevoProto
|
||||
case 0x92: // Sparky2
|
||||
m_oplink->MainPort->setVisible(false);
|
||||
m_oplink->MainPortLabel->setVisible(false);
|
||||
m_oplink->FlexiPort->setVisible(false);
|
||||
m_oplink->FlexiPortLabel->setVisible(false);
|
||||
m_oplink->VCPPort->setVisible(false);
|
||||
m_oplink->VCPPortLabel->setVisible(false);
|
||||
m_oplink->LinkType->setEnabled(true);
|
||||
break;
|
||||
case 0x03: // OPLinkMini
|
||||
m_oplink->MainPort->setVisible(true);
|
||||
m_oplink->MainPortLabel->setVisible(true);
|
||||
m_oplink->FlexiPort->setVisible(true);
|
||||
m_oplink->FlexiPortLabel->setVisible(true);
|
||||
m_oplink->VCPPort->setVisible(true);
|
||||
m_oplink->VCPPortLabel->setVisible(true);
|
||||
m_oplink->LinkType->setEnabled(true);
|
||||
break;
|
||||
default:
|
||||
// This shouldn't happen.
|
||||
break;
|
||||
}
|
||||
updateEnableControls();
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::updateEnableControls()
|
||||
{
|
||||
enableControls(true);
|
||||
updateCustomDeviceID();
|
||||
updateCoordID();
|
||||
protocolChanged();
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::disconnected()
|
||||
{
|
||||
if (settingsUpdated) {
|
||||
settingsUpdated = false;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::protocolChanged()
|
||||
{
|
||||
bool is_enabled = !isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_DISABLED);
|
||||
bool is_coordinator = isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_OPLINKCOORDINATOR);
|
||||
bool is_receiver = isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_OPLINKRECEIVER);
|
||||
bool is_openlrs = isComboboxOptionSelected(m_oplink->Protocol, OPLinkSettings::PROTOCOL_OPENLRS);
|
||||
bool is_ppm_only = isComboboxOptionSelected(m_oplink->LinkType, OPLinkSettings::LINKTYPE_CONTROL);
|
||||
bool is_oplm = m_oplink->MainPort->isVisible();
|
||||
bool is_bound = (m_oplink->CoordID->text() != "");
|
||||
|
||||
m_oplink->ComSpeed->setEnabled(!is_ppm_only && !is_openlrs && is_enabled);
|
||||
m_oplink->CoordID->setEnabled(is_receiver & is_enabled);
|
||||
m_oplink->UnbindButton->setEnabled(is_bound && !is_coordinator && is_enabled);
|
||||
m_oplink->ComSpeed->setEnabled(is_enabled && !is_ppm_only && !is_openlrs);
|
||||
m_oplink->CoordID->setEnabled(is_enabled && is_receiver);
|
||||
m_oplink->UnbindButton->setEnabled(is_enabled && is_bound && !is_coordinator);
|
||||
m_oplink->CustomDeviceID->setEnabled(is_coordinator);
|
||||
|
||||
m_oplink->MinimumChannel->setEnabled(is_receiver || is_coordinator);
|
||||
m_oplink->MaximumChannel->setEnabled(is_receiver || is_coordinator);
|
||||
m_oplink->MainPort->setEnabled(is_oplm);
|
||||
m_oplink->FlexiPort->setEnabled(is_oplm);
|
||||
m_oplink->VCPPort->setEnabled(is_oplm);
|
||||
|
||||
enableComboBoxOptionItem(m_oplink->VCPPort, OPLinkSettings::VCPPORT_SERIAL, (is_receiver || is_coordinator));
|
||||
|
||||
@ -283,9 +269,14 @@ void ConfigOPLinkWidget::protocolChanged()
|
||||
m_oplink->MaxRFTxPower->setEnabled(is_enabled && !is_openlrs);
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::protocolChanged()
|
||||
{
|
||||
updateSettings();
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::linkTypeChanged()
|
||||
{
|
||||
protocolChanged();
|
||||
updateSettings();
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::minChannelChanged()
|
||||
@ -395,45 +386,18 @@ void ConfigOPLinkWidget::vcpPortChanged()
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void ConfigOPLinkWidget::updateCoordID()
|
||||
{
|
||||
bool coordinatorNotSet = (m_oplink->CoordID->text() == "0");
|
||||
|
||||
if (settingsUpdated && coordinatorNotSet) {
|
||||
m_oplink->CoordID->clear();
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::updateCustomDeviceID()
|
||||
{
|
||||
bool customDeviceIDNotSet = (m_oplink->CustomDeviceID->text() == "0");
|
||||
|
||||
if (settingsUpdated && customDeviceIDNotSet) {
|
||||
m_oplink->CustomDeviceID->clear();
|
||||
m_oplink->CustomDeviceID->setPlaceholderText("AutoGen");
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigOPLinkWidget::unbind()
|
||||
{
|
||||
if (settingsUpdated) {
|
||||
// Clear the coordinator ID
|
||||
oplinkSettingsObj->getField("CoordID")->setValue(0);
|
||||
m_oplink->CoordID->setText("0");
|
||||
// Clear the coordinator ID
|
||||
oplinkSettingsObj->setCoordID(0);
|
||||
m_oplink->CoordID->clear();
|
||||
|
||||
// Clear the OpenLRS settings
|
||||
oplinkSettingsObj->getField("Version")->setValue(0);
|
||||
oplinkSettingsObj->getField("SerialBaudrate")->setValue(0);
|
||||
oplinkSettingsObj->getField("RFFrequency")->setValue(0);
|
||||
oplinkSettingsObj->getField("RFPower")->setValue(0);
|
||||
oplinkSettingsObj->getField("RFChannelSpacing")->setValue(0);
|
||||
oplinkSettingsObj->getField("ModemParams")->setValue(0);
|
||||
oplinkSettingsObj->getField("Flags")->setValue(0);
|
||||
}
|
||||
// Clear the OpenLRS settings
|
||||
oplinkSettingsObj->setVersion((quint16)0);
|
||||
oplinkSettingsObj->setSerialBaudrate(0);
|
||||
oplinkSettingsObj->setRFFrequency(0);
|
||||
oplinkSettingsObj->setRFPower((quint16)0);
|
||||
oplinkSettingsObj->setRFChannelSpacing((quint16)0);
|
||||
oplinkSettingsObj->setModemParams((quint16)0);
|
||||
oplinkSettingsObj->setFlags((quint16)0);
|
||||
}
|
||||
|
||||
/**
|
||||
@}
|
||||
@}
|
||||
*/
|
||||
|
@ -8,7 +8,7 @@
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief The Configuration Gadget used to configure the OPLink and Revo modem
|
||||
* @brief The Configuration Gadget used to configure the OPLink, Revo and Sparky2 modems
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
@ -30,7 +30,8 @@
|
||||
|
||||
#include "configtaskwidget.h"
|
||||
|
||||
#include "oplinksettings.h"
|
||||
class OPLinkStatus;
|
||||
class OPLinkSettings;
|
||||
|
||||
class Ui_OPLinkWidget;
|
||||
|
||||
@ -41,38 +42,39 @@ public:
|
||||
ConfigOPLinkWidget(QWidget *parent = 0);
|
||||
~ConfigOPLinkWidget();
|
||||
|
||||
public slots:
|
||||
void updateStatus(UAVObject *object1);
|
||||
void updateSettings(UAVObject *object1);
|
||||
protected:
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
|
||||
private:
|
||||
Ui_OPLinkWidget *m_oplink;
|
||||
|
||||
// The OPLink status UAVObject
|
||||
UAVDataObject *oplinkStatusObj;
|
||||
|
||||
// The OPLink ssettins UAVObject
|
||||
OPLinkStatus *oplinkStatusObj;
|
||||
OPLinkSettings *oplinkSettingsObj;
|
||||
|
||||
// Are the settings current?
|
||||
bool settingsUpdated;
|
||||
// Is the status current?
|
||||
bool statusUpdated;
|
||||
|
||||
protected:
|
||||
void updateEnableControls();
|
||||
void updateStatus();
|
||||
void updateInfo();
|
||||
void updateSettings();
|
||||
|
||||
void setPortsVisible(bool visible);
|
||||
|
||||
private slots:
|
||||
void disconnected();
|
||||
void linkTypeChanged();
|
||||
void connected();
|
||||
|
||||
void protocolChanged();
|
||||
void linkTypeChanged();
|
||||
|
||||
void minChannelChanged();
|
||||
void maxChannelChanged();
|
||||
void updateCoordID();
|
||||
void updateCustomDeviceID();
|
||||
void unbind();
|
||||
void channelChanged(bool isMax);
|
||||
|
||||
void mainPortChanged();
|
||||
void flexiPortChanged();
|
||||
void vcpPortChanged();
|
||||
|
||||
void unbind();
|
||||
};
|
||||
|
||||
#endif // CONFIGOPLINKWIDGET_H
|
||||
|
@ -36,7 +36,6 @@
|
||||
|
||||
#include "uavsettingsimportexport/uavsettingsimportexportfactory.h"
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include <uavobjecthelper.h>
|
||||
|
||||
#include "mixersettings.h"
|
||||
@ -50,35 +49,27 @@
|
||||
#include <QStringList>
|
||||
#include <QWidget>
|
||||
#include <QTextEdit>
|
||||
#include <QVBoxLayout>
|
||||
#include <QPushButton>
|
||||
#include <QMessageBox>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
|
||||
ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_ui = new Ui_OutputWidget();
|
||||
m_ui->setupUi(this);
|
||||
|
||||
// must be done before auto binding !
|
||||
setWikiURL("Output+Configuration");
|
||||
|
||||
addAutoBindings();
|
||||
|
||||
m_ui->gvFrame->setVisible(false);
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_ui->saveRCOutputToRAM->setVisible(false);
|
||||
}
|
||||
|
||||
UAVSettingsImportExportFactory *importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
|
||||
connect(importexportplugin, SIGNAL(importAboutToBegin()), this, SLOT(stopTests()));
|
||||
|
||||
connect(m_ui->channelOutTest, SIGNAL(clicked(bool)), this, SLOT(runChannelTests(bool)));
|
||||
|
||||
// Configure the task widget
|
||||
// Connect the help button
|
||||
connect(m_ui->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
addApplySaveButtons(m_ui->saveRCOutputToRAM, m_ui->saveRCOutputToSD);
|
||||
|
||||
// Track the ActuatorSettings object
|
||||
addUAVObject("ActuatorSettings");
|
||||
@ -99,7 +90,6 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
addWidget(form->ui->actuatorLink);
|
||||
}
|
||||
|
||||
|
||||
// Associate the buttons with their UAVO fields
|
||||
addWidget(m_ui->spinningArmed);
|
||||
connect(m_ui->spinningArmed, SIGNAL(clicked(bool)), this, SLOT(updateSpinStabilizeCheckComboBoxes()));
|
||||
@ -137,12 +127,8 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
SystemAlarms *systemAlarmsObj = SystemAlarms::GetInstance(getObjectManager());
|
||||
connect(systemAlarmsObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateWarnings(UAVObject *)));
|
||||
|
||||
// TODO why do we do that ?
|
||||
disconnect(this, SLOT(refreshWidgetsValues(UAVObject *)));
|
||||
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
|
||||
updateEnableControls();
|
||||
}
|
||||
|
||||
ConfigOutputWidget::~ConfigOutputWidget()
|
||||
@ -314,11 +300,9 @@ void ConfigOutputWidget::setColor(QWidget *widget, const QColor color)
|
||||
/**
|
||||
Request the current config from the board (RC Output)
|
||||
*/
|
||||
void ConfigOutputWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
void ConfigOutputWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
bool dirty = isDirty();
|
||||
|
||||
ConfigTaskWidget::refreshWidgetsValues(obj);
|
||||
Q_UNUSED(obj);
|
||||
|
||||
// Get Actuator Settings
|
||||
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
|
||||
@ -422,17 +406,13 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
}
|
||||
|
||||
updateSpinStabilizeCheckComboBoxes();
|
||||
|
||||
setDirty(dirty);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends the config to the board, without saving to the SD card (RC Output)
|
||||
*/
|
||||
void ConfigOutputWidget::updateObjectsFromWidgets()
|
||||
void ConfigOutputWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
|
||||
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
|
||||
|
||||
Q_ASSERT(actuatorSettings);
|
||||
@ -500,12 +480,6 @@ void ConfigOutputWidget::updateAlwaysStabilizeStatus()
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigOutputWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Output+Configuration"),
|
||||
QUrl::StrictMode));
|
||||
}
|
||||
|
||||
void ConfigOutputWidget::onBankTypeChange()
|
||||
{
|
||||
QComboBox *bankModeCombo = qobject_cast<QComboBox *>(sender());
|
||||
|
@ -89,6 +89,9 @@ protected:
|
||||
void enableControls(bool enable);
|
||||
void setWarning(QString message);
|
||||
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private:
|
||||
Ui_OutputWidget *m_ui;
|
||||
QList<QSlider> m_sliders;
|
||||
@ -107,11 +110,8 @@ private slots:
|
||||
void updateSpinStabilizeCheckComboBoxes();
|
||||
void updateAlwaysStabilizeStatus();
|
||||
void stopTests();
|
||||
virtual void refreshWidgetsValues(UAVObject *obj = NULL);
|
||||
void updateObjectsFromWidgets();
|
||||
void runChannelTests(bool state);
|
||||
void sendChannelTest(int index, int value);
|
||||
void openHelp();
|
||||
void onBankTypeChange();
|
||||
};
|
||||
|
||||
|
@ -1,8 +1,9 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configplugin.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @file configplugin.cpp
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
@ -25,12 +26,15 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "configplugin.h"
|
||||
|
||||
#include "configgadgetfactory.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <uavobjects/uavobjectmanager.h>
|
||||
|
||||
#include <QtPlugin>
|
||||
#include <QStringList>
|
||||
#include <QTimer>
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include "objectpersistence.h"
|
||||
|
||||
ConfigPlugin::ConfigPlugin()
|
||||
{
|
||||
@ -46,7 +50,8 @@ bool ConfigPlugin::initialize(const QStringList & args, QString *errMsg)
|
||||
{
|
||||
Q_UNUSED(args);
|
||||
Q_UNUSED(errMsg);
|
||||
cf = new ConfigGadgetFactory(this);
|
||||
|
||||
ConfigGadgetFactory *cf = new ConfigGadgetFactory(this);
|
||||
addAutoReleasedObject(cf);
|
||||
|
||||
return true;
|
||||
|
@ -1,8 +1,9 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configgadgetplugin.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @file configplugin.h
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
@ -28,14 +29,11 @@
|
||||
#define CONFIGPLUGIN_H
|
||||
|
||||
#include <extensionsystem/iplugin.h>
|
||||
#include <coreplugin/icore.h>
|
||||
#include <coreplugin/coreconstants.h>
|
||||
#include <coreplugin/actionmanager/actionmanager.h>
|
||||
#include "objectpersistence.h"
|
||||
|
||||
#include <QMessageBox>
|
||||
#include <QString>
|
||||
#include <QStringList>
|
||||
|
||||
class ConfigGadgetFactory;
|
||||
class UAVObjectManager;
|
||||
|
||||
class ConfigPlugin : public ExtensionSystem::IPlugin {
|
||||
Q_OBJECT
|
||||
@ -49,9 +47,6 @@ public:
|
||||
void extensionsInitialized();
|
||||
bool initialize(const QStringList & arguments, QString *errorString);
|
||||
void shutdown();
|
||||
|
||||
private:
|
||||
ConfigGadgetFactory *cf;
|
||||
};
|
||||
|
||||
#endif // CONFIGPLUGIN_H
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configrevohwwidget.cpp
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
@ -29,30 +29,21 @@
|
||||
|
||||
#include "ui_configrevohwwidget.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include <uavobjecthelper.h>
|
||||
|
||||
#include "hwsettings.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <QMessageBox>
|
||||
|
||||
ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(parent), m_refreshing(true)
|
||||
ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_ui = new Ui_RevoHWWidget();
|
||||
m_ui->setupUi(this);
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_ui->saveTelemetryToRAM->setEnabled(false);
|
||||
m_ui->saveTelemetryToRAM->setVisible(false);
|
||||
}
|
||||
// must be done before auto binding !
|
||||
setWikiURL("Revolution+Configuration");
|
||||
|
||||
addApplySaveButtons(m_ui->saveTelemetryToRAM, m_ui->saveTelemetryToSD);
|
||||
addAutoBindings();
|
||||
|
||||
addUAVObject("HwSettings");
|
||||
|
||||
addWidgetBinding("HwSettings", "RM_FlexiPort", m_ui->cbFlexi);
|
||||
addWidgetBinding("HwSettings", "RM_MainPort", m_ui->cbMain);
|
||||
@ -75,14 +66,7 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbRcvrGPSProtocol);
|
||||
|
||||
connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
setupCustomCombos();
|
||||
enableControls(true);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
forceConnectedState();
|
||||
m_refreshing = false;
|
||||
}
|
||||
|
||||
ConfigRevoHWWidget::~ConfigRevoHWWidget()
|
||||
@ -104,37 +88,29 @@ void ConfigRevoHWWidget::setupCustomCombos()
|
||||
connect(m_ui->cbRcvr, SIGNAL(currentIndexChanged(int)), this, SLOT(rcvrPortChanged(int)));
|
||||
}
|
||||
|
||||
void ConfigRevoHWWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
void ConfigRevoHWWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
m_refreshing = true;
|
||||
ConfigTaskWidget::refreshWidgetsValues(obj);
|
||||
Q_UNUSED(obj);
|
||||
|
||||
usbVCPPortChanged(0);
|
||||
mainPortChanged(0);
|
||||
flexiPortChanged(0);
|
||||
rcvrPortChanged(0);
|
||||
m_refreshing = false;
|
||||
}
|
||||
|
||||
void ConfigRevoHWWidget::updateObjectsFromWidgets()
|
||||
void ConfigRevoHWWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields data = hwSettings->getData();
|
||||
|
||||
// If any port is configured to be GPS port, enable GPS module if it is not enabled.
|
||||
// Otherwise disable GPS module.
|
||||
quint8 enableModule = HwSettings::OPTIONALMODULES_DISABLED;
|
||||
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)
|
||||
|| isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
|
||||
data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_ENABLED;
|
||||
} else {
|
||||
data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED;
|
||||
enableModule = HwSettings::OPTIONALMODULES_ENABLED;
|
||||
}
|
||||
|
||||
UAVObjectUpdaterHelper updateHelper;
|
||||
hwSettings->setData(data, false);
|
||||
updateHelper.doObjectAndWait(hwSettings);
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_GPS, enableModule);
|
||||
}
|
||||
|
||||
void ConfigRevoHWWidget::usbVCPPortChanged(int index)
|
||||
@ -488,9 +464,3 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index)
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigRevoHWWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Revolution+Configuration"),
|
||||
QUrl::StrictMode));
|
||||
}
|
||||
|
@ -2,7 +2,8 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configrevohwwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
@ -42,14 +43,14 @@ public:
|
||||
ConfigRevoHWWidget(QWidget *parent = 0);
|
||||
~ConfigRevoHWWidget();
|
||||
|
||||
protected:
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private:
|
||||
Ui_RevoHWWidget *m_ui;
|
||||
bool m_refreshing;
|
||||
void setupCustomCombos();
|
||||
|
||||
protected slots:
|
||||
void refreshWidgetsValues(UAVObject *obj = NULL);
|
||||
void updateObjectsFromWidgets();
|
||||
void setupCustomCombos();
|
||||
|
||||
private slots:
|
||||
void usbVCPPortChanged(int index);
|
||||
@ -57,7 +58,6 @@ private slots:
|
||||
void flexiPortChanged(int index);
|
||||
void mainPortChanged(int index);
|
||||
void rcvrPortChanged(int index);
|
||||
void openHelp();
|
||||
};
|
||||
|
||||
#endif // CONFIGREVOHWWIDGET_H
|
||||
|
@ -121,9 +121,9 @@
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>-148</y>
|
||||
<y>0</y>
|
||||
<width>796</width>
|
||||
<height>804</height>
|
||||
<height>807</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
@ -548,7 +548,7 @@
|
||||
<string/>
|
||||
</property>
|
||||
<property name="pixmap">
|
||||
<pixmap resource="configgadget.qrc">:/configgadget/images/revolution_top.png</pixmap>
|
||||
<pixmap>:/configgadget/images/revolution_top.png</pixmap>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>false</bool>
|
||||
@ -739,7 +739,7 @@
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="cchwHelp">
|
||||
<widget class="QPushButton" name="helpButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -777,10 +777,13 @@
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:help</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToRAM">
|
||||
<widget class="QPushButton" name="applyButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -879,10 +882,13 @@ Beware of not locking yourself out!</string>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToSD">
|
||||
<widget class="QPushButton" name="saveButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -908,6 +914,9 @@ Beware of not locking yourself out!</string>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
|
@ -1,14 +1,14 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configrevohwwidget.cpp
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* @file configrevonanohwwidget.cpp
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Revolution hardware configuration panel
|
||||
* @brief Revolution Nano hardware configuration panel
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
@ -29,32 +29,21 @@
|
||||
|
||||
#include "ui_configrevonanohwwidget.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include <uavobjecthelper.h>
|
||||
|
||||
#include "hwsettings.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <QMessageBox>
|
||||
|
||||
ConfigRevoNanoHWWidget::ConfigRevoNanoHWWidget(QWidget *parent) : ConfigTaskWidget(parent), m_refreshing(true)
|
||||
ConfigRevoNanoHWWidget::ConfigRevoNanoHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_ui = new Ui_RevoNanoHWWidget();
|
||||
m_ui->setupUi(this);
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_ui->saveTelemetryToRAM->setEnabled(false);
|
||||
m_ui->saveTelemetryToRAM->setVisible(false);
|
||||
}
|
||||
// must be done before auto binding !
|
||||
setWikiURL("Revo+Nano+Configuration");
|
||||
|
||||
addApplySaveButtons(m_ui->saveTelemetryToRAM, m_ui->saveTelemetryToSD);
|
||||
addAutoBindings();
|
||||
|
||||
forceConnectedState();
|
||||
addUAVObject("HwSettings");
|
||||
|
||||
addWidgetBinding("HwSettings", "RM_FlexiPort", m_ui->cbFlexi);
|
||||
addWidgetBinding("HwSettings", "RM_MainPort", m_ui->cbMain);
|
||||
@ -73,13 +62,7 @@ ConfigRevoNanoHWWidget::ConfigRevoNanoHWWidget(QWidget *parent) : ConfigTaskWidg
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
|
||||
|
||||
connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
setupCustomCombos();
|
||||
enableControls(true);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
setDirty(false);
|
||||
m_refreshing = false;
|
||||
}
|
||||
|
||||
ConfigRevoNanoHWWidget::~ConfigRevoNanoHWWidget()
|
||||
@ -97,37 +80,29 @@ void ConfigRevoNanoHWWidget::setupCustomCombos()
|
||||
connect(m_ui->cbRcvr, SIGNAL(currentIndexChanged(int)), this, SLOT(rcvrPortChanged(int)));
|
||||
}
|
||||
|
||||
void ConfigRevoNanoHWWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
void ConfigRevoNanoHWWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
m_refreshing = true;
|
||||
ConfigTaskWidget::refreshWidgetsValues(obj);
|
||||
Q_UNUSED(obj);
|
||||
|
||||
usbVCPPortChanged(0);
|
||||
mainPortChanged(0);
|
||||
flexiPortChanged(0);
|
||||
rcvrPortChanged(0);
|
||||
m_refreshing = false;
|
||||
}
|
||||
|
||||
void ConfigRevoNanoHWWidget::updateObjectsFromWidgets()
|
||||
void ConfigRevoNanoHWWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields data = hwSettings->getData();
|
||||
|
||||
// If any port is configured to be GPS port, enable GPS module if it is not enabled.
|
||||
// Otherwise disable GPS module.
|
||||
quint8 enableModule = HwSettings::OPTIONALMODULES_DISABLED;
|
||||
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)
|
||||
|| isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
|
||||
data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_ENABLED;
|
||||
} else {
|
||||
data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED;
|
||||
enableModule = HwSettings::OPTIONALMODULES_ENABLED;
|
||||
}
|
||||
|
||||
UAVObjectUpdaterHelper updateHelper;
|
||||
hwSettings->setData(data, false);
|
||||
updateHelper.doObjectAndWait(hwSettings);
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_GPS, enableModule);
|
||||
}
|
||||
|
||||
void ConfigRevoNanoHWWidget::usbVCPPortChanged(int index)
|
||||
@ -279,9 +254,3 @@ void ConfigRevoNanoHWWidget::rcvrPortChanged(int index)
|
||||
Q_UNUSED(index);
|
||||
/* Nano has no USART at rcvrPort */
|
||||
}
|
||||
|
||||
void ConfigRevoNanoHWWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Revo+Nano+Configuration"),
|
||||
QUrl::StrictMode));
|
||||
}
|
||||
|
@ -1,8 +1,9 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configrevohwwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @file configrevonanohwwidget.h
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
@ -42,14 +43,14 @@ public:
|
||||
ConfigRevoNanoHWWidget(QWidget *parent = 0);
|
||||
~ConfigRevoNanoHWWidget();
|
||||
|
||||
protected:
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private:
|
||||
Ui_RevoNanoHWWidget *m_ui;
|
||||
bool m_refreshing;
|
||||
void setupCustomCombos();
|
||||
|
||||
protected slots:
|
||||
void refreshWidgetsValues(UAVObject *obj = NULL);
|
||||
void updateObjectsFromWidgets();
|
||||
void setupCustomCombos();
|
||||
|
||||
private slots:
|
||||
void usbVCPPortChanged(int index);
|
||||
@ -57,7 +58,6 @@ private slots:
|
||||
void flexiPortChanged(int index);
|
||||
void mainPortChanged(int index);
|
||||
void rcvrPortChanged(int index);
|
||||
void openHelp();
|
||||
};
|
||||
|
||||
#endif // CONFIGREVONANOHWWIDGET_H
|
||||
|
@ -254,7 +254,7 @@
|
||||
<string/>
|
||||
</property>
|
||||
<property name="pixmap">
|
||||
<pixmap resource="configgadget.qrc">:/configgadget/images/nano_top.png</pixmap>
|
||||
<pixmap>:/configgadget/images/nano_top.png</pixmap>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>false</bool>
|
||||
@ -459,7 +459,7 @@
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="cchwHelp">
|
||||
<widget class="QPushButton" name="helpButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -497,10 +497,13 @@
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:help</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToRAM">
|
||||
<widget class="QPushButton" name="applyButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -599,10 +602,13 @@ Beware of not locking yourself out!</string>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToSD">
|
||||
<widget class="QPushButton" name="saveButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -628,6 +634,9 @@ Beware of not locking yourself out!</string>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
|
@ -1,7 +1,7 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file ConfigRevoWidget.h
|
||||
* @file configrevowidget.cpp
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
@ -29,7 +29,9 @@
|
||||
|
||||
#include "ui_revosensors.h"
|
||||
|
||||
#include <uavobjectmanager.h>
|
||||
#include <uavobjecthelper.h>
|
||||
|
||||
#include <attitudestate.h>
|
||||
#include <attitudesettings.h>
|
||||
#include <revocalibration.h>
|
||||
@ -38,29 +40,17 @@
|
||||
#include <accelstate.h>
|
||||
#include <magstate.h>
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
|
||||
#include "assertions.h"
|
||||
#include "calibration.h"
|
||||
#include "calibration/calibrationutils.h"
|
||||
|
||||
#include "math.h"
|
||||
#include <QDebug>
|
||||
#include <QTimer>
|
||||
#include <QStringList>
|
||||
#include <QWidget>
|
||||
#include <QTextEdit>
|
||||
#include <QVBoxLayout>
|
||||
#include <QPushButton>
|
||||
#include <QMessageBox>
|
||||
#include <QThread>
|
||||
#include <QErrorMessage>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <math.h>
|
||||
#include <iostream>
|
||||
|
||||
#include <math.h>
|
||||
#include <QDebug>
|
||||
#include <QStringList>
|
||||
#include <QWidget>
|
||||
#include <QThread>
|
||||
|
||||
// #define DEBUG
|
||||
|
||||
@ -78,20 +68,16 @@ public:
|
||||
};
|
||||
|
||||
ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
|
||||
ConfigTaskWidget(parent),
|
||||
m_ui(new Ui_RevoSensorsWidget()),
|
||||
isBoardRotationStored(false)
|
||||
ConfigTaskWidget(parent), isBoardRotationStored(false)
|
||||
{
|
||||
m_ui = new Ui_RevoSensorsWidget();
|
||||
m_ui->setupUi(this);
|
||||
m_ui->tabWidget->setCurrentIndex(0);
|
||||
|
||||
addApplySaveButtons(m_ui->revoCalSettingsSaveRAM, m_ui->revoCalSettingsSaveSD);
|
||||
// must be done before auto binding !
|
||||
setWikiURL("Revo+Attitude+Configuration");
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_ui->revoCalSettingsSaveRAM->setVisible(false);
|
||||
}
|
||||
addAutoBindings();
|
||||
|
||||
// Initialization of the visual help
|
||||
m_ui->calibrationVisualHelp->setScene(new QGraphicsScene(this));
|
||||
@ -108,7 +94,6 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
|
||||
addUAVObject("RevoSettings");
|
||||
addUAVObject("AccelGyroSettings");
|
||||
addUAVObject("AuxMagSettings");
|
||||
autoLoadWidgets();
|
||||
|
||||
// accel calibration
|
||||
m_accelCalibrationModel = new OpenPilot::SixPointCalibrationModel(this);
|
||||
@ -223,16 +208,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
|
||||
|
||||
displayMagError = false;
|
||||
|
||||
// Connect the help button
|
||||
connect(m_ui->attitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
populateWidgets();
|
||||
enableAllCalibrations();
|
||||
|
||||
updateEnableControls();
|
||||
|
||||
forceConnectedState();
|
||||
refreshWidgetsValues();
|
||||
}
|
||||
|
||||
ConfigRevoWidget::~ConfigRevoWidget()
|
||||
@ -414,9 +390,9 @@ void ConfigRevoWidget::displayTemperatureRange(float temperatureRange)
|
||||
* Called by the ConfigTaskWidget parent when RevoCalibration is updated
|
||||
* to update the UI
|
||||
*/
|
||||
void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object)
|
||||
void ConfigRevoWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
ConfigTaskWidget::refreshWidgetsValues(object);
|
||||
Q_UNUSED(obj);
|
||||
|
||||
m_ui->isSetCheckBox->setEnabled(false);
|
||||
|
||||
@ -431,10 +407,8 @@ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object)
|
||||
onBoardAuxMagError();
|
||||
}
|
||||
|
||||
void ConfigRevoWidget::updateObjectsFromWidgets()
|
||||
void ConfigRevoWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
|
||||
if (m_accelCalibrationModel->dirty()) {
|
||||
m_accelCalibrationModel->save();
|
||||
}
|
||||
@ -714,9 +688,3 @@ void ConfigRevoWidget::updateMagStatus()
|
||||
m_ui->magStatusSource->setToolTip("");
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigRevoWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Revo+Attitude+Configuration"),
|
||||
QUrl::StrictMode));
|
||||
}
|
||||
|
@ -1,8 +1,9 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configahrstwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @file configrevowidget.h
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
@ -28,8 +29,7 @@
|
||||
#define CONFIGREVOWIDGET_H
|
||||
|
||||
#include "configtaskwidget.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
#include "uavobject.h"
|
||||
|
||||
#include "calibration/thermal/thermalcalibrationmodel.h"
|
||||
@ -48,6 +48,10 @@ public:
|
||||
ConfigRevoWidget(QWidget *parent = 0);
|
||||
~ConfigRevoWidget();
|
||||
|
||||
protected:
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private:
|
||||
OpenPilot::SixPointCalibrationModel *m_accelCalibrationModel;
|
||||
OpenPilot::SixPointCalibrationModel *m_magCalibrationModel;
|
||||
@ -83,10 +87,6 @@ private slots:
|
||||
void displayTemperatureGradient(float temparetureGradient);
|
||||
void displayTemperatureRange(float temparetureRange);
|
||||
|
||||
// ! Overriden method from the configTaskWidget to update UI
|
||||
virtual void refreshWidgetsValues(UAVObject *object = NULL);
|
||||
virtual void updateObjectsFromWidgets();
|
||||
|
||||
// Slot for clearing home location
|
||||
void clearHomeLocation();
|
||||
|
||||
@ -101,7 +101,6 @@ private slots:
|
||||
float getMagError(float mag[3]);
|
||||
|
||||
void updateVisualHelp();
|
||||
void openHelp();
|
||||
|
||||
protected:
|
||||
void showEvent(QShowEvent *event);
|
||||
|
@ -29,30 +29,21 @@
|
||||
|
||||
#include "ui_configsparky2hwwidget.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include <uavobjecthelper.h>
|
||||
|
||||
#include "hwsettings.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <QMessageBox>
|
||||
|
||||
ConfigSparky2HWWidget::ConfigSparky2HWWidget(QWidget *parent) : ConfigTaskWidget(parent), m_refreshing(true)
|
||||
ConfigSparky2HWWidget::ConfigSparky2HWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_ui = new Ui_Sparky2HWWidget();
|
||||
m_ui->setupUi(this);
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_ui->saveTelemetryToRAM->setEnabled(false);
|
||||
m_ui->saveTelemetryToRAM->setVisible(false);
|
||||
}
|
||||
// must be done before auto binding !
|
||||
setWikiURL("Sparky2+Configuration");
|
||||
|
||||
addApplySaveButtons(m_ui->saveTelemetryToRAM, m_ui->saveTelemetryToSD);
|
||||
addAutoBindings();
|
||||
|
||||
addUAVObject("HwSettings");
|
||||
|
||||
addWidgetBinding("HwSettings", "SPK2_FlexiPort", m_ui->cbFlexi);
|
||||
addWidgetBinding("HwSettings", "SPK2_MainPort", m_ui->cbMain);
|
||||
@ -72,14 +63,7 @@ ConfigSparky2HWWidget::ConfigSparky2HWWidget(QWidget *parent) : ConfigTaskWidget
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
|
||||
|
||||
connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
setupCustomCombos();
|
||||
enableControls(true);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
forceConnectedState();
|
||||
m_refreshing = false;
|
||||
}
|
||||
|
||||
ConfigSparky2HWWidget::~ConfigSparky2HWWidget()
|
||||
@ -100,36 +84,28 @@ void ConfigSparky2HWWidget::setupCustomCombos()
|
||||
connect(m_ui->cbMain, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged(int)));
|
||||
}
|
||||
|
||||
void ConfigSparky2HWWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
void ConfigSparky2HWWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
m_refreshing = true;
|
||||
ConfigTaskWidget::refreshWidgetsValues(obj);
|
||||
Q_UNUSED(obj);
|
||||
|
||||
usbVCPPortChanged(0);
|
||||
mainPortChanged(0);
|
||||
flexiPortChanged(0);
|
||||
m_refreshing = false;
|
||||
}
|
||||
|
||||
void ConfigSparky2HWWidget::updateObjectsFromWidgets()
|
||||
void ConfigSparky2HWWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields data = hwSettings->getData();
|
||||
|
||||
// If any port is configured to be GPS port, enable GPS module if it is not enabled.
|
||||
// Otherwise disable GPS module.
|
||||
quint8 enableModule = HwSettings::OPTIONALMODULES_DISABLED;
|
||||
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::SPK2_FLEXIPORT_GPS)
|
||||
|| isComboboxOptionSelected(m_ui->cbMain, HwSettings::SPK2_MAINPORT_GPS)) {
|
||||
data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_ENABLED;
|
||||
} else {
|
||||
data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED;
|
||||
enableModule = HwSettings::OPTIONALMODULES_ENABLED;
|
||||
}
|
||||
|
||||
UAVObjectUpdaterHelper updateHelper;
|
||||
hwSettings->setData(data, false);
|
||||
updateHelper.doObjectAndWait(hwSettings);
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_GPS, enableModule);
|
||||
}
|
||||
|
||||
void ConfigSparky2HWWidget::usbVCPPortChanged(int index)
|
||||
@ -275,9 +251,3 @@ void ConfigSparky2HWWidget::mainPortChanged(int index)
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigSparky2HWWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Sparky2+Configuration"),
|
||||
QUrl::StrictMode));
|
||||
}
|
||||
|
@ -43,21 +43,20 @@ public:
|
||||
ConfigSparky2HWWidget(QWidget *parent = 0);
|
||||
~ConfigSparky2HWWidget();
|
||||
|
||||
protected:
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private:
|
||||
Ui_Sparky2HWWidget *m_ui;
|
||||
bool m_refreshing;
|
||||
void setupCustomCombos();
|
||||
|
||||
protected slots:
|
||||
void refreshWidgetsValues(UAVObject *obj = NULL);
|
||||
void updateObjectsFromWidgets();
|
||||
void setupCustomCombos();
|
||||
|
||||
private slots:
|
||||
void usbVCPPortChanged(int index);
|
||||
void usbHIDPortChanged(int index);
|
||||
void flexiPortChanged(int index);
|
||||
void mainPortChanged(int index);
|
||||
void openHelp();
|
||||
};
|
||||
|
||||
#endif // CONFIGSPARKY2HWWIDGET_H
|
||||
|
@ -121,9 +121,9 @@
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>-258</y>
|
||||
<width>794</width>
|
||||
<height>927</height>
|
||||
<y>0</y>
|
||||
<width>796</width>
|
||||
<height>731</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
@ -434,7 +434,7 @@
|
||||
<string/>
|
||||
</property>
|
||||
<property name="pixmap">
|
||||
<pixmap resource="configgadget.qrc">:/configgadget/images/sparky2_top.png</pixmap>
|
||||
<pixmap>:/configgadget/images/sparky2_top.png</pixmap>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>false</bool>
|
||||
@ -555,7 +555,7 @@
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="cchwHelp">
|
||||
<widget class="QPushButton" name="helpButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -593,10 +593,13 @@
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:help</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToRAM">
|
||||
<widget class="QPushButton" name="applyButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -695,10 +698,13 @@ Beware of not locking yourself out!</string>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToSD">
|
||||
<widget class="QPushButton" name="saveButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
@ -724,6 +730,9 @@ Beware of not locking yourself out!</string>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<string notr="true">button:save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configstabilizationwidget.cpp
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
@ -29,11 +29,9 @@
|
||||
|
||||
#include "ui_stabilization.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include "uavobjectutilmanager.h"
|
||||
|
||||
#include <uavobjectmanager.h>
|
||||
#include "objectpersistence.h"
|
||||
|
||||
#include "altitudeholdsettings.h"
|
||||
#include "stabilizationsettings.h"
|
||||
|
||||
@ -45,38 +43,30 @@
|
||||
#include <QDebug>
|
||||
#include <QStringList>
|
||||
#include <QWidget>
|
||||
#include <QTextEdit>
|
||||
#include <QVBoxLayout>
|
||||
#include <QPushButton>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <QList>
|
||||
#include <QTabBar>
|
||||
#include <QMessageBox>
|
||||
#include <QToolButton>
|
||||
#include <QMenu>
|
||||
#include <QAction>
|
||||
|
||||
ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent),
|
||||
boardModel(0), m_stabSettingsBankCount(0), m_currentStabSettingsBank(0)
|
||||
m_stabSettingsBankCount(0), m_currentStabSettingsBank(0)
|
||||
{
|
||||
ui = new Ui_StabilizationWidget();
|
||||
ui->setupUi(this);
|
||||
|
||||
// must be done before auto binding !
|
||||
setWikiURL("Stabilization+Configuration");
|
||||
|
||||
setupExpoPlot();
|
||||
|
||||
setupStabBanksGUI();
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
addAutoBindings();
|
||||
|
||||
if (!settings->useExpertMode()) {
|
||||
ui->saveStabilizationToRAM_6->setVisible(false);
|
||||
}
|
||||
disableMouseWheelEvents();
|
||||
|
||||
autoLoadWidgets();
|
||||
connect(this, SIGNAL(enableControlsChanged(bool)), this, SLOT(enableControlsChanged(bool)));
|
||||
|
||||
setupExpoPlot();
|
||||
|
||||
realtimeUpdates = new QTimer(this);
|
||||
connect(realtimeUpdates, SIGNAL(timeout()), this, SLOT(apply()));
|
||||
@ -116,12 +106,13 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
|
||||
addWidget(ui->pushButton_13);
|
||||
addWidget(ui->pushButton_14);
|
||||
addWidget(ui->pushButton_20);
|
||||
addWidget(ui->pushButton_21);
|
||||
addWidget(ui->pushButton_22);
|
||||
addWidget(ui->pushButton_23);
|
||||
|
||||
addWidget(ui->basicResponsivenessGroupBox);
|
||||
addWidget(ui->basicResponsivenessCheckBox);
|
||||
connect(ui->basicResponsivenessCheckBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
|
||||
|
||||
addWidget(ui->advancedResponsivenessGroupBox);
|
||||
addWidget(ui->advancedResponsivenessCheckBox);
|
||||
connect(ui->advancedResponsivenessCheckBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
|
||||
@ -144,15 +135,12 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
|
||||
addWidget(ui->thrustPIDScalingCurve);
|
||||
connect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *)));
|
||||
|
||||
connect(this, SIGNAL(autoPilotConnected()), this, SLOT(onBoardConnected()));
|
||||
|
||||
addWidget(ui->expoPlot);
|
||||
connect(ui->expoSpinnerRoll, SIGNAL(valueChanged(int)), this, SLOT(replotExpoRoll(int)));
|
||||
connect(ui->expoSpinnerPitch, SIGNAL(valueChanged(int)), this, SLOT(replotExpoPitch(int)));
|
||||
connect(ui->expoSpinnerYaw, SIGNAL(valueChanged(int)), this, SLOT(replotExpoYaw(int)));
|
||||
|
||||
disableMouseWheelEvents();
|
||||
updateEnableControls();
|
||||
ui->AltitudeHold->setEnabled(false);
|
||||
}
|
||||
|
||||
void ConfigStabilizationWidget::setupStabBanksGUI()
|
||||
@ -247,9 +235,9 @@ ConfigStabilizationWidget::~ConfigStabilizationWidget()
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void ConfigStabilizationWidget::refreshWidgetsValues(UAVObject *o)
|
||||
void ConfigStabilizationWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
ConfigTaskWidget::refreshWidgetsValues(o);
|
||||
Q_UNUSED(obj);
|
||||
|
||||
updateThrottleCurveFromObject();
|
||||
|
||||
@ -269,10 +257,9 @@ void ConfigStabilizationWidget::refreshWidgetsValues(UAVObject *o)
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigStabilizationWidget::updateObjectsFromWidgets()
|
||||
void ConfigStabilizationWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
updateObjectFromThrottleCurve();
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
}
|
||||
|
||||
void ConfigStabilizationWidget::updateThrottleCurveFromObject()
|
||||
@ -647,15 +634,12 @@ void ConfigStabilizationWidget::processLinkedWidgets(QWidget *widget)
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigStabilizationWidget::onBoardConnected()
|
||||
void ConfigStabilizationWidget::enableControlsChanged(bool enable)
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
|
||||
Q_ASSERT(utilMngr);
|
||||
boardModel = utilMngr->getBoardModel();
|
||||
// If Revolution/Sparky2 board enable Althold tab, otherwise disable it
|
||||
ui->AltitudeHold->setEnabled(((boardModel & 0xff00) == 0x0900) || ((boardModel & 0xff00) == 0x9200));
|
||||
bool enableAltitudeHold = (((boardModel() & 0xff00) == 0x0900) || ((boardModel() & 0xff00) == 0x9200));
|
||||
|
||||
ui->AltitudeHold->setEnabled(enable && enableAltitudeHold);
|
||||
}
|
||||
|
||||
void ConfigStabilizationWidget::stabBankChanged(int index)
|
||||
@ -687,7 +671,7 @@ void ConfigStabilizationWidget::stabBankChanged(int index)
|
||||
bool ConfigStabilizationWidget::shouldObjectBeSaved(UAVObject *object)
|
||||
{
|
||||
// AltitudeHoldSettings should only be saved for Revolution/Sparky2 board to avoid error.
|
||||
if (((boardModel & 0xff00) != 0x0900) && ((boardModel & 0xff00) != 0x9200)) {
|
||||
if (((boardModel() & 0xff00) != 0x0900) && ((boardModel() & 0xff00) != 0x9200)) {
|
||||
return dynamic_cast<AltitudeHoldSettings *>(object) == 0;
|
||||
} else {
|
||||
return true;
|
||||
|
@ -2,7 +2,8 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configstabilizationwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
@ -28,11 +29,8 @@
|
||||
#define CONFIGSTABILIZATIONWIDGET_H
|
||||
|
||||
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavobject.h"
|
||||
|
||||
#include "stabilizationsettings.h"
|
||||
#include "uavobject.h"
|
||||
|
||||
#include "qwt/src/qwt_plot_curve.h"
|
||||
#include "qwt/src/qwt_plot_grid.h"
|
||||
@ -51,8 +49,15 @@ class ConfigStabilizationWidget : public ConfigTaskWidget {
|
||||
public:
|
||||
ConfigStabilizationWidget(QWidget *parent = 0);
|
||||
~ConfigStabilizationWidget();
|
||||
|
||||
bool shouldObjectBeSaved(UAVObject *object);
|
||||
|
||||
protected:
|
||||
QString mapObjectName(const QString objectName);
|
||||
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private:
|
||||
Ui_StabilizationWidget *ui;
|
||||
QTimer *realtimeUpdates;
|
||||
@ -65,7 +70,6 @@ private:
|
||||
static const int EXPO_CURVE_POINTS_COUNT = 100;
|
||||
constexpr static const double EXPO_CURVE_CONSTANT = 1.01395948;
|
||||
|
||||
int boardModel;
|
||||
int m_stabSettingsBankCount;
|
||||
int m_currentStabSettingsBank;
|
||||
|
||||
@ -86,18 +90,12 @@ private:
|
||||
void resetStabBank(int bank);
|
||||
void restoreStabBank(int bank);
|
||||
|
||||
protected:
|
||||
QString mapObjectName(const QString objectName);
|
||||
|
||||
protected slots:
|
||||
void refreshWidgetsValues(UAVObject *o = NULL);
|
||||
void updateObjectsFromWidgets();
|
||||
|
||||
private slots:
|
||||
void enableControlsChanged(bool enable);
|
||||
|
||||
void realtimeUpdatesSlot(bool value);
|
||||
void linkCheckBoxes(bool value);
|
||||
void processLinkedWidgets(QWidget *);
|
||||
void onBoardConnected();
|
||||
void stabBankChanged(int index);
|
||||
void resetThrottleCurveToDefault();
|
||||
void throttleCurveUpdated();
|
||||
|
@ -30,9 +30,6 @@
|
||||
|
||||
#include "ui_txpid.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
|
||||
#include "txpidsettings.h"
|
||||
#include "hwsettings.h"
|
||||
#include "attitudesettings.h"
|
||||
@ -46,25 +43,14 @@ ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
m_txpid = new Ui_TxPIDWidget();
|
||||
m_txpid->setupUi(this);
|
||||
|
||||
// must be done before auto binding !
|
||||
setWikiURL("TxPID");
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_txpid->Apply->setVisible(false);
|
||||
}
|
||||
autoLoadWidgets();
|
||||
addApplySaveButtons(m_txpid->Apply, m_txpid->Save);
|
||||
|
||||
// Cannot use addUAVObjectToWidgetRelation() for OptionaModules enum because
|
||||
// QCheckBox returns bool (0 or -1) and this value is then set to enum instead
|
||||
// or enum options
|
||||
connect(HwSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues()));
|
||||
connect(m_txpid->Apply, SIGNAL(clicked()), this, SLOT(applySettings()));
|
||||
connect(m_txpid->Save, SIGNAL(clicked()), this, SLOT(saveSettings()));
|
||||
addAutoBindings();
|
||||
|
||||
connect(m_txpid->PID1, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSpinBoxProperties(int)));
|
||||
connect(m_txpid->PID2, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSpinBoxProperties(int)));
|
||||
connect(m_txpid->PID3, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSpinBoxProperties(int)));
|
||||
disableMouseWheelEvents();
|
||||
|
||||
addUAVObject("HwSettings");
|
||||
|
||||
addWidgetBinding("TxPIDSettings", "BankNumber", m_txpid->pidBank, 0, 1, true);
|
||||
|
||||
@ -94,15 +80,14 @@ ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
|
||||
addWidgetBinding("TxPIDSettings", "UpdateMode", m_txpid->UpdateMode);
|
||||
|
||||
connect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *)));
|
||||
|
||||
addWidget(m_txpid->TxPIDEnable);
|
||||
addWidget(m_txpid->enableAutoCalcYaw);
|
||||
enableControls(false);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
|
||||
disableMouseWheelEvents();
|
||||
connect(m_txpid->PID1, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSpinBoxProperties(int)));
|
||||
connect(m_txpid->PID2, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSpinBoxProperties(int)));
|
||||
connect(m_txpid->PID3, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSpinBoxProperties(int)));
|
||||
|
||||
connect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *)));
|
||||
}
|
||||
|
||||
ConfigTxPIDWidget::~ConfigTxPIDWidget()
|
||||
@ -110,6 +95,40 @@ ConfigTxPIDWidget::~ConfigTxPIDWidget()
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
/*
|
||||
* This overridden function refreshes widgets which have no direct relation
|
||||
* to any of UAVObjects. It saves their dirty state first because update comes
|
||||
* from UAVObjects, and then restores it.
|
||||
*/
|
||||
void ConfigTxPIDWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
Q_UNUSED(obj);
|
||||
|
||||
// Set module enable checkbox from OptionalModules UAVObject item.
|
||||
// It needs special processing because ConfigTaskWidget uses TRUE/FALSE
|
||||
// for QCheckBox, but OptionalModules uses Enabled/Disabled enum values.
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
|
||||
m_txpid->TxPIDEnable->setChecked(
|
||||
hwSettings->getOptionalModules(HwSettings::OPTIONALMODULES_TXPID) == HwSettings::OPTIONALMODULES_ENABLED);
|
||||
}
|
||||
|
||||
/*
|
||||
* This overridden function updates UAVObjects which have no direct relation
|
||||
* to any of widgets.
|
||||
*/
|
||||
void ConfigTxPIDWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
// Save state of the module enable checkbox first.
|
||||
// Do not use setData() member on whole object, if possible, since it triggers unnecessary UAVObect update.
|
||||
quint8 enableModule = m_txpid->TxPIDEnable->isChecked() ?
|
||||
HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED;
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
|
||||
hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_TXPID, enableModule);
|
||||
}
|
||||
|
||||
|
||||
static bool isResponsivenessOption(int pidOption)
|
||||
{
|
||||
switch (pidOption) {
|
||||
@ -444,32 +463,6 @@ void ConfigTxPIDWidget::updateSpinBoxProperties(int selectedPidOption)
|
||||
maxPID->setValue(value);
|
||||
}
|
||||
|
||||
void ConfigTxPIDWidget::refreshValues()
|
||||
{
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
|
||||
m_txpid->TxPIDEnable->setChecked(
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_TXPID] == HwSettings::OPTIONALMODULES_ENABLED);
|
||||
}
|
||||
|
||||
void ConfigTxPIDWidget::applySettings()
|
||||
{
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_TXPID] =
|
||||
m_txpid->TxPIDEnable->isChecked() ? HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED;
|
||||
hwSettings->setData(hwSettingsData);
|
||||
}
|
||||
|
||||
void ConfigTxPIDWidget::saveSettings()
|
||||
{
|
||||
applySettings();
|
||||
UAVObject *obj = HwSettings::GetInstance(getObjectManager());
|
||||
saveObjectToSD(obj);
|
||||
}
|
||||
|
||||
void ConfigTxPIDWidget::processLinkedWidgets(QWidget *widget)
|
||||
{
|
||||
Q_UNUSED(widget);
|
||||
|
@ -37,15 +37,18 @@ class ConfigTxPIDWidget : public ConfigTaskWidget {
|
||||
public:
|
||||
ConfigTxPIDWidget(QWidget *parent = 0);
|
||||
~ConfigTxPIDWidget();
|
||||
|
||||
protected:
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private:
|
||||
Ui_TxPIDWidget *m_txpid;
|
||||
|
||||
private slots:
|
||||
void processLinkedWidgets(QWidget *widget);
|
||||
void updateSpinBoxProperties(int selectedPidOption);
|
||||
float getDefaultValueForPidOption(int pidOption);
|
||||
void refreshValues();
|
||||
void applySettings();
|
||||
void saveSettings();
|
||||
};
|
||||
|
||||
#endif // CONFIGTXPIDWIDGET_H
|
||||
|
@ -31,7 +31,6 @@
|
||||
|
||||
#include "configgadgetfactory.h"
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
|
||||
#include "systemsettings.h"
|
||||
#include "actuatorsettings.h"
|
||||
@ -47,11 +46,7 @@
|
||||
#include <QTimer>
|
||||
#include <QWidget>
|
||||
#include <QTextEdit>
|
||||
#include <QVBoxLayout>
|
||||
#include <QPushButton>
|
||||
#include <math.h>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
|
||||
/**
|
||||
Static function to get currently assigned channelDescriptions
|
||||
@ -120,12 +115,14 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
|
||||
m_aircraft = new Ui_AircraftWidget();
|
||||
m_aircraft->setupUi(this);
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_aircraft->saveAircraftToRAM->setVisible(false);
|
||||
}
|
||||
// must be done before auto binding !
|
||||
setWikiURL("Vehicle+Configuration");
|
||||
|
||||
addAutoBindings();
|
||||
|
||||
disableMouseWheelEvents();
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
ConfigGadgetFactory *configGadgetFactory = pm->getObject<ConfigGadgetFactory>();
|
||||
connect(m_aircraft->vehicleSetupWizardButton, SIGNAL(clicked()), configGadgetFactory, SIGNAL(onOpenVehicleConfigurationWizard()));
|
||||
|
||||
@ -133,31 +130,22 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
|
||||
Q_ASSERT(syssettings);
|
||||
m_aircraft->nameEdit->setMaxLength(syssettings->VEHICLENAME_NUMELEM);
|
||||
|
||||
addApplySaveButtons(m_aircraft->saveAircraftToRAM, m_aircraft->saveAircraftToSD);
|
||||
|
||||
addUAVObject("SystemSettings");
|
||||
addUAVObject("MixerSettings");
|
||||
addUAVObject("ActuatorSettings");
|
||||
|
||||
// The order of the tabs is important since they correspond with the AirframCategory enum
|
||||
addWidget(m_aircraft->nameEdit);
|
||||
|
||||
// The order of the tabs is important since they correspond with the AirframeCategory enum
|
||||
m_aircraft->aircraftType->addTab(tr("Multirotor"));
|
||||
m_aircraft->aircraftType->addTab(tr("Fixed Wing"));
|
||||
m_aircraft->aircraftType->addTab(tr("Helicopter"));
|
||||
m_aircraft->aircraftType->addTab(tr("Ground"));
|
||||
m_aircraft->aircraftType->addTab(tr("Custom"));
|
||||
// switchAirframeType(0);
|
||||
|
||||
// Connect aircraft type selection dropbox to callback function
|
||||
connect(m_aircraft->aircraftType, SIGNAL(currentChanged(int)), this, SLOT(switchAirframeType(int)));
|
||||
|
||||
// Connect the help pushbutton
|
||||
connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
refreshWidgetsValues();
|
||||
|
||||
addWidget(m_aircraft->nameEdit);
|
||||
|
||||
disableMouseWheelEvents();
|
||||
updateEnableControls();
|
||||
}
|
||||
|
||||
/**
|
||||
@ -171,23 +159,22 @@ ConfigVehicleTypeWidget::~ConfigVehicleTypeWidget()
|
||||
void ConfigVehicleTypeWidget::switchAirframeType(int index)
|
||||
{
|
||||
m_aircraft->airframesWidget->setCurrentWidget(getVehicleConfigWidget(index));
|
||||
setDirty(true);
|
||||
}
|
||||
|
||||
/**
|
||||
Refreshes the current value of the SystemSettings which holds the aircraft type
|
||||
Note: The default behavior of ConfigTaskWidget is bypassed.
|
||||
Therefore no automatic synchronization of UAV Objects to UI is done.
|
||||
Refreshes the current value of the SystemSettings which holds the aircraft type.
|
||||
Note: no widgets are bound so the default behavior of ConfigTaskWidget will not do much.
|
||||
Almost everything is handled here to the exception of one case (see ConfigCustomWidget...)
|
||||
*/
|
||||
void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *object)
|
||||
void ConfigVehicleTypeWidget::refreshWidgetsValuesImpl(UAVObject *obj)
|
||||
{
|
||||
ConfigTaskWidget::refreshWidgetsValues(object);
|
||||
Q_UNUSED(obj);
|
||||
|
||||
if (!allObjectsUpdated()) {
|
||||
return;
|
||||
}
|
||||
|
||||
bool dirty = isDirty();
|
||||
|
||||
// Get the Airframe type from the system settings:
|
||||
UAVDataObject *system = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(QString("SystemSettings")));
|
||||
Q_ASSERT(system);
|
||||
@ -233,8 +220,6 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *object)
|
||||
}
|
||||
}
|
||||
m_aircraft->nameEdit->setText(name);
|
||||
|
||||
setDirty(dirty);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -243,11 +228,8 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *object)
|
||||
We do all the tasks common to all airframes, or family of airframes, and
|
||||
we call additional methods for specific frames, so that we do not have a code
|
||||
that is too heavy.
|
||||
|
||||
Note: The default behavior of ConfigTaskWidget is bypassed.
|
||||
Therefore no automatic synchronization of UI to UAV Objects is done.
|
||||
*/
|
||||
void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
|
||||
void ConfigVehicleTypeWidget::updateObjectsFromWidgetsImpl()
|
||||
{
|
||||
// Airframe type defaults to Custom
|
||||
QString airframeType = "Custom";
|
||||
@ -262,7 +244,7 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
|
||||
UAVDataObject *system = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(QString("SystemSettings")));
|
||||
Q_ASSERT(system);
|
||||
|
||||
QPointer<UAVObjectField> field = system->getField(QString("AirframeType"));
|
||||
UAVObjectField *field = system->getField(QString("AirframeType"));
|
||||
if (field) {
|
||||
field->setValue(airframeType);
|
||||
}
|
||||
@ -279,8 +261,8 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
|
||||
}
|
||||
|
||||
// call refreshWidgetsValues() to reflect actual saved values
|
||||
// TODO is this needed ?
|
||||
refreshWidgetsValues();
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
}
|
||||
|
||||
int ConfigVehicleTypeWidget::frameCategory(QString frameType)
|
||||
@ -311,46 +293,52 @@ int ConfigVehicleTypeWidget::frameCategory(QString frameType)
|
||||
|
||||
VehicleConfig *ConfigVehicleTypeWidget::getVehicleConfigWidget(int frameCategory)
|
||||
{
|
||||
VehicleConfig *vehiculeConfig;
|
||||
VehicleConfig *vehicleConfig;
|
||||
|
||||
if (!m_vehicleIndexMap.contains(frameCategory)) {
|
||||
// create config widget
|
||||
vehiculeConfig = createVehicleConfigWidget(frameCategory);
|
||||
// bind config widget "field" to this ConfigTaskWodget
|
||||
// this is necessary to get "dirty" state management
|
||||
vehiculeConfig->registerWidgets(*this);
|
||||
vehicleConfig = createVehicleConfigWidget(frameCategory);
|
||||
|
||||
// add config widget to UI
|
||||
int index = m_aircraft->airframesWidget->insertWidget(m_aircraft->airframesWidget->count(), vehiculeConfig);
|
||||
int index = m_aircraft->airframesWidget->insertWidget(m_aircraft->airframesWidget->count(), vehicleConfig);
|
||||
m_vehicleIndexMap[frameCategory] = index;
|
||||
|
||||
// and enable controls (needed?)
|
||||
updateEnableControls();
|
||||
}
|
||||
int index = m_vehicleIndexMap.value(frameCategory);
|
||||
vehiculeConfig = (VehicleConfig *)m_aircraft->airframesWidget->widget(index);
|
||||
return vehiculeConfig;
|
||||
vehicleConfig = (VehicleConfig *)m_aircraft->airframesWidget->widget(index);
|
||||
return vehicleConfig;
|
||||
}
|
||||
|
||||
VehicleConfig *ConfigVehicleTypeWidget::createVehicleConfigWidget(int frameCategory)
|
||||
{
|
||||
if (frameCategory == ConfigVehicleTypeWidget::FIXED_WING) {
|
||||
return new ConfigFixedWingWidget();
|
||||
} else if (frameCategory == ConfigVehicleTypeWidget::MULTIROTOR) {
|
||||
return new ConfigMultiRotorWidget();
|
||||
} else if (frameCategory == ConfigVehicleTypeWidget::HELICOPTER) {
|
||||
return new ConfigCcpmWidget();
|
||||
} else if (frameCategory == ConfigVehicleTypeWidget::GROUND) {
|
||||
return new ConfigGroundVehicleWidget();
|
||||
} else if (frameCategory == ConfigVehicleTypeWidget::CUSTOM) {
|
||||
return new ConfigCustomWidget();
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
VehicleConfig *vehicleConfig;
|
||||
|
||||
/**
|
||||
Opens the wiki from the user's default browser
|
||||
*/
|
||||
void ConfigVehicleTypeWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Vehicle+Configuration"),
|
||||
QUrl::StrictMode));
|
||||
switch (frameCategory) {
|
||||
case ConfigVehicleTypeWidget::FIXED_WING:
|
||||
vehicleConfig = new ConfigFixedWingWidget();
|
||||
break;
|
||||
case ConfigVehicleTypeWidget::MULTIROTOR:
|
||||
vehicleConfig = new ConfigMultiRotorWidget();
|
||||
break;
|
||||
case ConfigVehicleTypeWidget::HELICOPTER:
|
||||
vehicleConfig = new ConfigCcpmWidget();
|
||||
break;
|
||||
case ConfigVehicleTypeWidget::GROUND:
|
||||
vehicleConfig = new ConfigGroundVehicleWidget();
|
||||
break;
|
||||
case ConfigVehicleTypeWidget::CUSTOM:
|
||||
vehicleConfig = new ConfigCustomWidget();
|
||||
break;
|
||||
default:
|
||||
vehicleConfig = NULL;
|
||||
break;
|
||||
}
|
||||
if (vehicleConfig) {
|
||||
// bind config widget "field" to this ConfigTaskWodget
|
||||
// this is necessary to get "dirty" state management
|
||||
vehicleConfig->registerWidgets(*this);
|
||||
}
|
||||
return vehicleConfig;
|
||||
}
|
||||
|
@ -41,10 +41,7 @@ class Ui_AircraftWidget;
|
||||
class QWidget;
|
||||
|
||||
/*
|
||||
* This class derives from ConfigTaskWidget and overrides its default "binding" mechanism.
|
||||
* This widget bypasses automatic synchronization of UAVObjects and UI by providing its own implementations of
|
||||
* virtual void refreshWidgetsValues(UAVObject *obj = NULL);
|
||||
* virtual void updateObjectsFromWidgets();
|
||||
* This class derives from ConfigTaskWidget but almost bypasses the need its default "binding" mechanism.
|
||||
*
|
||||
* It does use the "dirty" state management and registers its relevant widgets with ConfigTaskWidget to do so.
|
||||
*
|
||||
@ -52,7 +49,6 @@ class QWidget;
|
||||
* Note: for "dirty" state management it is important to register the fields of child widgets with the parent
|
||||
* ConfigVehicleTypeWidget class.
|
||||
*
|
||||
* TODO consider to call "super" to benefit from default logic...
|
||||
* TODO improve handling of relationship with VehicleConfig derived classes (i.e. ConfigTaskWidget within ConfigTaskWidget)
|
||||
*/
|
||||
class ConfigVehicleTypeWidget : public ConfigTaskWidget {
|
||||
@ -64,9 +60,9 @@ public:
|
||||
ConfigVehicleTypeWidget(QWidget *parent = 0);
|
||||
~ConfigVehicleTypeWidget();
|
||||
|
||||
protected slots:
|
||||
virtual void refreshWidgetsValues(UAVObject *object = NULL);
|
||||
virtual void updateObjectsFromWidgets();
|
||||
protected:
|
||||
virtual void refreshWidgetsValuesImpl(UAVObject *obj);
|
||||
virtual void updateObjectsFromWidgetsImpl();
|
||||
|
||||
private:
|
||||
Ui_AircraftWidget *m_aircraft;
|
||||
@ -84,7 +80,6 @@ private:
|
||||
|
||||
private slots:
|
||||
void switchAirframeType(int index);
|
||||
void openHelp();
|
||||
};
|
||||
|
||||
#endif // CONFIGVEHICLETYPEWIDGET_H
|
||||
|
@ -1,77 +0,0 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>defaultattitude</class>
|
||||
<widget class="QWidget" name="defaultattitude">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>400</width>
|
||||
<height>300</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QFrame" name="frame">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<widget class="QTextBrowser" name="textBrowser">
|
||||
<property name="html">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">Attitude Calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt; font-weight:600;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This panel will be updated to provide the relevant controls to let you calibrate your flight controller, depending on the board which is detected once telemetry is connected and running.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p></body></html></string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -1,45 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file defaultattitudewidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Placeholder for attitude panel until board is connected.
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program 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.
|
||||
*
|
||||
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "defaultattitudewidget.h"
|
||||
|
||||
#include "ui_defaultattitude.h"
|
||||
|
||||
#include <QMutexLocker>
|
||||
#include <QErrorMessage>
|
||||
#include <QDebug>
|
||||
|
||||
DefaultAttitudeWidget::DefaultAttitudeWidget(QWidget *parent) :
|
||||
QWidget(parent),
|
||||
ui(new Ui_defaultattitude)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
}
|
||||
|
||||
DefaultAttitudeWidget::~DefaultAttitudeWidget()
|
||||
{
|
||||
delete ui;
|
||||
}
|
267
ground/gcs/src/plugins/config/defaultconfig.ui
Normal file
267
ground/gcs/src/plugins/config/defaultconfig.ui
Normal file
@ -0,0 +1,267 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>defaultconfig</class>
|
||||
<widget class="QWidget" name="defaultconfig">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>646</width>
|
||||
<height>596</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="currentIndex">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<widget class="QWidget" name="tab">
|
||||
<attribute name="title">
|
||||
<string notr="true"><place holder - do not translate></string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QScrollArea" name="scrollArea">
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>232</red>
|
||||
<green>232</green>
|
||||
<blue>232</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Plain</enum>
|
||||
</property>
|
||||
<property name="widgetResizable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<widget class="QWidget" name="scrollAreaWidgetContents">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>622</width>
|
||||
<height>519</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item row="1" column="0">
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QTextBrowser" name="textBrowser">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="sizeAdjustPolicy">
|
||||
<enum>QAbstractScrollArea::AdjustToContents</enum>
|
||||
</property>
|
||||
<property name="lineWrapMode">
|
||||
<enum>QTextEdit::WidgetWidth</enum>
|
||||
</property>
|
||||
<property name="html">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">This panel will be updated to provide the relevant controls to let you configure your device once it is connected and running.</span></p></body></html></string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<property name="spacing">
|
||||
<number>4</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>369</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="helpButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Takes you to the wiki page</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../coreplugin/core.qrc">
|
||||
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="applyButton">
|
||||
<property name="text">
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveButton">
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
@ -1,13 +1,13 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file DefaultHwSettingsWidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @file defaultconfigwidget.cpp
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Placeholder for attitude panel until board is connected.
|
||||
* @brief Placeholder for config widget until board connected.
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
@ -24,22 +24,24 @@
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "defaulthwsettingswidget.h"
|
||||
#include "defaultconfigwidget.h"
|
||||
|
||||
#include "ui_defaulthwsettings.h"
|
||||
#include "ui_defaultconfig.h"
|
||||
|
||||
#include <QMutexLocker>
|
||||
#include <QErrorMessage>
|
||||
#include <QDebug>
|
||||
|
||||
DefaultHwSettingsWidget::DefaultHwSettingsWidget(QWidget *parent) :
|
||||
QWidget(parent),
|
||||
ui(new Ui_defaulthwsettings)
|
||||
DefaultConfigWidget::DefaultConfigWidget(QWidget *parent, QString title) : QWidget(parent)
|
||||
{
|
||||
ui = new Ui_defaultconfig();
|
||||
ui->setupUi(this);
|
||||
|
||||
ui->tabWidget->setTabText(0, title);
|
||||
|
||||
ui->helpButton->setEnabled(false);
|
||||
ui->saveButton->setEnabled(false);
|
||||
ui->applyButton->setVisible(false);
|
||||
ui->applyButton->setEnabled(false);
|
||||
}
|
||||
|
||||
DefaultHwSettingsWidget::~DefaultHwSettingsWidget()
|
||||
DefaultConfigWidget::~DefaultConfigWidget()
|
||||
{
|
||||
delete ui;
|
||||
}
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user