diff --git a/CREDITS.txt b/CREDITS.txt index 8abc0d029..c39940316 100644 --- a/CREDITS.txt +++ b/CREDITS.txt @@ -16,6 +16,7 @@ Ed Faulkner Darren Furniss Frederic Goddeeris Daniel Godin +Anthony Gomez Bani Greyling Nuno Guedes Erik Gustavsson @@ -27,6 +28,7 @@ Ryan Hunt Mark James Sami Korhonen Thorsten Klose +Ricky King Hallvard Kristiansen Edouard Lafargue Mike Labranche @@ -36,12 +38,14 @@ David Llama Matt Lipski Les Newell Ken Northup +Ben Matthews Greg Matthews Guy McCaldin Gary Mortimer Alessio Morale Cathy Moss Angus Peart +John Pike Dmytro Poplavskiy Eric Price Richard Querin @@ -58,6 +62,7 @@ Oleg Semyonov Stacey Sheldon Troy Schultz Dr. Erhard Siegl +Dusty Anne Smith Mike Smith Alex Sowa Pete Stapley @@ -69,6 +74,7 @@ Jasper van Loenen Vassilis Varveropoulos Kevin Vertucio Alex Vrubel +Mike Walters Brian Webb Justin Welander Mat Wellington diff --git a/WHATSNEW.txt b/WHATSNEW.txt index 7cf724ff4..2b0d7e7c2 100644 --- a/WHATSNEW.txt +++ b/WHATSNEW.txt @@ -127,6 +127,12 @@ KNOWN ISSUES: - Sensor calibration is not final. It will be reworked completely to increase its accuracy and make it easier to use. +- Until the calibration is reworked, default attitude estimation algorithm + used by Revo is a complimentary filter with magnetometers disabled. Hence + Revo does not use them yet to correct yaw drift. Magnetometers can be + enabled, but you should properly calibrate them first. That's the reason + why they are disabled by default. + - AltitudeHold mode is enabled, but it is not officially supported. Do not expect it to work perfectly and be considered production quality. You may play with it and report your issues and suggestions at your own @@ -169,16 +175,17 @@ Due to major rework of all code and integration of Revo code into mainline list above. Some of them can be found using this link: http://progress.openpilot.org/issues/?filter=10860 -OP-678, OP-693, OP-719, OP-726, OP-727, OP-747, OP-761, OP-769, OP-770, -OP-772, OP-784, OP-792, OP-804, OP-807, OP-812, OP-816, OP-817, OP-820, -OP-821, OP-843, OP-846, OP-854, OP-855, OP-856, OP-861, OP-864, OP-867, -OP-871, OP-873, OP-874, OP-875, OP-879, OP-885, OP-886, OP-888, OP-889, -OP-890, OP-891, OP-892, OP-893, OP-894, OP-895, OP-896, OP-897, OP-898, -OP-899, OP-900, OP-903, OP-905, OP-906, OP-907, OP-910, OP-912, OP-917, -OP-920, OP-925, OP-926, OP-928, OP-935, OP-936, OP-939, OP-952, OP-955, -OP-957, OP-958, OP-965, OP-968, OP-969, OP-970, OP-976, OP-977, OP-980, -OP-981, OP-982, OP-983, OP-987, OP-988, OP-989, OP-990, OP-991, OP-993 -OP-997, OP-998, OP-999 +OP-678, OP-693, OP-719, OP-726, OP-727, OP-747, OP-761, OP-769, OP-770, +OP-772, OP-784, OP-792, OP-804, OP-807, OP-812, OP-816, OP-817, OP-820, +OP-821, OP-843, OP-846, OP-854, OP-855, OP-856, OP-861, OP-864, OP-867, +OP-871, OP-873, OP-874, OP-875, OP-879, OP-885, OP-886, OP-888, OP-889, +OP-890, OP-891, OP-892, OP-893, OP-894, OP-895, OP-896, OP-897, OP-898, +OP-899, OP-900, OP-903, OP-905, OP-906, OP-907, OP-910, OP-912, OP-917, +OP-920, OP-925, OP-926, OP-928, OP-935, OP-936, OP-939, OP-952, OP-955, +OP-957, OP-958, OP-965, OP-968, OP-969, OP-970, OP-977, OP-979, OP-980, +OP-981, OP-982, OP-983, OP-988, OP-989, OP-990, OP-991, OP-993, OP-997, +OP-998, OP-999, OP-1000, OP-1002, OP-1005, OP-1007, OP-1008, OP-1009, OP-1010, +OP-1011, OP-1012, OP-1013, OP-1015, OP-1016, OP-1021 Short summary of changes. For a complete list see the git log. @@ -228,6 +235,10 @@ Flight code changes: - Cyr's attitude patch is ported from CC3D to Revo; - added magnetometer options (mags are disabled by default for Revo complimenary filter); - advance camera stabilisation is now officially released; +- Revo alarm led now distinguish between Critical(lit led), Error(blink fast), Warning(blink slowly) Alarm condition +- Revo alarm led flash fast(like in Error Alarm) during calibration using complementary attitude estimation. +- Redo gyro bias zero after calibration parameters changes +- Do not raise GPS alarm if a gps port is not configured. - fixed numerous internal firmware bugs (too many to list here). GCS code changes: @@ -255,6 +266,10 @@ GCS code changes: - anti-aliased scope plugin; - numerous code fixes and cleanups (too many to list here); - USB HID code is replaced by new cross-platform hidapi library to fix old Linux/OSX problems. +- Adds GUI to set Altitude Hold filter parameters. +- Adds configurable units for velocity/speed and altitude in QML PFD. Units are configured in settings panel. +- Reduces precision of the PDOP value in the PFD display to 1 decimal. +- Remove deprecated powerlog Common parts: - added simple toolchain install make targets; diff --git a/flight/libraries/sanitycheck.c b/flight/libraries/sanitycheck.c index dfc7b2c31..c1bb65eb3 100644 --- a/flight/libraries/sanitycheck.c +++ b/flight/libraries/sanitycheck.c @@ -110,6 +110,7 @@ int32_t configuration_check() } break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD: + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEVARIO: if (coptercontrol) { severity = SYSTEMALARMS_ALARM_ERROR; } else if (!PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_ALTITUDEHOLD)) { // Revo supports altitude hold diff --git a/flight/modules/Airspeed/revolution/baro_airspeed_etasv3.c b/flight/modules/Airspeed/revolution/baro_airspeed_etasv3.c index e26262ec2..50c5d78fb 100644 --- a/flight/modules/Airspeed/revolution/baro_airspeed_etasv3.c +++ b/flight/modules/Airspeed/revolution/baro_airspeed_etasv3.c @@ -72,7 +72,8 @@ void baro_airspeedGetETASV3(AirspeedSensorData *airspeedSensor, AirspeedSettings // Calibrate sensor by averaging zero point value if (calibrationCount <= CALIBRATION_IDLE_MS / airspeedSettings->SamplePeriod) { calibrationCount++; - calibrationCount2++; + calibrationSum = 0; + calibrationCount2 = 0; return; } else if (calibrationCount <= (CALIBRATION_IDLE_MS + CALIBRATION_COUNT_MS) / airspeedSettings->SamplePeriod) { calibrationCount++; @@ -81,6 +82,9 @@ void baro_airspeedGetETASV3(AirspeedSensorData *airspeedSensor, AirspeedSettings if (calibrationCount > (CALIBRATION_IDLE_MS + CALIBRATION_COUNT_MS) / airspeedSettings->SamplePeriod) { airspeedSettings->ZeroPoint = (int16_t)(((float)calibrationSum) / calibrationCount2); AirspeedSettingsZeroPointSet(&airspeedSettings->ZeroPoint); + calibrationCount = 0; + calibrationSum = 0; + calibrationCount2 = 0; } return; } diff --git a/flight/modules/AltitudeHold/altitudehold.c b/flight/modules/AltitudeHold/altitudehold.c index 0eb34fcc8..a886de64c 100644 --- a/flight/modules/AltitudeHold/altitudehold.c +++ b/flight/modules/AltitudeHold/altitudehold.c @@ -139,11 +139,15 @@ static void altitudeHoldTask(__attribute__((unused)) void *parameters) BaroSensorConnectQueue(queue); FlightStatusConnectQueue(queue); AccelStateConnectQueue(queue); - + bool altitudeHoldFlightMode = false; BaroSensorAltitudeGet(&smoothed_altitude); running = false; enum init_state { WAITING_BARO, WAITIING_INIT, INITED } init = WAITING_BARO; + uint8_t flightMode; + FlightStatusFlightModeGet(&flightMode); + // initialize enable flag + altitudeHoldFlightMode = flightMode == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD || flightMode == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO; // Main task loop bool baro_updated = false; while (1) { @@ -161,10 +165,9 @@ static void altitudeHoldTask(__attribute__((unused)) void *parameters) init = (init == WAITING_BARO) ? WAITIING_INIT : init; } else if (ev.obj == FlightStatusHandle()) { - FlightStatusData flightStatus; - FlightStatusGet(&flightStatus); - - if (flightStatus.FlightMode == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD && !running) { + FlightStatusFlightModeGet(&flightMode); + altitudeHoldFlightMode = flightMode == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD || flightMode == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO; + if (altitudeHoldFlightMode && !running) { // Copy the current throttle as a starting point for integral StabilizationDesiredThrottleGet(&throttleIntegral); switchThrottle = throttleIntegral; @@ -175,7 +178,7 @@ static void altitudeHoldTask(__attribute__((unused)) void *parameters) AltHoldSmoothedData altHold; AltHoldSmoothedGet(&altHold); starting_altitude = altHold.Altitude; - } else if (flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) { + } else if (!altitudeHoldFlightMode) { running = false; lastAltitudeHoldDesiredUpdate = PIOS_DELAY_GetRaw(); } @@ -348,11 +351,10 @@ static void altitudeHoldTask(__attribute__((unused)) void *parameters) AltHoldSmoothedGet(&altHold); - // Verify that we are in altitude hold mode - FlightStatusData flightStatus; - FlightStatusGet(&flightStatus); - if (flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD || - flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED) { + // Verify that we are in altitude hold mode + uint8_t armed; + FlightStatusArmedGet(&armed); + if (!altitudeHoldFlightMode || armed != FLIGHTSTATUS_ARMED_ARMED) { running = false; } diff --git a/flight/modules/Attitude/revolution/attitude.c b/flight/modules/Attitude/revolution/attitude.c index 27daef3cb..5d97f1748 100644 --- a/flight/modules/Attitude/revolution/attitude.c +++ b/flight/modules/Attitude/revolution/attitude.c @@ -77,10 +77,12 @@ #include "CoordinateConversions.h" // Private constants -#define STACK_SIZE_BYTES 2048 -#define TASK_PRIORITY (tskIDLE_PRIORITY + 3) -#define FAILSAFE_TIMEOUT_MS 10 +#define STACK_SIZE_BYTES 2048 +#define TASK_PRIORITY (tskIDLE_PRIORITY + 3) +#define FAILSAFE_TIMEOUT_MS 10 +#define CALIBRATION_DELAY 4000 +#define CALIBRATION_DURATION 6000 // low pass filter configuration to calculate offset // of barometric altitude sensor // reasoning: updates at: 10 Hz, tau= 300 s settle time @@ -326,6 +328,7 @@ static int32_t updateAttitudeComplementary(bool first_run) static uint8_t init = 0; static float gyro_bias[3] = { 0, 0, 0 }; static bool magCalibrated = true; + static uint32_t initStartupTime = 0; // Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe if (xQueueReceive(gyroQueue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE || @@ -403,11 +406,28 @@ static int32_t updateAttitudeComplementary(bool first_run) timeval = PIOS_DELAY_GetRaw(); + // wait calibration_delay only at powerup + if (xTaskGetTickCount() < 3000) { + initStartupTime = 0; + } else { + initStartupTime = xTaskGetTickCount() - CALIBRATION_DELAY; + } + + // Zero gyro bias + // This is really needed after updating calibration settings. + GyrosBiasData zeroGyrosBias; + GyrosBiasGet(&zeroGyrosBias); + zeroGyrosBias.x = 0; + zeroGyrosBias.y = 0; + zeroGyrosBias.z = 0; + GyrosBiasSet(&zeroGyrosBias); return 0; } - if ((xTaskGetTickCount() < 10000) && (xTaskGetTickCount() > 4000)) { - // For first 7 seconds use accels to get gyro bias + if ((xTaskGetTickCount() - initStartupTime < CALIBRATION_DURATION + CALIBRATION_DELAY) && + (xTaskGetTickCount() - initStartupTime > CALIBRATION_DELAY)) { + // For first CALIBRATION_DURATION seconds after CALIBRATION_DELAY from startup + // Zero gyro bias assuming it is steady, smoothing the gyro input value applying rollPitchBiasRate. attitudeSettings.AccelKp = 1.0f; attitudeSettings.AccelKi = 0.0f; attitudeSettings.YawBiasRate = 0.23f; @@ -469,12 +489,6 @@ static int32_t updateAttitudeComplementary(bool first_run) accel_mag = accels_filtered[0] * accels_filtered[0] + accels_filtered[1] * accels_filtered[1] + accels_filtered[2] * accels_filtered[2]; accel_mag = sqrtf(accel_mag); - // TODO! check accel vector magnitude value for correctness - - accel_err[0] /= accel_mag; - accel_err[1] /= accel_mag; - accel_err[2] /= accel_mag; - float grot_mag; if (accel_filter_enabled) { grot_mag = sqrtf(grot_filtered[0] * grot_filtered[0] + grot_filtered[1] * grot_filtered[1] + grot_filtered[2] * grot_filtered[2]); @@ -482,7 +496,7 @@ static int32_t updateAttitudeComplementary(bool first_run) grot_mag = 1.0f; } - // TODO! check grot_mag value for correctness. + // TODO! check grot_mag & accel vector magnitude values for correctness. accel_err[0] /= (accel_mag * grot_mag); accel_err[1] /= (accel_mag * grot_mag); @@ -644,8 +658,9 @@ static int32_t updateAttitudeComplementary(bool first_run) } } - - if (variance_error) { + if (!init && flightStatus.Armed == FLIGHTSTATUS_ARMED_DISARMED) { + AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR); + } else if (variance_error) { AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_CRITICAL); } else { AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); diff --git a/flight/modules/GPS/GPS.c b/flight/modules/GPS/GPS.c index 973340e1a..cecbd1b7f 100644 --- a/flight/modules/GPS/GPS.c +++ b/flight/modules/GPS/GPS.c @@ -116,8 +116,6 @@ int32_t GPSStart(void) PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_GPS, gpsTaskHandle); return 0; } - - AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_ERROR); } return -1; } diff --git a/flight/modules/ManualControl/inc/manualcontrol.h b/flight/modules/ManualControl/inc/manualcontrol.h index 6278daa45..7b989fb5e 100644 --- a/flight/modules/ManualControl/inc/manualcontrol.h +++ b/flight/modules/ManualControl/inc/manualcontrol.h @@ -41,6 +41,7 @@ typedef enum { FLIGHTMODE_UNDEFINED = 0, FLIGHTMODE_MANUAL = 1, FLIGHTMODE_STABI (x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED2) ? FLIGHTMODE_STABILIZED : \ (x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) ? FLIGHTMODE_STABILIZED : \ (x == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) ? FLIGHTMODE_GUIDANCE : \ + (x == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) ? FLIGHTMODE_GUIDANCE : \ @@ -116,6 +117,7 @@ int32_t ManualControlInitialize(); ((int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED2) && \ ((int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) && \ ((int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD == (int)FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) && \ + ((int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEVARIO == (int)FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO) && \ ((int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL == (int)FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) && \ ((int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD == (int)FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) && \ ((int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_PATHPLANNER == (int)FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) && \ diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index eddec26ae..0c0d07a04 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -459,6 +459,7 @@ static void manualControlTask(__attribute__((unused)) void *parameters) case FLIGHTMODE_GUIDANCE: switch (flightStatus.FlightMode) { case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD: + case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO: altitudeHoldDesired(&cmd, lastFlightMode != flightStatus.FlightMode); break; case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: @@ -819,17 +820,24 @@ static void altitudeHoldDesired(ManualControlCommandData *cmd, bool changed) uint8_t throttleRate; uint8_t throttleExp; + static uint8_t flightMode; static portTickType lastSysTimeAH; static bool zeroed = false; portTickType thisSysTime; float dT; - AltitudeHoldDesiredData altitudeHoldDesiredData; + FlightStatusFlightModeGet(&flightMode); + AltitudeHoldDesiredData altitudeHoldDesiredData; AltitudeHoldDesiredGet(&altitudeHoldDesiredData); - AltitudeHoldSettingsThrottleExpGet(&throttleExp); - AltitudeHoldSettingsThrottleRateGet(&throttleRate); + if (flightMode == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) { + throttleExp = 128; + throttleRate = 0; + } else { + AltitudeHoldSettingsThrottleExpGet(&throttleExp); + AltitudeHoldSettingsThrottleRateGet(&throttleRate); + } StabilizationSettingsData stabSettings; StabilizationSettingsGet(&stabSettings); @@ -850,12 +858,13 @@ static void altitudeHoldDesired(ManualControlCommandData *cmd, bool changed) zeroed = false; } else if (cmd->Throttle > DEADBAND_HIGH && zeroed) { // being the two band symmetrical I can divide by DEADBAND_LOW to scale it to a value betweeon 0 and 1 - // then apply an "exp" f(x,k) = (k∙x∙x∙x + x∙(256−k)) / 256 + // then apply an "exp" f(x,k) = (k*x*x*x + x*(256−k)) / 256 altitudeHoldDesiredData.Altitude += (throttleExp * powf((cmd->Throttle - DEADBAND_HIGH) / (DEADBAND_LOW), 3) + (256 - throttleExp)) / 256 * throttleRate * dT; } else if (cmd->Throttle < DEADBAND_LOW && zeroed) { altitudeHoldDesiredData.Altitude -= (throttleExp * powf((DEADBAND_LOW - (cmd->Throttle < 0 ? 0 : cmd->Throttle)) / DEADBAND_LOW, 3) + (256 - throttleExp)) / 256 * throttleRate * dT; - } else if (cmd->Throttle >= DEADBAND_LOW && cmd->Throttle <= DEADBAND_HIGH) { + } else if (cmd->Throttle >= DEADBAND_LOW && cmd->Throttle <= DEADBAND_HIGH && (throttleRate != 0)) { // Require the stick to enter the dead band before they can move height + // Vario is not "engaged" when throttleRate == 0 zeroed = true; } diff --git a/flight/modules/System/systemmod.c b/flight/modules/System/systemmod.c index b218876be..9ff5dd7e0 100644 --- a/flight/modules/System/systemmod.c +++ b/flight/modules/System/systemmod.c @@ -167,7 +167,7 @@ static void systemTask(__attribute__((unused)) void *parameters) { /* start the delayed callback scheduler */ CallbackSchedulerStart(); - + uint8_t cycleCount = 0; /* create all modules thread */ MODULE_TASKCREATE_ALL; @@ -204,6 +204,7 @@ static void systemTask(__attribute__((unused)) void *parameters) while (1) { // Update the system statistics updateStats(); + cycleCount = cycleCount > 0 ? cycleCount - 1 : 7; // Update the system alarms updateSystemAlarms(); @@ -220,26 +221,33 @@ static void systemTask(__attribute__((unused)) void *parameters) // Flash the heartbeat LED #if defined(PIOS_LED_HEARTBEAT) - PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); + uint8_t armingStatus; + FlightStatusArmedGet(&armingStatus); + if ((armingStatus == FLIGHTSTATUS_ARMED_ARMED && (cycleCount & 0x1)) || + (armingStatus != FLIGHTSTATUS_ARMED_ARMED && (cycleCount & 0x4))) { + PIOS_LED_On(PIOS_LED_HEARTBEAT); + } else { + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } + DEBUG_MSG("+ 0x%08x\r\n", 0xDEADBEEF); #endif /* PIOS_LED_HEARTBEAT */ // Turn on the error LED if an alarm is set #if defined(PIOS_LED_ALARM) - if (AlarmsHasWarnings()) { + if (AlarmsHasCritical()) { + PIOS_LED_On(PIOS_LED_ALARM); + } else if ((AlarmsHasErrors() && (cycleCount & 0x1)) || + (!AlarmsHasErrors() && AlarmsHasWarnings() && (cycleCount & 0x4))) { PIOS_LED_On(PIOS_LED_ALARM); } else { PIOS_LED_Off(PIOS_LED_ALARM); } #endif /* PIOS_LED_ALARM */ - FlightStatusData flightStatus; - FlightStatusGet(&flightStatus); UAVObjEvent ev; - int delayTime = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED ? - SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) : - SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS; + int delayTime = SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2); if (xQueueReceive(objectPersistenceQueue, &ev, delayTime) == pdTRUE) { // If object persistence is updated call the callback @@ -468,14 +476,14 @@ static void updateStats() idleCounter = 0; } #if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) - if(pios_uavo_settings_fs_id){ + if (pios_uavo_settings_fs_id) { PIOS_FLASHFS_GetStats(pios_uavo_settings_fs_id, &fsStats); - stats.SysSlotsFree = fsStats.num_free_slots; + stats.SysSlotsFree = fsStats.num_free_slots; stats.SysSlotsActive = fsStats.num_active_slots; } - if(pios_user_fs_id){ + if (pios_user_fs_id) { PIOS_FLASHFS_GetStats(pios_user_fs_id, &fsStats); - stats.UsrSlotsFree = fsStats.num_free_slots; + stats.UsrSlotsFree = fsStats.num_free_slots; stats.UsrSlotsActive = fsStats.num_active_slots; } #endif diff --git a/flight/pios/common/pios_flashfs_logfs.c b/flight/pios/common/pios_flashfs_logfs.c index 6dfea60b6..81b103de7 100644 --- a/flight/pios/common/pios_flashfs_logfs.c +++ b/flight/pios/common/pios_flashfs_logfs.c @@ -1164,7 +1164,8 @@ out_exit: * @return 0 if success or error code * @retval -1 if fs_id is not a valid filesystem instance */ -int32_t PIOS_FLASHFS_GetStats(uintptr_t fs_id, struct PIOS_FLASHFS_Stats *stats){ +int32_t PIOS_FLASHFS_GetStats(uintptr_t fs_id, struct PIOS_FLASHFS_Stats *stats) +{ PIOS_Assert(stats); struct logfs_state *logfs = (struct logfs_state *)fs_id; @@ -1172,7 +1173,7 @@ int32_t PIOS_FLASHFS_GetStats(uintptr_t fs_id, struct PIOS_FLASHFS_Stats *stats) return -1; } stats->num_active_slots = logfs->num_active_slots; - stats->num_free_slots = logfs->num_free_slots; + stats->num_free_slots = logfs->num_free_slots; return 0; } #endif /* PIOS_INCLUDE_FLASH */ diff --git a/flight/pios/inc/pios_flashfs.h b/flight/pios/inc/pios_flashfs.h index a37a5333c..ebfa030db 100644 --- a/flight/pios/inc/pios_flashfs.h +++ b/flight/pios/inc/pios_flashfs.h @@ -29,9 +29,9 @@ #include -struct PIOS_FLASHFS_Stats{ - uint16_t num_free_slots; /* slots in free state */ - uint16_t num_active_slots; /* slots in active state */ +struct PIOS_FLASHFS_Stats { + uint16_t num_free_slots; /* slots in free state */ + uint16_t num_active_slots; /* slots in active state */ }; int32_t PIOS_FLASHFS_Format(uintptr_t fs_id); diff --git a/flight/pios/stm32f4xx/pios_usb.c b/flight/pios/stm32f4xx/pios_usb.c index 5ef3ca3b2..6578785e6 100644 --- a/flight/pios/stm32f4xx/pios_usb.c +++ b/flight/pios/stm32f4xx/pios_usb.c @@ -53,9 +53,9 @@ struct pios_usb_dev { xSemaphoreHandle statusCheckSemaphore; #endif }; - +#ifdef PIOS_INCLUDE_FREERTOS static void raiseDisconnectionCallbacks(void); - +#endif /** * @brief Validate the usb device structure * @returns true if valid device or false otherwise @@ -170,30 +170,33 @@ uint32_t usb_found; bool PIOS_USB_CheckAvailable(__attribute__((unused)) uint32_t id) { struct pios_usb_dev *usb_dev = (struct pios_usb_dev *)pios_usb_id; - static bool lastStatus = false; if (!PIOS_USB_validate(usb_dev)) { return false; } usb_found = ((usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin) != 0) ^ usb_dev->cfg->vsense_active_low; - +// Please note that checks of transfer_possible and the reconnection handling is +// suppressed for non freertos mode (aka bootloader) as this is causing problems detecting connection and +// broken communications. +#ifdef PIOS_INCLUDE_FREERTOS + static bool lastStatus = false; bool status = usb_found != 0 && transfer_possible ? 1 : 0; bool reconnect = false; -#ifdef PIOS_INCLUDE_FREERTOS if (xSemaphoreTakeFromISR(usb_dev->statusCheckSemaphore, NULL) == pdTRUE) { -#endif - reconnect = (lastStatus && !status); - lastStatus = status; -#ifdef PIOS_INCLUDE_FREERTOS - xSemaphoreGiveFromISR(usb_dev->statusCheckSemaphore, NULL); -} -#endif + reconnect = (lastStatus && !status); + lastStatus = status; + xSemaphoreGiveFromISR(usb_dev->statusCheckSemaphore, NULL); + } if (reconnect) { raiseDisconnectionCallbacks(); } - return status; + +#else + return usb_found; + +#endif } /* @@ -212,7 +215,7 @@ void PIOS_USB_RegisterDisconnectionCallback(void (*disconnectionCB)(void)) } PIOS_Assert(0); } - +#ifdef PIOS_INCLUDE_FREERTOS static void raiseDisconnectionCallbacks(void) { uint32_t i = 0; @@ -221,7 +224,7 @@ static void raiseDisconnectionCallbacks(void) (disconnection_cb_list[i++])(); } } - +#endif /* * * Provide STM32 USB OTG BSP layer API diff --git a/ground/openpilotgcs/share/openpilotgcs/default_configurations/Developer.xml b/ground/openpilotgcs/share/openpilotgcs/default_configurations/Developer.xml index 99d6599b3..430eeac3f 100644 --- a/ground/openpilotgcs/share/openpilotgcs/default_configurations/Developer.xml +++ b/ground/openpilotgcs/share/openpilotgcs/default_configurations/Developer.xml @@ -1781,32 +1781,6 @@ - - - - false - 0.0.0 - - - false - %%DATAPATH%%pfd/default/pfd.svg - false - false - - - - - false - 0.0.0 - - - true - %%DATAPATH%%pfd/default/pfd.svg - false - false - - - @@ -1816,12 +1790,14 @@ false 2000 + 1 false %%DATAPATH%%pfd/default/readymap.earth 46.6715 10.1589 true %%DATAPATH%%pfd/default/Pfd.qml + 1 false @@ -2802,11 +2778,47 @@ splitter - PFDGadget - - raw - - uavGadget + + + DialGadget + + Deluxe Attitude + + uavGadget + + + DialGadget + + Deluxe Baro Altimeter + + uavGadget + + 2 + @Variant(AAAACQAAAAA=) + splitter + + + + DialGadget + + Deluxe Compass + + uavGadget + + + DialGadget + + Deluxe Climbrate + + uavGadget + + 2 + @Variant(AAAACQAAAAA=) + splitter + + 1 + @Variant(AAAACQAAAAA=) + splitter 2 @Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAAHf) diff --git a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml index 0c2236054..cb6d21ffb 100644 --- a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml +++ b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml @@ -5,13 +5,16 @@ Default configuration
Default configuration built to work on all screen sizes
false - - true - 600 - 800 default false + + Environment + General + 600 + 800 + 150 + @@ -1819,33 +1822,7 @@ true - - - - - false - 0.0.0 - - - false - %%DATAPATH%%pfd/default/pfd.svg - false - false - - - - - false - 0.0.0 - - - true - %%DATAPATH%%pfd/default/pfd.svg - false - false - - - + @@ -1855,12 +1832,14 @@ false 2000 + 1 false %%DATAPATH%%pfd/default/readymap.earth 46.6715 10.1589 true %%DATAPATH%%pfd/default/Pfd.qml + 1 false @@ -2783,11 +2762,47 @@ splitter - PFDGadget - - raw - - uavGadget + + + DialGadget + + Deluxe Attitude + + uavGadget + + + DialGadget + + Deluxe Baro Altimeter + + uavGadget + + 2 + @Variant(AAAACQAAAAA=) + splitter + + + + DialGadget + + Deluxe Compass + + uavGadget + + + DialGadget + + Deluxe Climbrate + + uavGadget + + 2 + @Variant(AAAACQAAAAA=) + splitter + + 1 + @Variant(AAAACQAAAAA=) + splitter 2 @Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAAHf) diff --git a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS_wide.xml b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS_wide.xml index 89a57f21e..c66b7188a 100644 --- a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS_wide.xml +++ b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS_wide.xml @@ -1797,33 +1797,7 @@ true - - - - - false - 0.0.0 - - - false - %%DATAPATH%%pfd/default/pfd.svg - false - false - - - - - false - 0.0.0 - - - true - %%DATAPATH%%pfd/default/pfd.svg - false - false - - - + @@ -1833,12 +1807,14 @@ false 2000 + 1 false %%DATAPATH%%pfd/default/readymap.earth 46.6715 10.1589 true %%DATAPATH%%pfd/default/Pfd.qml + 1 false @@ -2785,11 +2761,47 @@ splitter - PFDGadget - - raw - - uavGadget + + + DialGadget + + Deluxe Attitude + + uavGadget + + + DialGadget + + Deluxe Baro Altimeter + + uavGadget + + 2 + @Variant(AAAACQAAAAA=) + splitter + + + + DialGadget + + Deluxe Compass + + uavGadget + + + DialGadget + + Deluxe Climbrate + + uavGadget + + 2 + @Variant(AAAACQAAAAA=) + splitter + + 1 + @Variant(AAAACQAAAAA=) + splitter 2 @Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAAHf) diff --git a/ground/openpilotgcs/share/openpilotgcs/dials/deluxe/attitude.svg b/ground/openpilotgcs/share/openpilotgcs/dials/deluxe/attitude.svg index 9a1de6638..0740be27f 100644 --- a/ground/openpilotgcs/share/openpilotgcs/dials/deluxe/attitude.svg +++ b/ground/openpilotgcs/share/openpilotgcs/dials/deluxe/attitude.svg @@ -12,7 +12,7 @@ xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape" version="1.1" id="svg4745" - inkscape:version="0.48.0 r9654" + inkscape:version="0.48.4 r9939" sodipodi:docname="attitude.svg" x="0px" y="0px" @@ -1205,17 +1205,17 @@ guidetolerance="10" inkscape:pageopacity="0" inkscape:pageshadow="2" - inkscape:window-width="1366" - inkscape:window-height="691" + inkscape:window-width="1920" + inkscape:window-height="1017" id="namedview2585" showgrid="false" inkscape:zoom="1.3107546" - inkscape:cx="78.320852" + inkscape:cx="-40.694561" inkscape:cy="152.84311" - inkscape:window-x="0" - inkscape:window-y="24" + inkscape:window-x="-8" + inkscape:window-y="-8" inkscape:window-maximized="1" - inkscape:current-layer="layer5" /> + inkscape:current-layer="background-7" /> @@ -7558,7 +7558,12 @@ + transform="translate(230.4171,-2.5493479)"> @@ -1980,7 +1979,7 @@ + transform="translate(19.192898,0)"> + transform="translate(184.16754,0)"> + + + - ALT - m/s - m + inkscape:label="rect2816" + style="display:inline"> - - PowerlogPlugin - - - Log filename - - - - - PowerLog-%0.csv - - - - - Comma Separated Values (*.csv) - - - QmlViewGadgetFactory diff --git a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_es.ts b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_es.ts index ac404a5fe..8f5d3d6cb 100644 --- a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_es.ts +++ b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_es.ts @@ -13563,24 +13563,6 @@ Move the %1 stick. - - PowerlogPlugin - - - Log filename - - - - - PowerLog-%0.csv - - - - - Comma Separated Values (*.csv) - - - QmlViewGadgetFactory diff --git a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts index c95082bb6..b4f7cf54b 100644 --- a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts +++ b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts @@ -14000,24 +14000,6 @@ Bougez le manche %1. - - PowerlogPlugin - - - Log filename - Fichier de journal - - - - PowerLog-%0.csv - - - - - Comma Separated Values (*.csv) - - - QmlViewGadgetFactory diff --git a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_ru.ts b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_ru.ts index 259c1c7a9..75687dfff 100644 --- a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_ru.ts +++ b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_ru.ts @@ -13585,24 +13585,6 @@ Move the %1 stick. - - PowerlogPlugin - - - Log filename - - - - - PowerLog-%0.csv - - - - - Comma Separated Values (*.csv) - - - QmlViewGadgetFactory diff --git a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_zh_CN.ts b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_zh_CN.ts index 3a764cd2d..6d9c4593e 100644 --- a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_zh_CN.ts +++ b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_zh_CN.ts @@ -13565,24 +13565,6 @@ Move the %1 stick. - - PowerlogPlugin - - - Log filename - - - - - PowerLog-%0.csv - - - - - Comma Separated Values (*.csv) - - - QmlViewGadgetFactory diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index 65a9851af..d0db17f9b 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -110,6 +110,11 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren updateEnableControls(); } +ConfigOutputWidget::~ConfigOutputWidget() +{ + // Do nothing +} + void ConfigOutputWidget::enableControls(bool enable) { ConfigTaskWidget::enableControls(enable); @@ -120,11 +125,6 @@ void ConfigOutputWidget::enableControls(bool enable) ui->channelOutTest->setEnabled(enable); } -ConfigOutputWidget::~ConfigOutputWidget() -{ - // Do nothing -} - /** Toggles the channel testing mode by making the GCS take over the ActuatorCommand objects @@ -242,6 +242,8 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject *obj) { Q_UNUSED(obj); + bool dirty = isDirty(); + // Get Actuator Settings ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager()); Q_ASSERT(actuatorSettings); @@ -353,6 +355,8 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject *obj) int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()]; outputChannelForm->neutral(neutral); } + + setDirty(dirty); } /** diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 896801f16..013f82666 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -90,9 +90,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa connect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *))); - // Link by default - ui->checkBox_7->setChecked(true); - ui->checkBox_8->setChecked(true); + connect(this, SIGNAL(autoPilotConnected()), this, SLOT(onBoardConnected())); disableMouseWheelEvents(); updateEnableControls(); @@ -103,7 +101,6 @@ ConfigStabilizationWidget::~ConfigStabilizationWidget() // Do nothing } - void ConfigStabilizationWidget::refreshWidgetsValues(UAVObject *o) { ConfigTaskWidget::refreshWidgetsValues(o); @@ -194,3 +191,14 @@ void ConfigStabilizationWidget::processLinkedWidgets(QWidget *widget) } } } + +void ConfigStabilizationWidget::onBoardConnected() +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectUtilManager *utilMngr = pm->getObject(); + + Q_ASSERT(utilMngr); + + // If Revolution board enable misc tab, otherwise disable it + ui->AltitudeHold->setEnabled((utilMngr->getBoardModel() & 0xff00) == 0x0900); +} diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h index 7f6324779..0a783f4c5 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h @@ -58,6 +58,7 @@ private slots: void realtimeUpdatesSlot(bool value); void linkCheckBoxes(bool value); void processLinkedWidgets(QWidget *); + void onBoardConnected(); }; #endif // ConfigStabilizationWidget_H diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index f45f7888c..040f2c046 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,7 +6,7 @@ 0 0 - 983 + 820 736 @@ -456,11 +456,23 @@ 6 - - 12 + + 9 + + + 9 + + + 9 + + + 9 + + true + 0 @@ -508,7 +520,16 @@ Basic - + + 0 + + + 0 + + + 0 + + 0 @@ -606,8 +627,8 @@ 0 0 - 953 - 653 + 778 + 659 @@ -644,8 +665,17 @@ true - - 12 + + 9 + + + 9 + + + 9 + + + 9 @@ -2684,8 +2714,17 @@ border-radius: 5; false - - 12 + + 9 + + + 9 + + + 9 + + + 9 6 @@ -6060,8 +6099,17 @@ border-radius: 5; Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - 12 + + 9 + + + 9 + + + 9 + + + 9 6 @@ -8610,8 +8658,17 @@ border-radius: 5; Integral - - 12 + + 9 + + + 9 + + + 9 + + + 9 @@ -8719,7 +8776,16 @@ border-radius: 5; Advanced - + + 0 + + + 0 + + + 0 + + 0 @@ -8801,9 +8867,9 @@ border-radius: 5; 0 - 0 - 936 - 702 + -117 + 778 + 762 @@ -9357,8 +9423,17 @@ border-radius: 5; false - - 12 + + 9 + + + 9 + + + 9 + + + 9 6 @@ -12706,8 +12781,17 @@ border-radius: 5; false - - 12 + + 9 + + + 9 + + + 9 + + + 9 6 @@ -16032,12 +16116,21 @@ border-radius: 5; false + + 9 + + + 9 + + + 9 + + + 9 + 4 - - 12 - @@ -18719,7 +18812,16 @@ border-radius: 5; Expert - + + 0 + + + 0 + + + 0 + + 0 @@ -18805,15 +18907,24 @@ border-radius: 5; 0 0 - 953 - 653 + 792 + 645 9 - + + 9 + + + 9 + + + 9 + + 9 @@ -18837,8 +18948,17 @@ border-radius: 5; Weak Leveling / Axis Lock - - 12 + + 9 + + + 9 + + + 9 + + + 9 @@ -21451,8 +21571,17 @@ border-radius: 5; Integral Limits - - 12 + + 9 + + + 9 + + + 9 + + + 9 6 @@ -24403,8 +24532,17 @@ border-radius: 5; Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - 12 + + 9 + + + 9 + + + 9 + + + 9 @@ -26852,6 +26990,3876 @@ border-radius: 5; + + + Altitude Hold + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + QFrame::NoFrame + + + true + + + + + 0 + 0 + 792 + 645 + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Tuning + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + 9 + + + 9 + + + 9 + + + 9 + + + 6 + + + + + Qt::Horizontal + + + + 497 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:AltitudeHoldSettings + button:default + buttongroup:99 + + + + + + + + + 0 + 0 + + + + + 0 + 140 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + QGroupBox{border: 0px;} + + + + + + true + + + + 0 + + + 0 + + + 0 + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 58 + 0 + + + + + 16777215 + 16777215 + + + + + + + Derivative + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + + objname:AltitudeHoldSettings + fieldname:Kp + scale:0.001 + haslimits:yes + buttongroup:99 + + + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + + objname:AltitudeHoldSettings + fieldname:Ki + scale:0.001 + haslimits:yes + buttongroup:99 + + + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + + objname:AltitudeHoldSettings + fieldname:Kd + scale:0.001 + haslimits:yes + buttongroup:99 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + 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; + + + Altitude + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 100 + + + 51 + + + + objname:AltitudeHoldSettings + fieldname:Kp + scale:0.001 + haslimits:yes + buttongroup:99 + + + + + + + + + 0 + 0 + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 100 + + + 51 + + + + objname:AltitudeHoldSettings + fieldname:Ki + scale:0.001 + haslimits:yes + buttongroup:99 + + + + + + + + + 0 + 0 + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 100 + + + 51 + + + + objname:AltitudeHoldSettings + fieldname:Kd + scale:0.001 + haslimits:yes + buttongroup:99 + + + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Vario Altitude + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + 9 + + + 9 + + + 9 + + + 9 + + + 6 + + + + + + 0 + 0 + + + + + 0 + 140 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + QGroupBox{border: 0px;} + + + + + + true + + + + 0 + + + 0 + + + 0 + + + + + 10 + + + 1 + + + 1 + + + 5 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 0 + + + + objname:AltitudeHoldSettings + fieldname:ThrottleRate + haslimits:no + scale:0.5 + buttongroup:99 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Exponential + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>Throttle exponential value.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 256.000000000000000 + + + 1.000000000000000 + + + 128.000000000000000 + + + + objname:AltitudeHoldSettings + fieldname:ThrottleExp + haslimits:no + scale:1 + buttongroup:99 + + + + + + + + + 0 + 0 + + + + + + + Max Vertical Velocity + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>Maximum allowed vertical velocity in m/s.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 1 + + + 5.000000000000000 + + + 0.100000000000000 + + + 2.500000000000000 + + + + objname:AltitudeHoldSettings + fieldname:ThrottleRate + haslimits:no + scale:1 + buttongroup:99 + + + + + + + + 256 + + + 128 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + + objname:AltitudeHoldSettings + fieldname:ThrottleExp + haslimits:no + scale:1 + buttongroup:99 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + 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; + + + Throttle Stick Response + + + Qt::AlignCenter + + + + + + + + + + Qt::Horizontal + + + + 497 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:AltitudeHoldSettings + button:default + buttongroup:99 + + + + + + + + + + + + 0 + 0 + + + + + 0 + 60 + + + + Instant Update + + + + + + + 0 + 0 + + + + + 136 + 20 + + + + <html><head/><body><p>Enabling this feature mean that any changes made to the sliders will be instantly sent and used by the Flight Controller, useful for two person tuning where one normally flies and ones changes the GCS.</p></body></html> + + + + + + Update flight controller in real time + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Expanding + + + + 20 + 40 + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/ioptionspage.h b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/ioptionspage.h index 1060d072d..a8ee2a8f9 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/ioptionspage.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/ioptionspage.h @@ -41,6 +41,7 @@ QT_END_NAMESPACE namespace Core { class CORE_EXPORT IOptionsPage : public QObject { Q_OBJECT + public: IOptionsPage(QObject *parent = 0) : QObject(parent), @@ -51,6 +52,7 @@ public: { m_icon = icon; } + QIcon icon() { return m_icon; @@ -63,22 +65,31 @@ public: { return ""; }; + virtual QString trName() const { return ""; }; + virtual QString category() const { return "DefaultCategory"; }; + virtual QString trCategory() const { return "DefaultCategory"; }; virtual QWidget *createPage(QWidget *parent) = 0; + virtual void apply() = 0; virtual void finish() = 0; + +public slots: + virtual void updateState() + {}; + private: QIcon m_icon; }; diff --git a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/settingsdialog.cpp b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/settingsdialog.cpp index be2b98a84..ea545a82c 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/settingsdialog.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/settingsdialog.cpp @@ -99,6 +99,7 @@ Q_DECLARE_METATYPE(::PageData) SettingsDialog::SettingsDialog(QWidget *parent, c QSettings *settings = ICore::instance()->settings(); settings->beginGroup("General"); + settings->beginGroup("Settings"); // restore last displayed category and page // this is done only if no category or page was provided through the constructor @@ -112,30 +113,26 @@ Q_DECLARE_METATYPE(::PageData) SettingsDialog::SettingsDialog(QWidget *parent, c } // restore window size - int windowWidth = settings->value("SettingsWindowWidth", 0).toInt(); - int windowHeight = settings->value("SettingsWindowHeight", 0).toInt(); + int windowWidth = settings->value("WindowWidth", 0).toInt(); + int windowHeight = settings->value("WindowHeight", 0).toInt(); qDebug() << "SettingsDialog window width :" << windowWidth << ", height:" << windowHeight; if (windowWidth > 0 && windowHeight > 0) { resize(windowWidth, windowHeight); } // restore splitter size - int size0 = settings->value("SettingsSplitterSize0", 0).toInt(); - int size1 = settings->value("SettingsSplitterSize1", 0).toInt(); - qDebug() << "SettingsDialog splitter size0:" << size0 << ", size1:" << size1; + int splitterPosition = settings->value("SplitterPosition", 350).toInt(); + qDebug() << "SettingsDialog splitter position:" << splitterPosition; QList sizes; - if (size0 > 0 && size1 > 0) { - sizes << size0 << size1; - } else { - sizes << 150 << 300; - } + sizes << splitterPosition << 400; splitter->setSizes(sizes); + settings->endGroup(); settings->endGroup(); // all extra space must go to the option page and none to the tree - splitter->setStretchFactor(splitter->indexOf(pageTree), 0); - splitter->setStretchFactor(splitter->indexOf(layoutWidget), 1); + splitter->setStretchFactor(0, 0); + splitter->setStretchFactor(1, 1); buttonBox->button(QDialogButtonBox::Ok)->setDefault(true); @@ -146,14 +143,15 @@ Q_DECLARE_METATYPE(::PageData) SettingsDialog::SettingsDialog(QWidget *parent, c connect(this, SIGNAL(settingsDialogShown(Core::Internal::SettingsDialog *)), m_instanceManager, SLOT(settingsDialogShown(Core::Internal::SettingsDialog *))); connect(this, SIGNAL(settingsDialogRemoved()), m_instanceManager, SLOT(settingsDialogRemoved())); - connect(this, SIGNAL(categoryItemSelected()), this, SLOT(categoryItemSelectedShowChildInstead()), - Qt::QueuedConnection); + + // needs to be queued to be able to change the selection from the selection change signal call + connect(this, SIGNAL(categoryItemSelected()), this, SLOT(onCategorySelected()), Qt::QueuedConnection); splitter->setCollapsible(0, false); splitter->setCollapsible(1, false); pageTree->header()->setVisible(false); - connect(pageTree, SIGNAL(currentItemChanged(QTreeWidgetItem *, QTreeWidgetItem *)), this, SLOT(pageSelected())); + connect(pageTree, SIGNAL(currentItemChanged(QTreeWidgetItem *, QTreeWidgetItem *)), this, SLOT(onItemSelected())); QList pluginPages; QList gadgetPages; @@ -168,10 +166,11 @@ Q_DECLARE_METATYPE(::PageData) SettingsDialog::SettingsDialog(QWidget *parent, c } } - // the plugin options page list sorted by untranslated names to facilitate access to the language settings when GCS - // is not running in a language understood by the user. + // the plugin options page list is sorted by untranslated category and names + // this is done to facilitate access to the language settings when GCS is not running in a language understood by the user. qStableSort(pluginPages.begin(), pluginPages.end(), compareOptionsPageByCategoryAndId); - // the plugin options page list sorted is sorted by translated names + + // the plugin options page list is sorted by translated names qStableSort(gadgetPages.begin(), gadgetPages.end(), compareOptionsPageByCategoryAndNameTr); // will hold the initially selected item if any @@ -181,14 +180,14 @@ Q_DECLARE_METATYPE(::PageData) SettingsDialog::SettingsDialog(QWidget *parent, c foreach(IOptionsPage * page, pluginPages) { QTreeWidgetItem *item = addPage(page); - // to automatically expand all plugin categories, uncomment next line - // item->parent()->setExpanded(true); + // automatically expand all plugin categories + item->parent()->setExpanded(true); if (page->id() == initialPage && page->category() == initialCategory) { initialItem = item; } } - // insert separator bewteen plugin and gadget pages + // insert separator between plugin and gadget pages QTreeWidgetItem *separator = new QTreeWidgetItem(pageTree); separator->setFlags(separator->flags() & ~Qt::ItemIsSelectable & ~Qt::ItemIsEnabled); separator->setText(0, QString(30, 0xB7)); @@ -288,7 +287,7 @@ QTreeWidgetItem *SettingsDialog::addPage(IOptionsPage *page) return item; } -void SettingsDialog::pageSelected() +void SettingsDialog::onItemSelected() { QTreeWidgetItem *item = pageTree->currentItem(); @@ -296,10 +295,23 @@ void SettingsDialog::pageSelected() return; } + if (pageTree->indexOfTopLevelItem(item) >= 0) { + if (item->childCount() == 1) { + // single child : category will not be expanded + item = item->child(0); + } else if (item->childCount() > 1) { + // multiple children : expand category and select 1st child + emit categoryItemSelected(); + return; + } + } + + // get user data PageData data = item->data(0, Qt::UserRole).value(); int index = data.index; m_currentCategory = data.category; m_currentPage = data.id; + // check if we are looking at a place holder or not QWidget *widget = dynamic_cast(stackedPages->widget(index)); if (widget) { @@ -310,25 +322,27 @@ void SettingsDialog::pageSelected() IOptionsPage *page = m_pages.at(index); stackedPages->insertWidget(index, page->createPage(stackedPages)); } + + IOptionsPage *page = m_pages.at(index); + page->updateState(); + stackedPages->setCurrentIndex(index); - // If user selects a toplevel item, select the first child for them - // I.e. Top level items are not really selectable - if ((pageTree->indexOfTopLevelItem(item) >= 0) && (item->childCount() > 0)) { - emit categoryItemSelected(); - } } -void SettingsDialog::categoryItemSelectedShowChildInstead() +void SettingsDialog::onCategorySelected() { QTreeWidgetItem *item = pageTree->currentItem(); - item->setExpanded(true); - pageTree->setCurrentItem(item->child(0), 0, QItemSelectionModel::SelectCurrent); + if (item->childCount() > 1) { + item->setExpanded(true); + pageTree->setCurrentItem(item->child(0), 0, QItemSelectionModel::SelectCurrent); + } } void SettingsDialog::deletePage() { QTreeWidgetItem *item = pageTree->currentItem(); + PageData data = item->data(0, Qt::UserRole).value(); QString category = data.category; @@ -339,9 +353,9 @@ void SettingsDialog::deletePage() parentItem->removeChild(item); if (parentItem->childCount() == 1) { parentItem->child(0)->setHidden(true); + pageTree->setCurrentItem(parentItem, 0, QItemSelectionModel::SelectCurrent); } } - pageSelected(); } // TODO duplicates a lot of the addPage code... @@ -453,16 +467,18 @@ void SettingsDialog::done(int val) QSettings *settings = ICore::instance()->settings(); settings->beginGroup("General"); + settings->beginGroup("Settings"); settings->setValue("LastPreferenceCategory", m_currentCategory); settings->setValue("LastPreferencePage", m_currentPage); - settings->setValue("SettingsWindowWidth", this->width()); - settings->setValue("SettingsWindowHeight", this->height()); - QList sizes = splitter->sizes(); - qDebug() << "SettingsDialog splitter saving size0:" << sizes[0] << ", size1:" << sizes[1]; - settings->setValue("SettingsSplitterSize0", sizes[0]); - settings->setValue("SettingsSplitterSize1", sizes[1]); + settings->setValue("WindowWidth", this->width()); + settings->setValue("WindowHeight", this->height()); + + QList sizes = splitter->sizes(); + settings->setValue("SplitterPosition", sizes[0]); + + settings->endGroup(); settings->endGroup(); QDialog::done(val); diff --git a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/settingsdialog.h b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/settingsdialog.h index d922e128b..017623a3e 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/settingsdialog.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/settingsdialog.h @@ -62,11 +62,11 @@ public slots: void done(int); private slots: - void pageSelected(); + void onItemSelected(); + void onCategorySelected(); void accept(); void reject(); void apply(); - void categoryItemSelectedShowChildInstead(); private: QList m_pages; diff --git a/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetinstancemanager.cpp b/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetinstancemanager.cpp index 1aa28d890..751531ddf 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetinstancemanager.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetinstancemanager.cpp @@ -303,23 +303,31 @@ void UAVGadgetInstanceManager::removeAllGadgets() } -bool UAVGadgetInstanceManager::canDeleteConfiguration(IUAVGadgetConfiguration *config) +bool UAVGadgetInstanceManager::isConfigurationActive(IUAVGadgetConfiguration *config) { - // to be able to delete a configuration, no instance must be using it + // check if there is gadget currently using the configuration foreach(IUAVGadget * gadget, m_gadgetInstances) { if (gadget->activeConfiguration() == config) { - return false; - } - } - // and it cannot be the only configuration - foreach(IUAVGadgetConfiguration * c, m_configurations) { - if (c != config && c->classId() == config->classId()) { return true; } } return false; } +UAVGadgetInstanceManager::DeleteStatus UAVGadgetInstanceManager::canDeleteConfiguration(IUAVGadgetConfiguration *config) +{ + // to be able to delete a configuration, no instance must be using it + if (isConfigurationActive(config)) { + return UAVGadgetInstanceManager::KO_ACTIVE; + } + // and it cannot be the only configuration + QList *configs = provisionalConfigurations(config->classId()); + if (configs->count() <= 1) { + return UAVGadgetInstanceManager::KO_LONE; + } + return UAVGadgetInstanceManager::OK; +} + void UAVGadgetInstanceManager::deleteConfiguration(IUAVGadgetConfiguration *config) { m_provisionalDeletes.append(config); @@ -504,6 +512,30 @@ QList *UAVGadgetInstanceManager::configurations(QStri return configs; } +QList *UAVGadgetInstanceManager::provisionalConfigurations(QString classId) const +{ + QList *configs = new QList; + // add current configurations + foreach(IUAVGadgetConfiguration * config, m_configurations) { + if (config->classId() == classId) { + configs->append(config); + } + } + // add provisional configurations + foreach(IUAVGadgetConfiguration * config, m_provisionalConfigs) { + if (config->classId() == classId) { + configs->append(config); + } + } + // remove provisional configurations + foreach(IUAVGadgetConfiguration * config, m_provisionalDeletes) { + if (config->classId() == classId) { + configs->removeOne(config); + } + } + return configs; +} + int UAVGadgetInstanceManager::indexForConfig(QList configurations, QString classId, QString configName) { diff --git a/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetinstancemanager.h b/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetinstancemanager.h index 23ee1075a..bab32efb2 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetinstancemanager.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetinstancemanager.h @@ -53,22 +53,30 @@ class IUAVGadgetFactory; class CORE_EXPORT UAVGadgetInstanceManager : public QObject { Q_OBJECT public: + enum DeleteStatus { OK, KO_ACTIVE, KO_LONE }; + explicit UAVGadgetInstanceManager(QObject *parent = 0); ~UAVGadgetInstanceManager(); + void readSettings(QSettings *qs); void saveSettings(QSettings *qs); + IUAVGadget *createGadget(QString classId, QWidget *parent, bool loadDefaultConfiguration = true); void removeGadget(IUAVGadget *gadget); void removeAllGadgets(); - bool canDeleteConfiguration(IUAVGadgetConfiguration *config); + + bool isConfigurationActive(IUAVGadgetConfiguration *config); + DeleteStatus canDeleteConfiguration(IUAVGadgetConfiguration *config); void deleteConfiguration(IUAVGadgetConfiguration *config); void cloneConfiguration(IUAVGadgetConfiguration *config); void applyChanges(IUAVGadgetConfiguration *config); void configurationNameEdited(QString text, bool hasText = true); + QStringList classIds() const { return m_classIdNameMap.keys(); } + QStringList configurationNames(QString classId) const; QString gadgetName(QString classId) const; QIcon gadgetIcon(QString classId) const; @@ -84,10 +92,6 @@ public slots: void settingsDialogRemoved(); private: - IUAVGadgetFactory *factory(QString classId) const; - void createOptionsPages(); - QList *configurations(QString classId) const; - QString suggestName(QString classId, QString name); QList m_gadgetInstances; QList m_factories; QList m_configurations; @@ -100,8 +104,18 @@ private: QList m_provisionalOptionsPages; Core::Internal::SettingsDialog *m_settingsDialog; ExtensionSystem::PluginManager *m_pm; - int indexForConfig(QList configurations, - QString classId, QString configName); + + IUAVGadgetFactory *factory(QString classId) const; + + void createOptionsPages(); + + QList *configurations(QString classId) const; + QList *provisionalConfigurations(QString classId) const; + + QString suggestName(QString classId, QString name); + + int indexForConfig(QList configurations, QString classId, QString configName); + void readConfigs_1_1_0(QSettings *qs); void readConfigs_1_2_0(QSettings *qs); }; diff --git a/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetoptionspagedecorator.cpp b/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetoptionspagedecorator.cpp index a2a956c99..dc76ae08d 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetoptionspagedecorator.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetoptionspagedecorator.cpp @@ -51,18 +51,8 @@ UAVGadgetOptionsPageDecorator::UAVGadgetOptionsPageDecorator(IOptionsPage *page, QWidget *UAVGadgetOptionsPageDecorator::createPage(QWidget *parent) { m_page = new Ui_TopOptionsPage(); - QWidget *w = new QWidget(parent); + QWidget *w = new QWidget(parent); m_page->setupUi(w); - if (m_config->locked()) { - m_page->deleteButton->hide(); - m_page->lockCheckBox->hide(); - m_page->nameLineEdit->setDisabled(true); - } - if (!m_instanceManager->canDeleteConfiguration(m_config)) { - m_page->deleteButton->setDisabled(true); - } - m_page->lockCheckBox->hide(); // - m_page->nameLineEdit->setText(m_id); QWidget *wi = m_optionsPage->createPage(w); wi->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); @@ -73,6 +63,8 @@ QWidget *UAVGadgetOptionsPageDecorator::createPage(QWidget *parent) m_page->configurationBox->hide(); } + updateState(); + connect(m_page->cloneButton, SIGNAL(clicked()), this, SLOT(cloneConfiguration())); connect(m_page->deleteButton, SIGNAL(clicked()), this, SLOT(deleteConfiguration())); connect(m_page->nameLineEdit, SIGNAL(textEdited(QString)), this, SLOT(textEdited(QString))); @@ -92,6 +84,35 @@ void UAVGadgetOptionsPageDecorator::finish() m_optionsPage->finish(); } +void UAVGadgetOptionsPageDecorator::updateState() +{ + if (m_config->locked()) { + m_page->deleteButton->hide(); + m_page->lockCheckBox->hide(); + m_page->nameLineEdit->setDisabled(true); + } + switch (m_instanceManager->canDeleteConfiguration(m_config)) { + case UAVGadgetInstanceManager::OK: + m_page->deleteButton->setEnabled(true); + m_page->deleteButton->setToolTip(tr("Delete this configuration")); + break; + case UAVGadgetInstanceManager::KO_ACTIVE: + m_page->deleteButton->setEnabled(false); + m_page->deleteButton->setToolTip(tr("Cannot delete a configuration currently in use")); + break; + case UAVGadgetInstanceManager::KO_LONE: + m_page->deleteButton->setEnabled(false); + m_page->deleteButton->setToolTip(tr("Cannot delete the last configuration")); + break; + default: + m_page->deleteButton->setEnabled(false); + m_page->deleteButton->setToolTip(tr("DON'T KNOW !")); + break; + } + m_page->lockCheckBox->hide(); + m_page->nameLineEdit->setText(m_id); +} + void UAVGadgetOptionsPageDecorator::cloneConfiguration() { m_instanceManager->cloneConfiguration(m_config); diff --git a/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetoptionspagedecorator.h b/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetoptionspagedecorator.h index f82244a0d..00145387d 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetoptionspagedecorator.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/uavgadgetoptionspagedecorator.h @@ -67,6 +67,7 @@ public: signals: public slots: + void updateState(); private slots: void cloneConfiguration(); diff --git a/ground/openpilotgcs/src/plugins/pfd/PFDGadget.pluginspec b/ground/openpilotgcs/src/plugins/pfd/PFDGadget.pluginspec deleted file mode 100644 index 0a4f70bc0..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/PFDGadget.pluginspec +++ /dev/null @@ -1,11 +0,0 @@ - - The OpenPilot Project - (C) 2010 Edouard Lafargue - The GNU Public License (GPL) Version 3 - The Primary Flight Display gadget - http://www.openpilot.org - - - - - diff --git a/ground/openpilotgcs/src/plugins/pfd/images/pfd-default.svg b/ground/openpilotgcs/src/plugins/pfd/images/pfd-default.svg deleted file mode 100644 index 0fdc3669b..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/images/pfd-default.svg +++ /dev/null @@ -1,394 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/pfd/pfd.pro b/ground/openpilotgcs/src/plugins/pfd/pfd.pro deleted file mode 100644 index 961d89c19..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfd.pro +++ /dev/null @@ -1,22 +0,0 @@ -TEMPLATE = lib -TARGET = PFDGadget -QT += svg -QT += opengl -include(../../openpilotgcsplugin.pri) -include(../../plugins/coreplugin/coreplugin.pri) -include(pfd_dependencies.pri) -HEADERS += pfdplugin.h -HEADERS += pfdgadget.h -HEADERS += pfdgadgetwidget.h -HEADERS += pfdgadgetfactory.h -HEADERS += pfdgadgetconfiguration.h -HEADERS += pfdgadgetoptionspage.h -SOURCES += pfdplugin.cpp -SOURCES += pfdgadget.cpp -SOURCES += pfdgadgetfactory.cpp -SOURCES += pfdgadgetwidget.cpp -SOURCES += pfdgadgetconfiguration.cpp -SOURCES += pfdgadgetoptionspage.cpp -OTHER_FILES += PFDGadget.pluginspec -FORMS += pfdgadgetoptionspage.ui -RESOURCES += pfd.qrc diff --git a/ground/openpilotgcs/src/plugins/pfd/pfd.qrc b/ground/openpilotgcs/src/plugins/pfd/pfd.qrc deleted file mode 100644 index 278dd281e..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfd.qrc +++ /dev/null @@ -1,5 +0,0 @@ - - - images/pfd-default.svg - - diff --git a/ground/openpilotgcs/src/plugins/pfd/pfd_dependencies.pri b/ground/openpilotgcs/src/plugins/pfd/pfd_dependencies.pri deleted file mode 100644 index 9aae5fbc0..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfd_dependencies.pri +++ /dev/null @@ -1 +0,0 @@ -include(../../plugins/uavobjects/uavobjects.pri) diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadget.cpp b/ground/openpilotgcs/src/plugins/pfd/pfdgadget.cpp deleted file mode 100644 index 6d91e3c88..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadget.cpp +++ /dev/null @@ -1,57 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdgadget.cpp - * @author Edouard Lafargue Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 "pfdgadget.h" -#include "pfdgadgetwidget.h" -#include "pfdgadgetconfiguration.h" - -PFDGadget::PFDGadget(QString classId, PFDGadgetWidget *widget, QWidget *parent) : - IUAVGadget(classId, parent), - m_widget(widget) -{} - -PFDGadget::~PFDGadget() -{ - delete m_widget; -} - -/* - This is called when a configuration is loaded, and updates the plugin's settings. - Careful: the plugin is already drawn before the loadConfiguration method is called the - first time, so you have to be careful not to assume all the plugin values are initialized - the first time you use them - */ -void PFDGadget::loadConfiguration(IUAVGadgetConfiguration *config) -{ - PFDGadgetConfiguration *m = qobject_cast(config); - - m_widget->setHqFonts(m->getHqFonts()); - m_widget->setDialFile(m->dialFile()); - m_widget->enableOpenGL(m->useOpenGL()); - m_widget->enableSmoothUpdates(m->getBeSmooth()); - m_widget->connectNeedles(); -} diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadget.h b/ground/openpilotgcs/src/plugins/pfd/pfdgadget.h deleted file mode 100644 index c161aa97f..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadget.h +++ /dev/null @@ -1,58 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdgadget.h - * @author Edouard Lafargue Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 - */ - -#ifndef PFDGADGET_H_ -#define PFDGADGET_H_ - -#include -#include "pfdgadgetwidget.h" - -class IUAVGadget; -class QWidget; -class QString; -class PFDGadgetWidget; - -using namespace Core; - -class PFDGadget : public Core::IUAVGadget { - Q_OBJECT -public: - PFDGadget(QString classId, PFDGadgetWidget *widget, QWidget *parent = 0); - ~PFDGadget(); - - QWidget *widget() - { - return m_widget; - } - void loadConfiguration(IUAVGadgetConfiguration *config); - -private: - PFDGadgetWidget *m_widget; -}; - - -#endif // PFDGADGET_H_ diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetconfiguration.cpp deleted file mode 100644 index f05235409..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetconfiguration.cpp +++ /dev/null @@ -1,77 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdgadgetconfiguration.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 "pfdgadgetconfiguration.h" -#include "utils/pathutils.h" - -/** - * Loads a saved configuration or defaults if non exist. - * - */ -PFDGadgetConfiguration::PFDGadgetConfiguration(QString classId, QSettings *qSettings, QObject *parent) : - IUAVGadgetConfiguration(classId, parent), - m_defaultDial("Unknown"), - beSmooth(true) -{ - // if a saved configuration exists load it - if (qSettings != 0) { - QString dialFile = qSettings->value("dialFile").toString(); - useOpenGLFlag = qSettings->value("useOpenGLFlag").toBool(); - hqFonts = qSettings->value("hqFonts").toBool(); - beSmooth = qSettings->value("beSmooth").toBool(); - m_defaultDial = Utils::PathUtils().InsertDataPath(dialFile); - } -} - -/** - * Clones a configuration. - * - */ -IUAVGadgetConfiguration *PFDGadgetConfiguration::clone() -{ - PFDGadgetConfiguration *m = new PFDGadgetConfiguration(this->classId()); - - m->m_defaultDial = m_defaultDial; - m->useOpenGLFlag = useOpenGLFlag; - m->hqFonts = hqFonts; - m->beSmooth = beSmooth; - return m; -} - -/** - * Saves a configuration. - * - */ -void PFDGadgetConfiguration::saveConfig(QSettings *qSettings) const -{ - QString dialFile = Utils::PathUtils().RemoveDataPath(m_defaultDial); - - qSettings->setValue("dialFile", dialFile); - qSettings->setValue("useOpenGLFlag", useOpenGLFlag); - qSettings->setValue("hqFonts", hqFonts); - qSettings->setValue("beSmooth", beSmooth); -} diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetconfiguration.h b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetconfiguration.h deleted file mode 100644 index 9f3152c63..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetconfiguration.h +++ /dev/null @@ -1,86 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdgadgetconfiguration.h - * @author Edouard Lafargue Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 - */ - -#ifndef PFDGADGETCONFIGURATION_H -#define PFDGADGETCONFIGURATION_H - -#include - -using namespace Core; - -class PFDGadgetConfiguration : public IUAVGadgetConfiguration { - Q_OBJECT -public: - explicit PFDGadgetConfiguration(QString classId, QSettings *qSettings = 0, QObject *parent = 0); - - // set dial configuration functions - void setDialFile(QString dialFile) - { - m_defaultDial = dialFile; - } - void setUseOpenGL(bool flag) - { - useOpenGLFlag = flag; - } - void setHqFonts(bool flag) - { - hqFonts = flag; - } - void setBeSmooth(bool flag) - { - beSmooth = flag; - } - - // get dial configuration functions - QString dialFile() - { - return m_defaultDial; - } - bool useOpenGL() - { - return useOpenGLFlag; - } - bool getHqFonts() - { - return hqFonts; - } - bool getBeSmooth() - { - return beSmooth; - } - - void saveConfig(QSettings *settings) const; - IUAVGadgetConfiguration *clone(); - -private: - QString m_defaultDial; // The name of the dial's SVG source file - bool useOpenGLFlag; - bool hqFonts; - bool beSmooth; -}; - -#endif // PFDGADGETCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetfactory.cpp b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetfactory.cpp deleted file mode 100644 index 1e3725189..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetfactory.cpp +++ /dev/null @@ -1,58 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdgadgetfactory.cpp - * @author Edouard Lafargue Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 "pfdgadgetfactory.h" -#include "pfdgadgetwidget.h" -#include "pfdgadget.h" -#include "pfdgadgetconfiguration.h" -#include "pfdgadgetoptionspage.h" -#include - -PFDGadgetFactory::PFDGadgetFactory(QObject *parent) : - IUAVGadgetFactory(QString("PFDGadget"), - tr("Primary Flight Display"), - parent) -{} - -PFDGadgetFactory::~PFDGadgetFactory() -{} - -Core::IUAVGadget *PFDGadgetFactory::createGadget(QWidget *parent) -{ - PFDGadgetWidget *gadgetWidget = new PFDGadgetWidget(parent); - - return new PFDGadget(QString("PFDGadget"), gadgetWidget, parent); -} - -IUAVGadgetConfiguration *PFDGadgetFactory::createConfiguration(QSettings *qSettings) -{ - return new PFDGadgetConfiguration(QString("PFDGadget"), qSettings); -} - -IOptionsPage *PFDGadgetFactory::createOptionsPage(IUAVGadgetConfiguration *config) -{ - return new PFDGadgetOptionsPage(qobject_cast(config)); -} diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetfactory.h b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetfactory.h deleted file mode 100644 index be7867494..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetfactory.h +++ /dev/null @@ -1,51 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdgadgetfactory.h - * @author Edouard Lafargue Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 - */ - -#ifndef PFDGADGETFACTORY_H_ -#define PFDGADGETFACTORY_H_ - -#include - -namespace Core { -class IUAVGadget; -class IUAVGadgetFactory; -} - -using namespace Core; - -class PFDGadgetFactory : public IUAVGadgetFactory { - Q_OBJECT -public: - PFDGadgetFactory(QObject *parent = 0); - ~PFDGadgetFactory(); - - Core::IUAVGadget *createGadget(QWidget *parent); - IUAVGadgetConfiguration *createConfiguration(QSettings *qSettings); - IOptionsPage *createOptionsPage(IUAVGadgetConfiguration *config); -}; - -#endif // PFDGADGETFACTORY_H_ diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.cpp deleted file mode 100644 index 3af712dd4..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.cpp +++ /dev/null @@ -1,85 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdgadgetoptionspage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 "pfdgadgetoptionspage.h" -#include "pfdgadgetconfiguration.h" -#include "ui_pfdgadgetoptionspage.h" -#include "extensionsystem/pluginmanager.h" -#include "uavobjectmanager.h" -#include "uavdataobject.h" - - -#include -#include -#include - -PFDGadgetOptionsPage::PFDGadgetOptionsPage(PFDGadgetConfiguration *config, QObject *parent) : - IOptionsPage(parent), - m_config(config) -{} - -// creates options page widget (uses the UI file) -QWidget *PFDGadgetOptionsPage::createPage(QWidget *parent) -{ - Q_UNUSED(parent); - - options_page = new Ui::PFDGadgetOptionsPage(); - // main widget - QWidget *optionsPageWidget = new QWidget; - // main layout - options_page->setupUi(optionsPageWidget); - - - // Restore the contents from the settings: - options_page->svgSourceFile->setExpectedKind(Utils::PathChooser::File); - options_page->svgSourceFile->setPromptDialogFilter(tr("SVG image (*.svg)")); - options_page->svgSourceFile->setPromptDialogTitle(tr("Choose SVG image")); - options_page->svgSourceFile->setPath(m_config->dialFile()); - options_page->useOpenGL->setChecked(m_config->useOpenGL()); - options_page->hqText->setChecked(m_config->getHqFonts()); - options_page->smoothUpdates->setChecked(m_config->getBeSmooth()); - - return optionsPageWidget; -} - -/** - * Called when the user presses apply or OK. - * - * Saves the current values - * - */ -void PFDGadgetOptionsPage::apply() -{ - m_config->setDialFile(options_page->svgSourceFile->path()); - m_config->setUseOpenGL(options_page->useOpenGL->checkState()); - m_config->setHqFonts(options_page->hqText->checkState()); - m_config->setBeSmooth(options_page->smoothUpdates->checkState()); -} - - -void PFDGadgetOptionsPage::finish() -{} diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.h b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.h deleted file mode 100644 index 83ea51ded..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.h +++ /dev/null @@ -1,64 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdgadgetoptionspage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 - */ - -#ifndef PFDGADGETOPTIONSPAGE_H -#define PFDGADGETOPTIONSPAGE_H - -#include "coreplugin/dialogs/ioptionspage.h" -#include "QString" -#include -#include - -namespace Core { -class IUAVGadgetConfiguration; -} - -class PFDGadgetConfiguration; - -namespace Ui { -class PFDGadgetOptionsPage; -} - -using namespace Core; - -class PFDGadgetOptionsPage : public IOptionsPage { - Q_OBJECT -public: - explicit PFDGadgetOptionsPage(PFDGadgetConfiguration *config, QObject *parent = 0); - - QWidget *createPage(QWidget *parent); - void apply(); - void finish(); - -private: - Ui::PFDGadgetOptionsPage *options_page; - PFDGadgetConfiguration *m_config; - -private slots: -}; - -#endif // PFDGADGETOPTIONSPAGE_H diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.ui deleted file mode 100644 index 1373d2d3c..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.ui +++ /dev/null @@ -1,150 +0,0 @@ - - - PFDGadgetOptionsPage - - - - 0 - 0 - 430 - 306 - - - - - 0 - 0 - - - - Form - - - - 0 - - - - - QFrame::NoFrame - - - QFrame::Plain - - - true - - - - - 0 - 0 - 430 - 306 - - - - - 0 - - - - - 10 - - - QLayout::SetMaximumSize - - - 10 - - - - - PFD SVG: - - - - - - - - 0 - 0 - - - - - - - - - - - - true - - - Use OpenGL for rendering - - - true - - - - - - - High Quality text (OpenGL) - - - - - - - - - - - Smooth updates - - - true - - - - - - - - - Qt::Vertical - - - QSizePolicy::MinimumExpanding - - - - 20 - 40 - - - - - - - - - - - - - Utils::PathChooser - QWidget -
utils/pathchooser.h
- 1 -
-
- - -
diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp deleted file mode 100644 index 1ccf3a7e9..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp +++ /dev/null @@ -1,1133 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdgadgetwidget.cpp - * @author Edouard Lafargue Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 "pfdgadgetwidget.h" -#include -#include -#include -#include -#include -#include -#include - -PFDGadgetWidget::PFDGadgetWidget(QWidget *parent) : QGraphicsView(parent) -{ - setMinimumSize(64, 64); - setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); - setScene(new QGraphicsScene(this)); -// setRenderHint(QPainter::SmoothPixmapTransform); - - setViewportUpdateMode(QGraphicsView::FullViewportUpdate); - // setRenderHints(QPainter::Antialiasing | QPainter::TextAntialiasing); - // setRenderHints(QPainter::TextAntialiasing); - // setRenderHints(QPainter::HighQualityAntialiasing); - - m_renderer = new QSvgRenderer(); - - attitudeObj = NULL; - headingObj = NULL; - gcsBatteryObj = NULL; - gpsObj = NULL; - compassBandWidth = 0; - pfdError = true; - hqFonts = false; - rollTarget = 0; - rollValue = 0; - pitchTarget = 0; - pitchValue = 0; - headingTarget = 0; - headingValue = 0; - groundspeedTarget = 0; - groundspeedValue = 0; - altitudeTarget = 0; - altitudeValue = 0; - - // This timer mechanism makes needles rotate smoothly - connect(&dialTimer, SIGNAL(timeout()), this, SLOT(moveNeedles())); - dialTimer.start(30); - - connect(&skyDialTimer, SIGNAL(timeout()), this, SLOT(moveSky())); - skyDialTimer.start(30); -} - -PFDGadgetWidget::~PFDGadgetWidget() -{ - skyDialTimer.stop(); - dialTimer.stop(); -} - -void PFDGadgetWidget::setToolTipPrivate() -{ - static qint32 updateRate = 0; - UAVObject::Metadata mdata = attitudeObj->getMetadata(); - - if (mdata.flightTelemetryUpdatePeriod != updateRate) { - this->setToolTip("Current refresh rate:" + QString::number(mdata.flightTelemetryUpdatePeriod) + " miliseconds" + "\nIf you want to change it please edit the AttitudeState metadata on the object browser."); - } -} - -/*! - \brief Enables/Disables OpenGL - */ -void PFDGadgetWidget::enableOpenGL(bool flag) -{ - if (flag) { - setViewport(new QGLWidget(QGLFormat(QGL::SampleBuffers))); - } else { - setViewport(new QWidget); - } -} - -/*! - \brief Connects the widget to the relevant UAVObjects - - Should only be called after the PFD artwork is loaded. - We want: AttitudeState, FlightBattery, Location. - - */ -void PFDGadgetWidget::connectNeedles() -{ - if (attitudeObj != NULL) { - disconnect(attitudeObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateAttitude(UAVObject *))); - } - - if (headingObj != NULL) { - disconnect(headingObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateHeading(UAVObject *))); - } - - if (gcsBatteryObj != NULL) { - disconnect(gcsBatteryObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateBattery(UAVObject *))); - } - - if (gpsObj != NULL) { - disconnect(gpsObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateGPS(UAVObject *))); - } - - // Safeguard: if artwork did not load properly, don't go further - if (pfdError) { - return; - } - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - - airspeedObj = dynamic_cast(objManager->getObject("AirspeedState")); - if (airspeedObj != NULL) { - connect(airspeedObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateAirspeed(UAVObject *))); - } else { - qDebug() << "Error: Object is unknown (AirspeedState)."; - } - - groundspeedObj = dynamic_cast(objManager->getObject("VelocityState")); - if (groundspeedObj != NULL) { - connect(groundspeedObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateGroundspeed(UAVObject *))); - } else { - qDebug() << "Error: Object is unknown (VelocityState)."; - } - - altitudeObj = dynamic_cast(objManager->getObject("PositionState")); - if (altitudeObj != NULL) { - connect(altitudeObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateAltitude(UAVObject *))); - } else { - qDebug() << "Error: Object is unknown (PositionState)."; - } - - attitudeObj = dynamic_cast(objManager->getObject("AttitudeState")); - if (attitudeObj != NULL) { - connect(attitudeObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateAttitude(UAVObject *))); - } else { - qDebug() << "Error: Object is unknown (AttitudeState)."; - } - - headingObj = dynamic_cast(objManager->getObject("PositionState")); - if (headingObj != NULL) { - connect(headingObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateHeading(UAVObject *))); - } else { - qDebug() << "Error: Object is unknown (PositionState)."; - } - - if (gcsGPSStats) { - gpsObj = dynamic_cast(objManager->getObject("GPSPositionSensor")); - if (gpsObj != NULL) { - connect(gpsObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateGPS(UAVObject *))); - } else { - qDebug() << "Error: Object is unknown (GPSPositionSensor)."; - } - } - - if (gcsTelemetryArrow || gcsTelemetryStats) { - // Only register if the PFD wants link stats/status - gcsTelemetryObj = dynamic_cast(objManager->getObject("GCSTelemetryStats")); - if (gcsTelemetryObj != NULL) { - connect(gcsTelemetryObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateLinkStatus(UAVObject *))); - } else { - qDebug() << "Error: Object is unknown (GCSTelemetryStats)."; - } - } - - if (gcsBatteryStats) { // Only register if the PFD wants battery display - gcsBatteryObj = dynamic_cast(objManager->getObject("FlightBatteryState")); - if (gcsBatteryObj != NULL) { - connect(gcsBatteryObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateBattery(UAVObject *))); - } else { - qDebug() << "Error: Object is unknown (FlightBatteryState)."; - } - } -} - - -/*! - \brief Updates the GPS stats - */ -void PFDGadgetWidget::updateGPS(UAVObject *object1) -{ - UAVObjectField *field = object1->getField(QString("Satellites")); - UAVObjectField *field1 = object1->getField(QString("PDOP")); - - if (field && field1) { - QString s = QString("GPS: ") + field->getValue().toString() + "\nPDP: " - + field1->getValue().toString(); - if (s != satString) { - gcsGPSStats->setPlainText(s); - satString = s; - } - } -} - -/*! - \brief Updates the link stats - */ -void PFDGadgetWidget::updateLinkStatus(UAVObject *object1) -{ - // TODO: find a way to avoid updating the graphics if the value - // has not changed since the last update - // Double check that the field exists: - QString st = QString("Status"); - QString tdr = QString("TxDataRate"); - QString rdr = QString("RxDataRate"); - UAVObjectField *field = object1->getField(st); - UAVObjectField *field2 = object1->getField(tdr); - UAVObjectField *field3 = object1->getField(rdr); - - if (field && field2 && field3) { - QString s = field->getValue().toString(); - if (m_renderer->elementExists("gcstelemetry-" + s) && gcsTelemetryArrow) { - gcsTelemetryArrow->setElementId("gcstelemetry-" + s); - } else { // Safeguard - gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected"); - } - double v1 = field2->getDouble(); - double v2 = field3->getDouble(); - s.sprintf("%.0f/%.0f", v1, v2); - if (gcsTelemetryStats) { - gcsTelemetryStats->setPlainText(s); - } - } else { - qDebug() << "UpdateLinkStatus: Wrong field, maybe an issue with object disconnection ?"; - } -} - -/*! - \brief Reads the updated attitude and computes the new display position - - Resolution is 1 degree roll & 1/7.5 degree pitch. - */ -void PFDGadgetWidget::updateAttitude(UAVObject *object1) -{ - setToolTipPrivate(); - UAVObjectField *rollField = object1->getField(QString("Roll")); - UAVObjectField *yawField = object1->getField(QString("Yaw")); - UAVObjectField *pitchField = object1->getField(QString("Pitch")); - if (rollField && yawField && pitchField) { - // These factors assume some things about the PFD SVG, namely: - // - Roll, Pitch and Heading value in degrees - // - Pitch lines are 300px high for a +20/-20 range, which means - // 7.5 pixels per pitch degree. - // TODO: loosen this constraint and only require a +/- 20 deg range, - // and compute the height from the SVG element. - // Also: keep the integer value only, to avoid unnecessary redraws - rollTarget = -floor(rollField->getDouble() * 10) / 10; - if ((rollTarget - rollValue) > 180) { - rollValue += 360; - } else if (((rollTarget - rollValue) < -180)) { - rollValue -= 360; - } - pitchTarget = floor(pitchField->getDouble() * 7.5); - - // These factors assume some things about the PFD SVG, namely: - // - Heading value in degrees - // - "Scale" element is 540 degrees wide - - // Corvus Corax: "If you want a smooth transition between two angles, It is usually solved that by substracting - // one from another, and if the result is >180 or <-180 I substract (respectively add) 360 degrees - // to it. That way you always get the "shorter difference" to turn in." - double fac = compassBandWidth / 540; - headingTarget = yawField->getDouble() * (-fac); - if (headingTarget != headingTarget) { - headingTarget = headingValue; // NaN checking. - } - if ((headingValue - headingTarget) / fac > 180) { - headingTarget += 360 * fac; - } else if (((headingValue - headingTarget) / fac < -180)) { - headingTarget -= 360 * fac; - } - headingTarget = floor(headingTarget * 10) / 10; // Avoid stupid redraws - - if (!dialTimer.isActive()) { - dialTimer.start(); // Rearm the dial Timer which might be stopped. - } - } else { - qDebug() << "Unable to get one of the fields for attitude update"; - } -} - -/*! - \brief Updates the compass reading and speed dial. - - This also updates speed & altitude according to PositionState data. - - Note: the speed dial shows the ground speed at the moment, because - there is no airspeed by default. Should become configurable in a future - gadget release (TODO) - */ -void PFDGadgetWidget::updateHeading(UAVObject *object) -{ - Q_UNUSED(object); -} - -/*! - \brief Called by updates to @PositionState to compute groundspeed from velocity - */ -void PFDGadgetWidget::updateGroundspeed(UAVObject *object) -{ - UAVObjectField *northField = object->getField("North"); - UAVObjectField *eastField = object->getField("East"); - - if (northField && eastField) { - double val = floor(sqrt(pow(northField->getDouble(), 2) + pow(eastField->getDouble(), 2)) * 10) / 10; - groundspeedTarget = 3.6 * val * speedScaleHeight / 30; - - if (!dialTimer.isActive()) { - dialTimer.start(); // Rearm the dial Timer which might be stopped. - } - } else { - qDebug() << "UpdateHeading: Wrong field, maybe an issue with object disconnection ?"; - } -} - - -/*! - \brief Called by updates to @AirspeedState - */ -void PFDGadgetWidget::updateAirspeed(UAVObject *object) -{ - UAVObjectField *airspeedField = object->getField("CalibratedAirspeed"); - - if (airspeedField) { - airspeedTarget = airspeedField->getDouble(); - - if (!dialTimer.isActive()) { - dialTimer.start(); // Rearm the dial Timer which might be stopped. - } - } else { - qDebug() << "UpdateHeading: Wrong field, maybe an issue with object disconnection ?"; - } -} - -/*! - \brief Called by the @ref PositionState updates to show altitude - */ -void PFDGadgetWidget::updateAltitude(UAVObject *object) -{ - UAVObjectField *downField = object->getField("Down"); - - if (downField) { - altitudeTarget = -downField->getDouble(); - - if (!dialTimer.isActive()) { - dialTimer.start(); // Rearm the dial Timer which might be stopped. - } - } else { - qDebug() << "Unable to get field for altitude update. Obj: " << object->getName(); - } -} - - -/*! - \brief Called by the UAVObject which got updated - */ -void PFDGadgetWidget::updateBattery(UAVObject *object1) -{ - // Double check that the field exists: - QString voltage = QString("Voltage"); - QString current = QString("Current"); - QString energy = QString("ConsumedEnergy"); - UAVObjectField *field = object1->getField(voltage); - UAVObjectField *field2 = object1->getField(current); - UAVObjectField *field3 = object1->getField(energy); - - if (field && field2 && field3) { - QString s = QString(); - double v0 = field->getDouble(); - double v1 = field2->getDouble(); - double v2 = field3->getDouble(); - s.sprintf("%.2fV\n%.2fA\n%.0fmAh", v0, v1, v2); - if (s != batString) { - gcsBatteryStats->setPlainText(s); - batString = s; - } - } else { - qDebug() << "UpdateBattery: Wrong field, maybe an issue with object disconnection ?"; - } -} - - -/*! - \brief Sets up the PFD from the SVG master file. - - Initializes the display, and does all the one-time calculations. - */ -void PFDGadgetWidget::setDialFile(QString dfn) -{ - QGraphicsScene *l_scene = scene(); - - setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); - if (QFile::exists(dfn) && m_renderer->load(dfn) && m_renderer->isValid()) { -/* The PFD element IDs are fixed, not like with the analog dial. - - Background: background - - Foreground: foreground (contains all fixed elements, including plane) - - earth/sky : world - - Roll scale: rollscale - - compass frame: compass (part of the foreground) - - compass band : compass-band - - Home point: homewaypoint - - Next point: nextwaypoint - - Home point bearing: homewaypoint-bearing - - Next point bearing: nextwaypoint-bearing - - Speed rectangle (left side): speed-bg - - Speed scale: speed-scale. - - Black speed window: speed-window. - - Altitude rectangle (right site): altitude-bg. - - Altitude scale: altitude-scale. - - Black altitude window: altitude-window. - - GCS Telemetry status arrow: gcstelemetry-XXXX - - Telemetry link rate: linkrate - - GPS status text: gps-txt - - Battery stats: battery-txt - */ - l_scene->clear(); // Deletes all items contained in the scene as well. - m_background = new CachedSvgItem(); - // All other items will be clipped to the shape of the background - m_background->setFlags(QGraphicsItem::ItemClipsChildrenToShape | - QGraphicsItem::ItemClipsToShape); - m_background->setSharedRenderer(m_renderer); - m_background->setElementId("background"); - l_scene->addItem(m_background); - - m_world = new CachedSvgItem(); - m_world->setParentItem(m_background); - m_world->setSharedRenderer(m_renderer); - m_world->setElementId("world"); - l_scene->addItem(m_world); - - // red Roll scale: rollscale - m_rollscale = new CachedSvgItem(); - m_rollscale->setSharedRenderer(m_renderer); - m_rollscale->setElementId("rollscale"); - l_scene->addItem(m_rollscale); - - // Home point: - m_homewaypoint = new CachedSvgItem(); - // Next point: - m_nextwaypoint = new CachedSvgItem(); - // Home point bearing: - m_homepointbearing = new CachedSvgItem(); - // Next point bearing: - m_nextpointbearing = new CachedSvgItem(); - - QGraphicsSvgItem *m_foreground = new CachedSvgItem(); - m_foreground->setParentItem(m_background); - m_foreground->setSharedRenderer(m_renderer); - m_foreground->setElementId("foreground"); - l_scene->addItem(m_foreground); - - //////////////////// - // Compass - //////////////////// - // Get the default location of the Compass: - QMatrix compassMatrix = m_renderer->matrixForElement("compass"); - qreal startX = compassMatrix.mapRect(m_renderer->boundsOnElement("compass")).x(); - qreal startY = compassMatrix.mapRect(m_renderer->boundsOnElement("compass")).y(); - // Then once we have the initial location, we can put it - // into a QGraphicsSvgItem which we will display at the same - // place: we do this so that the heading scale can be clipped to - // the compass dial region. - m_compass = new CachedSvgItem(); - m_compass->setSharedRenderer(m_renderer); - m_compass->setElementId("compass"); - m_compass->setFlags(QGraphicsItem::ItemClipsChildrenToShape | - QGraphicsItem::ItemClipsToShape); - l_scene->addItem(m_compass); - QTransform matrix; - matrix.translate(startX, startY); - m_compass->setTransform(matrix, false); - - // Now place the compass scale inside: - m_compassband = new CachedSvgItem(); - m_compassband->setSharedRenderer(m_renderer); - m_compassband->setElementId("compass-band"); - m_compassband->setParentItem(m_compass); - l_scene->addItem(m_compassband); - matrix.reset(); - // Note: the compass band has to be a path, which means all text elements have to be - // converted, ortherwise boundsOnElement does not compute the height correctly - // if the highest element is a text element. This is a Qt Bug as far as I can tell. - - // compass-scale is the while bottom line inside the band: using the band's width - // includes half the width of the letters, which causes errors: - compassBandWidth = m_renderer->boundsOnElement("compass-scale").width(); - - //////////////////// - // Speed - //////////////////// - // Speedometer on the left hand: - // - compassMatrix = m_renderer->matrixForElement("speed-bg"); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-bg")).x(); - startY = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-bg")).y(); - QGraphicsSvgItem *verticalbg = new CachedSvgItem(); - verticalbg->setSharedRenderer(m_renderer); - verticalbg->setElementId("speed-bg"); - verticalbg->setFlags(QGraphicsItem::ItemClipsChildrenToShape | - QGraphicsItem::ItemClipsToShape); - l_scene->addItem(verticalbg); - matrix.reset(); - matrix.translate(startX, startY); - verticalbg->setTransform(matrix, false); - - // Note: speed-scale should contain exactly 6 major ticks - // for 30km/h - m_speedscale = new QGraphicsItemGroup(); - m_speedscale->setParentItem(verticalbg); - - QGraphicsSvgItem *speedscalelines = new CachedSvgItem(); - speedscalelines->setSharedRenderer(m_renderer); - speedscalelines->setElementId("speed-scale"); - speedScaleHeight = m_renderer->matrixForElement("speed-scale").mapRect( - m_renderer->boundsOnElement("speed-scale")).height(); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-bg")).width(); - startX -= m_renderer->matrixForElement("speed-scale").mapRect( - m_renderer->boundsOnElement("speed-scale")).width(); - matrix.reset(); - matrix.translate(startX, 0); - speedscalelines->setTransform(matrix, false); - // Quick way to reposition the item before putting it in the group: - speedscalelines->setParentItem(verticalbg); - m_speedscale->addToGroup(speedscalelines); // (reparents the item) - - // Add the scale text elements: - QGraphicsTextItem *speed0 = new QGraphicsTextItem("0"); - speed0->setDefaultTextColor(QColor("White")); - speed0->setFont(QFont("Arial", (int)speedScaleHeight / 30)); - if (hqFonts) { - speed0->setCacheMode(QGraphicsItem::DeviceCoordinateCache); - } - matrix.reset(); - matrix.translate(compassMatrix.mapRect(m_renderer->boundsOnElement("speed-bg")).width() / 10, -speedScaleHeight / 30); - speed0->setTransform(matrix, false); - speed0->setParentItem(verticalbg); - m_speedscale->addToGroup(speed0); - for (int i = 0; i < 6; i++) { - speed0 = new QGraphicsTextItem(""); - speed0->setDefaultTextColor(QColor("White")); - speed0->setFont(QFont("Arial", (int)speedScaleHeight / 30)); - speed0->setPlainText(QString().setNum(i * 5 + 1)); - if (hqFonts) { - speed0->setCacheMode(QGraphicsItem::DeviceCoordinateCache); - } - matrix.translate(0, speedScaleHeight / 6); - speed0->setTransform(matrix, false); - speed0->setParentItem(verticalbg); - m_speedscale->addToGroup(speed0); - } - // Now vertically center the speed scale on the speed background - QRectF rectB = verticalbg->boundingRect(); - QRectF rectN = speedscalelines->boundingRect(); - m_speedscale->setPos(0, rectB.height() / 2 - rectN.height() / 2 - rectN.height() / 6); - - // Isolate the speed window and put it above the speed scale - compassMatrix = m_renderer->matrixForElement("speed-window"); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).x(); - startY = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).y(); - qreal speedWindowHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).height(); - QGraphicsSvgItem *speedwindow = new CachedSvgItem(); - speedwindow->setSharedRenderer(m_renderer); - speedwindow->setElementId("speed-window"); - speedwindow->setFlags(QGraphicsItem::ItemClipsChildrenToShape | - QGraphicsItem::ItemClipsToShape); - l_scene->addItem(speedwindow); - matrix.reset(); - matrix.translate(startX, startY); - speedwindow->setTransform(matrix, false); - - // Last create a Text Item at the location of the speed window - // and save it for future updates: - m_speedtext = new QGraphicsTextItem("0000"); - m_speedtext->setDefaultTextColor(QColor("White")); - m_speedtext->setFont(QFont("Arial", (int)speedWindowHeight / 2)); - if (hqFonts) { - m_speedtext->setCacheMode(QGraphicsItem::DeviceCoordinateCache); - } - m_speedtext->setParentItem(speedwindow); - - //////////////////// - // Altitude - //////////////////// - // Right hand, very similar to speed - compassMatrix = m_renderer->matrixForElement("altitude-bg"); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-bg")).x(); - startY = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-bg")).y(); - verticalbg = new CachedSvgItem(); - verticalbg->setSharedRenderer(m_renderer); - verticalbg->setElementId("altitude-bg"); - verticalbg->setFlags(QGraphicsItem::ItemClipsChildrenToShape | - QGraphicsItem::ItemClipsToShape); - l_scene->addItem(verticalbg); - matrix.reset(); - matrix.translate(startX, startY); - verticalbg->setTransform(matrix, false); - - // Note: altitude-scale should contain exactly 6 major ticks - // for 30 meters - m_altitudescale = new QGraphicsItemGroup(); - m_altitudescale->setParentItem(verticalbg); - - QGraphicsSvgItem *altitudescalelines = new CachedSvgItem(); - altitudescalelines->setSharedRenderer(m_renderer); - altitudescalelines->setElementId("altitude-scale"); - altitudeScaleHeight = m_renderer->matrixForElement("altitude-scale").mapRect( - m_renderer->boundsOnElement("altitude-scale")).height(); - // Quick way to reposition the item before putting it in the group: - altitudescalelines->setParentItem(verticalbg); - m_altitudescale->addToGroup(altitudescalelines); // (reparents the item) - - // Add the scale text elements: - speed0 = new QGraphicsTextItem("XXXX"); - speed0->setDefaultTextColor(QColor("White")); - speed0->setFont(QFont("Arial", (int)altitudeScaleHeight / 30)); - if (hqFonts) { - speed0->setCacheMode(QGraphicsItem::DeviceCoordinateCache); - } - matrix.reset(); - matrix.translate(m_renderer->matrixForElement("altitude-scale").mapRect(m_renderer->boundsOnElement("altitude-scale")).width() - + m_renderer->matrixForElement("altitude-bg").mapRect(m_renderer->boundsOnElement("altitude-bg")).width() / 10, -altitudeScaleHeight / 30); - speed0->setTransform(matrix, false); - speed0->setParentItem(verticalbg); - m_altitudescale->addToGroup(speed0); - for (int i = 0; i < 6; i++) { - speed0 = new QGraphicsTextItem("XXXX"); - speed0->setDefaultTextColor(QColor("White")); - speed0->setFont(QFont("Arial", (int)altitudeScaleHeight / 30)); - speed0->setPlainText(QString().setNum(i * 5 + 1)); - if (hqFonts) { - speed0->setCacheMode(QGraphicsItem::DeviceCoordinateCache); - } - matrix.translate(0, altitudeScaleHeight / 6); - speed0->setTransform(matrix, false); - speed0->setParentItem(verticalbg); - m_altitudescale->addToGroup(speed0); - } - // Now vertically center the speed scale on the speed background - rectB = verticalbg->boundingRect(); - rectN = altitudescalelines->boundingRect(); - m_altitudescale->setPos(0, rectB.height() / 2 - rectN.height() / 2 - rectN.height() / 6); - - // Isolate the Altitude window and put it above the altitude scale - compassMatrix = m_renderer->matrixForElement("altitude-window"); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).x(); - startY = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).y(); - qreal altitudeWindowHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).height(); - QGraphicsSvgItem *altitudewindow = new CachedSvgItem(); - altitudewindow->setSharedRenderer(m_renderer); - altitudewindow->setElementId("altitude-window"); - altitudewindow->setFlags(QGraphicsItem::ItemClipsChildrenToShape | - QGraphicsItem::ItemClipsToShape); - l_scene->addItem(altitudewindow); - matrix.reset(); - matrix.translate(startX, startY); - altitudewindow->setTransform(matrix, false); - - // Last create a Text Item at the location of the speed window - // and save it for future updates: - m_altitudetext = new QGraphicsTextItem("0000"); - m_altitudetext->setDefaultTextColor(QColor("White")); - m_altitudetext->setFont(QFont("Arial", (int)altitudeWindowHeight / 2)); - if (hqFonts) { - m_altitudetext->setCacheMode(QGraphicsItem::DeviceCoordinateCache); - } - m_altitudetext->setParentItem(altitudewindow); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).width() / 10; - matrix.reset(); - matrix.translate(startX, 0); - m_altitudetext->setTransform(matrix, false); - - //////////////// - // GCS Telemetry Indicator - //////////////// - if (m_renderer->elementExists("gcstelemetry-Disconnected")) { - compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected"); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x(); - startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y(); - gcsTelemetryArrow = new CachedSvgItem(); - gcsTelemetryArrow->setSharedRenderer(m_renderer); - gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected"); - l_scene->addItem(gcsTelemetryArrow); - matrix.reset(); - matrix.translate(startX, startY); - gcsTelemetryArrow->setTransform(matrix, false); - } else { - gcsTelemetryArrow = NULL; - } - - if (m_renderer->elementExists("linkrate")) { - compassMatrix = m_renderer->matrixForElement("linkrate"); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("linkrate")).x(); - startY = compassMatrix.mapRect(m_renderer->boundsOnElement("linkrate")).y(); - qreal linkRateHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("linkrate")).height(); - gcsTelemetryStats = new QGraphicsTextItem(); - gcsTelemetryStats->setDefaultTextColor(QColor("White")); - gcsTelemetryStats->setFont(QFont("Arial", (int)linkRateHeight)); - if (hqFonts) { - gcsTelemetryStats->setCacheMode(QGraphicsItem::DeviceCoordinateCache); - } - l_scene->addItem(gcsTelemetryStats); - matrix.reset(); - matrix.translate(startX, startY - linkRateHeight / 2); - gcsTelemetryStats->setTransform(matrix, false); - } else { - gcsTelemetryStats = NULL; - } - - - //////////////// - // GCS Battery Indicator - //////////////// - /* (to be used the day I add a green/yellow/red indicator) - compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected"); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x(); - startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y(); - gcsTelemetryArrow = new CachedSvgItem(); - gcsTelemetryArrow->setSharedRenderer(m_renderer); - gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected"); - l_scene->addItem(gcsTelemetryArrow); - matrix.reset(); - matrix.translate(startX,startY); - gcsTelemetryArrow->setTransform(matrix,false); - */ - - if (m_renderer->elementExists("battery-txt")) { - compassMatrix = m_renderer->matrixForElement("battery-txt"); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("battery-txt")).x(); - startY = compassMatrix.mapRect(m_renderer->boundsOnElement("battery-txt")).y(); - qreal batStatHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("battery-txt")).height(); - gcsBatteryStats = new QGraphicsTextItem("Battery"); - gcsBatteryStats->setDefaultTextColor(QColor("White")); - gcsBatteryStats->setFont(QFont("Arial", (int)batStatHeight)); - if (hqFonts) { - gcsBatteryStats->setCacheMode(QGraphicsItem::DeviceCoordinateCache); - } - l_scene->addItem(gcsBatteryStats); - matrix.reset(); - matrix.translate(startX, startY - batStatHeight / 2); - gcsBatteryStats->setTransform(matrix, false); - } else { - gcsBatteryStats = NULL; - } - - //////////////// - // GCS GPS Indicator - //////////////// - /* (to be used the day I add a green/yellow/red indicator) - compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected"); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x(); - startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y(); - gcsTelemetryArrow = new CachedSvgItem(); - gcsTelemetryArrow->setSharedRenderer(m_renderer); - gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected"); - l_scene->addItem(gcsTelemetryArrow); - matrix.reset(); - matrix.translate(startX,startY); - gcsTelemetryArrow->setTransform(matrix,false); - */ - - if (m_renderer->elementExists("gps-txt")) { - compassMatrix = m_renderer->matrixForElement("gps-txt"); - startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gps-txt")).x(); - startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gps-txt")).y(); - qreal gpsStatHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("gps-txt")).height(); - gcsGPSStats = new QGraphicsTextItem("GPS"); - gcsGPSStats->setDefaultTextColor(QColor("White")); - gcsGPSStats->setFont(QFont("Arial", (int)gpsStatHeight)); - if (hqFonts) { - gcsGPSStats->setCacheMode(QGraphicsItem::DeviceCoordinateCache); - } - l_scene->addItem(gcsGPSStats); - matrix.reset(); - matrix.translate(startX, startY - gpsStatHeight / 2); - gcsGPSStats->setTransform(matrix, false); - } else { - gcsGPSStats = NULL; - } - - l_scene->setSceneRect(m_background->boundingRect()); - - ///////////////// - // Item placement - ///////////////// - - // Now Initialize the center for all transforms of the relevant elements to the - // center of the background: - - // 1) Move the center of the needle to the center of the background. - rectB = m_background->boundingRect(); - rectN = m_world->boundingRect(); - m_world->setPos(rectB.width() / 2 - rectN.width() / 2, rectB.height() / 2 - rectN.height() / 2); - // 2) Put the transform origin point of the needle at its center. - m_world->setTransformOriginPoint(rectN.width() / 2, rectN.height() / 2); - - rectN = m_rollscale->boundingRect(); - m_rollscale->setPos(rectB.width() / 2 - rectN.width() / 2, rectB.height() / 2 - rectN.height() / 2); - m_rollscale->setTransformOriginPoint(rectN.width() / 2, rectN.height() / 2); - - // Also to the same init for the compass: - rectB = m_compass->boundingRect(); - rectN = m_compassband->boundingRect(); - m_compassband->setPos(rectB.width() / 2 - rectN.width() / 2, rectB.height() / 2 - rectN.height() / 2); - m_compassband->setTransformOriginPoint(rectN.width() / 2, rectN.height() / 2); - - // Last: we just loaded the dial file which is by default valid for a "zero" value - // of the needles, so we have to reset the needles too upon dial file loading, otherwise - // we would end up with an offset when we change a dial file and the needle value - // is not zero at that time. - rollValue = 0; - pitchValue = 0; - headingValue = 0; - groundspeedValue = 0; - altitudeValue = 0; - pfdError = false; - if (!dialTimer.isActive()) { - dialTimer.start(); // Rearm the dial Timer which might be stopped. - } - } else { qDebug() << "Error on PFD artwork file."; - m_renderer->load(QString(":/pfd/images/pfd-default.svg")); - l_scene->clear(); // This also deletes all items contained in the scene. - m_background = new CachedSvgItem(); - m_background->setSharedRenderer(m_renderer); - l_scene->addItem(m_background); - pfdError = true; } -} - -void PFDGadgetWidget::paint() -{ - // update(); -} - -void PFDGadgetWidget::paintEvent(QPaintEvent *event) -{ - // Skip painting until the dial file is loaded - if (!m_renderer->isValid()) { - qDebug() << "Dial file not loaded, not rendering"; - return; - } - QGraphicsView::paintEvent(event); -} - -// This event enables the dial to be dynamically resized -// whenever the gadget is resized, taking advantage of the vector -// nature of SVG dials. -void PFDGadgetWidget::resizeEvent(QResizeEvent *event) -{ - Q_UNUSED(event); - fitInView(m_background, Qt::KeepAspectRatio); -} - - -/*! - \brief Update method for the vertical scales - */ -void PFDGadgetWidget::moveVerticalScales() {} - -void PFDGadgetWidget::moveSky() -{ - int dialCount = 2; // Gets decreased by one for each element - - // which has finished moving -// qDebug() << "MoveSky"; - /// TODO: optimize!!! - if (pfdError) { - // skyDialTimer.stop(); - return; - } - - // In some instances, it can happen that the rollValue & target are - // invalid inside the UAVObjects, and become a "nan" value, which freezes - // the PFD and the whole GCS: for this reason, we check this here. - // The strange check below works, it is a workaround because "isnan(double)" - // is not supported on every compiler. - if (rollTarget != rollTarget || pitchTarget != pitchTarget) { - return; - } - ////// - // Roll - ////// - if (rollValue != rollTarget) { - double rollDiff; - if ((abs((rollValue - rollTarget) * 10) > 5) && beSmooth) { - rollDiff = (rollTarget - rollValue) / 2; - } else { - rollDiff = rollTarget - rollValue; - dialCount--; - } - m_world->setRotation(m_world->rotation() + rollDiff); - m_rollscale->setRotation(m_rollscale->rotation() + rollDiff); - rollValue += rollDiff; - } else { - dialCount--; - } - - ////// - // Pitch - ////// - if (pitchValue != pitchTarget) { - double pitchDiff; - if ((abs((pitchValue - pitchTarget) * 10) > 5) && beSmooth) { - // if (0) { - pitchDiff = (pitchTarget - pitchValue) / 2; - } else { - pitchDiff = pitchTarget - pitchValue; - dialCount--; - } - QPointF opd = QPointF(0, pitchDiff); - m_world->setTransform(QTransform::fromTranslate(opd.x(), opd.y()), true); - QPointF oop = m_world->transformOriginPoint(); - m_world->setTransformOriginPoint((oop.x() - opd.x()), (oop.y() - opd.y())); - pitchValue += pitchDiff; - } else { - dialCount--; - } - - if (dialCount) { - scene()->update(sceneRect()); - } - // if (!dialCount) - // skyDialTimer.stop(); -} - - -// Take an input value and move the elements accordingly. -// Movement is smooth, starts fast and slows down when -// approaching the target. -// -void PFDGadgetWidget::moveNeedles() -{ - int dialCount = 3; // Gets decreased by one for each element - - // which has finished moving - -// qDebug() << "MoveNeedles"; - /// TODO: optimize!!! - - if (pfdError) { - dialTimer.stop(); - return; - } - - ////// - // Heading - // - // If you want a smooth transition between two angles, It is usually solved that by substracting - // one from another, and if the result is >180 or <-180 I substract (respectively add) 360 degrees - // to it. That way you always get the "shorter difference" to turn in. - ////// - if (headingValue != headingTarget) { - double headingDiff; - if ((abs((headingValue - headingTarget) * 10) > 5) && beSmooth) { - headingDiff = (headingTarget - headingValue) / 5; - } else { - headingDiff = headingTarget - headingValue; - dialCount--; - } - double threshold = 180 * compassBandWidth / 540; - // Note: rendering can jump oh so very slightly when crossing the 180 degree - // boundary, should not impact actual useability of the display. - if ((headingValue + headingDiff) >= threshold) { - // We went over 180°: activate a -360 degree offset - headingDiff -= 2 * threshold; - headingTarget -= 2 * threshold; - } else if ((headingValue + headingDiff) < -threshold) { - // We went under -180°: remove the -360 degree offset - headingDiff += 2 * threshold; - headingTarget += 2 * threshold; - } - QPointF opd = QPointF(headingDiff, 0); - m_compassband->setTransform(QTransform::fromTranslate(opd.x(), opd.y()), true); - headingValue += headingDiff; - } else { - dialCount--; - } - - ////// - // Airspeed - ////// - if (airspeedValue != airspeedTarget) { - if ((abs(airspeedValue - airspeedTarget) > speedScaleHeight / 100) && beSmooth) { - airspeedValue += (airspeedTarget - airspeedValue) / 2; - } else { - airspeedValue = airspeedTarget; - dialCount--; - } - - float airspeed_kph = airspeedValue * 3.6; - float airspeed_kph_scale = airspeed_kph * speedScaleHeight / 30; - - qreal x = m_speedscale->transform().dx(); - // opd = QPointF(x,fmod(airspeed_kph,speedScaleHeight/6)); - // fmod does rounding errors!! the formula below works better: - QPointF opd = QPointF(x, airspeed_kph_scale - floor(airspeed_kph_scale / speedScaleHeight * 6) * speedScaleHeight / 6); - m_speedscale->setTransform(QTransform::fromTranslate(opd.x(), opd.y()), false); - - double speedText = airspeed_kph; - QString s = QString().sprintf("%.0f", speedText); - m_speedtext->setPlainText(s); - - // Now update the text elements inside the scale: - // (Qt documentation states that the list has the same order - // as the item add order in the QGraphicsItemGroup) - QList textList = m_speedscale->childItems(); - qreal val = 5 * floor(airspeed_kph_scale / speedScaleHeight * 6) + 20; - foreach(QGraphicsItem * item, textList) { - if (QGraphicsTextItem * text = qgraphicsitem_cast(item)) { - QString s = (val < 0) ? QString() : QString().sprintf("%.0f", val); - if (text->toPlainText() == s) { - break; // This should happen at element one if is has not changed, indicating - } - // that it's not necessary to do the rest of the list - text->setPlainText(s); - val -= 5; - } - } - } else { - dialCount--; - } - - ////// - // Groundspeed - ////// - if (groundspeedValue != groundspeedTarget) { - groundspeedValue = groundspeedTarget; - qreal x = m_speedscale->transform().dx(); - // opd = QPointF(x,fmod(groundspeedValue,speedScaleHeight/6)); - // fmod does rounding errors!! the formula below works better: - QPointF opd = QPointF(x, groundspeedValue - floor(groundspeedValue / speedScaleHeight * 6) * speedScaleHeight / 6); - m_speedscale->setTransform(QTransform::fromTranslate(opd.x(), opd.y()), false); - - double speedText = groundspeedValue / speedScaleHeight * 30; - QString s = QString().sprintf("%.0f", speedText); - m_speedtext->setPlainText(s); - - // Now update the text elements inside the scale: - // (Qt documentation states that the list has the same order - // as the item add order in the QGraphicsItemGroup) - QList textList = m_speedscale->childItems(); - qreal val = 5 * floor(groundspeedValue / speedScaleHeight * 6) + 20; - foreach(QGraphicsItem * item, textList) { - if (QGraphicsTextItem * text = qgraphicsitem_cast(item)) { - QString s = (val < 0) ? QString() : QString().sprintf("%.0f", val); - if (text->toPlainText() == s) { - break; // This should happen at element one if is has not changed, indicating - } - // that it's not necessary to do the rest of the list - text->setPlainText(s); - val -= 5; - } - } - } - - ////// - // Altitude - ////// - if (altitudeValue != altitudeTarget) { - if ((abs(altitudeValue - altitudeTarget) > altitudeScaleHeight / 100) && beSmooth) { - altitudeValue += (altitudeTarget - altitudeValue) / 2; - } else { - altitudeValue = altitudeTarget; - dialCount--; - } - - // The altitude scale represents 30 meters - float altitudeValue_scale = floor(altitudeValue * 10) / 10 * altitudeScaleHeight / 30; - - qreal x = m_altitudescale->transform().dx(); - // opd = QPointF(x,fmod(altitudeValue,altitudeScaleHeight/6)); - // fmod does rounding errors!! the formula below works better: - QPointF opd = QPointF(x, altitudeValue_scale - floor(altitudeValue_scale / altitudeScaleHeight * 6) * altitudeScaleHeight / 6); - m_altitudescale->setTransform(QTransform::fromTranslate(opd.x(), opd.y()), false); - - double altitudeText = altitudeValue; - QString s = QString().sprintf("%.0f", altitudeText); - m_altitudetext->setPlainText(s); - - // Now update the text elements inside the scale: - // (Qt documentation states that the list has the same order - // as the item add order in the QGraphicsItemGroup) - QList textList = m_altitudescale->childItems(); - qreal val = 5 * floor(altitudeValue_scale / altitudeScaleHeight * 6) + 20; - foreach(QGraphicsItem * item, textList) { - if (QGraphicsTextItem * text = qgraphicsitem_cast(item)) { - QString s = (val < 0) ? QString() : QString().sprintf("%.0f", val); - if (text->toPlainText() == s) { - break; // This should happen at element one if is has not changed, indicating - } - // that it's not necessary to do the rest of the list - text->setPlainText(s); - val -= 5; - } - } - } else { - dialCount--; - } - - if (!dialCount) { - dialTimer.stop(); - } else { - scene()->update(sceneRect()); - } -} - -/** - @} - @} - */ diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.h b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.h deleted file mode 100644 index d80b73432..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.h +++ /dev/null @@ -1,160 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdgadgetwidget.h - * @author Edouard Lafargue Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 - */ - -#ifndef PFDGADGETWIDGET_H_ -#define PFDGADGETWIDGET_H_ - -#include "pfdgadgetconfiguration.h" -#include "extensionsystem/pluginmanager.h" -#include "uavobjectmanager.h" -#include "uavobject.h" -#include -#include -#include - -#include -#include - -class PFDGadgetWidget : public QGraphicsView { - Q_OBJECT - -public: - PFDGadgetWidget(QWidget *parent = 0); - ~PFDGadgetWidget(); - void setDialFile(QString dfn); - void paint(); - // Sets up needle/UAVObject connections: - void connectNeedles(); - void enableOpenGL(bool flag); - void setHqFonts(bool flag) - { - hqFonts = flag; - } - void enableSmoothUpdates(bool flag) - { - beSmooth = flag; - } - - -public slots: - void updateAttitude(UAVObject *object1); - void updateHeading(UAVObject *object1); - void updateGPS(UAVObject *object1); - void updateGroundspeed(UAVObject *object1); - void updateAirspeed(UAVObject *object1); - void updateAltitude(UAVObject *object1); - void updateBattery(UAVObject *object1); - void updateLinkStatus(UAVObject *object1); - -protected: - void paintEvent(QPaintEvent *event); - void resizeEvent(QResizeEvent *event); - - -private slots: - void moveNeedles(); - void moveVerticalScales(); - void moveSky(); - void setToolTipPrivate(); -private: - QSvgRenderer *m_renderer; - - // Background: background - QGraphicsSvgItem *m_background; - // earth/sky : world - QGraphicsSvgItem *m_world; - // Roll scale: rollscale - QGraphicsSvgItem *m_rollscale; - // Compass dial: - QGraphicsSvgItem *m_compass; - // Compass band: - QGraphicsSvgItem *m_compassband; - // Home point: - QGraphicsSvgItem *m_homewaypoint; - // Next point: - QGraphicsSvgItem *m_nextwaypoint; - // Home point bearing: - QGraphicsSvgItem *m_homepointbearing; - // Next point bearing: - QGraphicsSvgItem *m_nextpointbearing; - // Speed scale: - QGraphicsItemGroup *m_speedscale; - // Speed indicator text: - QGraphicsTextItem *m_speedtext; - // Vertical altitude scale: - QGraphicsItemGroup *m_altitudescale; - // Altitude indicator text: - QGraphicsTextItem *m_altitudetext; - // GCS link status Arrow - QGraphicsSvgItem *gcsTelemetryArrow; - QGraphicsTextItem *gcsTelemetryStats; - QGraphicsTextItem *gcsBatteryStats; - QGraphicsTextItem *gcsGPSStats; - - // The Value and target variables - // are expressed in degrees - double rollTarget; - double rollValue; - double pitchTarget; - double pitchValue; - double headingTarget; - double headingValue; - double groundspeedTarget; - double groundspeedValue; - double airspeedTarget; - double airspeedValue; - double altitudeTarget; - double altitudeValue; - - qreal compassBandWidth; - qreal speedScaleHeight; - qreal altitudeScaleHeight; - - // Name of the fields to read when an update is received: - UAVDataObject *airspeedObj; - UAVDataObject *altitudeObj; - UAVDataObject *attitudeObj; - UAVDataObject *groundspeedObj; - UAVDataObject *headingObj; - UAVDataObject *gpsObj; - UAVDataObject *gcsTelemetryObj; - UAVDataObject *gcsBatteryObj; - - // Rotation timer - QTimer dialTimer; - QTimer skyDialTimer; - - QString satString; - QString batString; - - // Flag to check for pfd Error - bool pfdError; - // Flag to enable better rendering of fonts in OpenGL - bool hqFonts; - bool beSmooth; -}; -#endif /* PFDGADGETWIDGET_H_ */ diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdplugin.cpp b/ground/openpilotgcs/src/plugins/pfd/pfdplugin.cpp deleted file mode 100644 index fce87ea88..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdplugin.cpp +++ /dev/null @@ -1,65 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdplugin.h - * @author Edouard Lafargue Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 "pfdplugin.h" -#include "pfdgadgetfactory.h" -#include -#include -#include -#include - - -PFDPlugin::PFDPlugin() -{ - // Do nothing -} - -PFDPlugin::~PFDPlugin() -{ - // Do nothing -} - -bool PFDPlugin::initialize(const QStringList & args, QString *errMsg) -{ - Q_UNUSED(args); - Q_UNUSED(errMsg); - mf = new PFDGadgetFactory(this); - addAutoReleasedObject(mf); - - return true; -} - -void PFDPlugin::extensionsInitialized() -{ - // Do nothing -} - -void PFDPlugin::shutdown() -{ - // Do nothing -} -Q_EXPORT_PLUGIN(PFDPlugin) diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdplugin.h b/ground/openpilotgcs/src/plugins/pfd/pfdplugin.h deleted file mode 100644 index 067384793..000000000 --- a/ground/openpilotgcs/src/plugins/pfd/pfdplugin.h +++ /dev/null @@ -1,46 +0,0 @@ -/** - ****************************************************************************** - * - * @file pfdplugin.h - * @author Edouard Lafargue Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin Primary Flight Display Plugin - * @{ - * @brief The Primary Flight Display Gadget - *****************************************************************************/ -/* - * 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 - */ - -#ifndef PFDPLUGIN_H_ -#define PFDPLUGIN_H_ - -#include - -class PFDGadgetFactory; - -class PFDPlugin : public ExtensionSystem::IPlugin { -public: - PFDPlugin(); - ~PFDPlugin(); - - void extensionsInitialized(); - bool initialize(const QStringList & arguments, QString *errorString); - void shutdown(); -private: - PFDGadgetFactory *mf; -}; -#endif /* PFDPLUGIN_H_ */ diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp index 265a96497..365a323b7 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp @@ -46,6 +46,10 @@ void PfdQmlGadget::loadConfiguration(IUAVGadgetConfiguration *config) m_widget->setLatitude(m->latitude()); m_widget->setLongitude(m->longitude()); m_widget->setAltitude(m->altitude()); + m_widget->setSpeedFactor(m->speedFactor()); + m_widget->setSpeedUnit(m->speedUnit()); + m_widget->setAltitudeFactor(m->altitudeFactor()); + m_widget->setAltitudeUnit(m->altitudeUnit()); // setting OSGEARTH_CACHE_ONLY seems to work the most reliably // between osgEarth versions I tried diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp index e00e52a1d..614441daf 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp @@ -31,8 +31,18 @@ PfdQmlGadgetConfiguration::PfdQmlGadgetConfiguration(QString classId, QSettings m_latitude(0), m_longitude(0), m_altitude(0), - m_cacheOnly(false) + m_cacheOnly(false), + m_speedFactor(1.0), + m_altitudeFactor(1.0) { + m_speedMap[1.0] = "m/s"; + m_speedMap[3.6] = "km/h"; + m_speedMap[2.2369] = "mph"; + m_speedMap[1.9438] = "knots"; + + m_altitudeMap[1.0] = "m"; + m_altitudeMap[3.2808] = "ft"; + // if a saved configuration exists load it if (qSettings != 0) { m_qmlFile = qSettings->value("qmlFile").toString(); @@ -48,6 +58,8 @@ PfdQmlGadgetConfiguration::PfdQmlGadgetConfiguration(QString classId, QSettings m_longitude = qSettings->value("longitude").toDouble(); m_altitude = qSettings->value("altitude").toDouble(); m_cacheOnly = qSettings->value("cacheOnly").toBool(); + m_speedFactor = qSettings->value("speedFactor").toDouble(); + m_altitudeFactor = qSettings->value("altitudeFactor").toDouble(); } } @@ -68,6 +80,8 @@ IUAVGadgetConfiguration *PfdQmlGadgetConfiguration::clone() m->m_longitude = m_longitude; m->m_altitude = m_altitude; m->m_cacheOnly = m_cacheOnly; + m->m_speedFactor = m_speedFactor; + m->m_altitudeFactor = m_altitudeFactor; return m; } @@ -91,4 +105,6 @@ void PfdQmlGadgetConfiguration::saveConfig(QSettings *qSettings) const qSettings->setValue("longitude", m_longitude); qSettings->setValue("altitude", m_altitude); qSettings->setValue("cacheOnly", m_cacheOnly); + qSettings->setValue("speedFactor", m_speedFactor); + qSettings->setValue("altitudeFactor", m_altitudeFactor); } diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h index f09e4a0ad..b3f8e9b34 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h @@ -18,6 +18,7 @@ #define PFDQMLGADGETCONFIGURATION_H #include +#include using namespace Core; @@ -62,6 +63,14 @@ public: { m_cacheOnly = flag; } + void setSpeedFactor(double factor) + { + m_speedFactor = factor; + } + void setAltitudeFactor(double factor) + { + m_altitudeFactor = factor; + } QString qmlFile() const { @@ -99,6 +108,34 @@ public: { return m_cacheOnly; } + double speedFactor() const + { + return m_speedFactor; + } + double altitudeFactor() const + { + return m_altitudeFactor; + } + + QString speedUnit() const + { + return m_speedMap[m_speedFactor]; + } + + QString altitudeUnit() const + { + return m_altitudeMap[m_altitudeFactor]; + } + + QMapIterator speedMapIterator() + { + return QMapIterator(m_speedMap); + } + + QMapIterator altitudeMapIterator() + { + return QMapIterator(m_altitudeMap); + } void saveConfig(QSettings *settings) const; IUAVGadgetConfiguration *clone(); @@ -113,6 +150,10 @@ private: double m_longitude; double m_altitude; bool m_cacheOnly; + double m_speedFactor; + double m_altitudeFactor; + QMap m_speedMap; + QMap m_altitudeMap; }; #endif // PfdQmlGADGETCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.cpp index 0fa0503aa..f7d6b1f66 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.cpp @@ -22,7 +22,7 @@ PfdQmlGadgetFactory::PfdQmlGadgetFactory(QObject *parent) : IUAVGadgetFactory(QString("PfdQmlGadget"), - tr("PFD (qml)"), + tr("PFD"), parent) {} diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp index 0b20b8480..b7f2aab5e 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp @@ -62,6 +62,21 @@ QWidget *PfdQmlGadgetOptionsPage::createPage(QWidget *parent) options_page->altitude->setText(QString::number(m_config->altitude())); options_page->useOnlyCache->setChecked(m_config->cacheOnly()); + // Setup units combos + QMapIterator iter = m_config->speedMapIterator(); + while (iter.hasNext()) { + iter.next(); + options_page->speedUnitCombo->addItem(iter.value(), iter.key()); + } + options_page->speedUnitCombo->setCurrentIndex(options_page->speedUnitCombo->findData(m_config->speedFactor())); + + iter = m_config->altitudeMapIterator(); + while (iter.hasNext()) { + iter.next(); + options_page->altUnitCombo->addItem(iter.value(), iter.key()); + } + options_page->altUnitCombo->setCurrentIndex(options_page->altUnitCombo->findData(m_config->altitudeFactor())); + #ifndef USE_OSG options_page->showTerrain->setChecked(false); options_page->showTerrain->setVisible(false); @@ -93,6 +108,9 @@ void PfdQmlGadgetOptionsPage::apply() m_config->setLongitude(options_page->longitude->text().toDouble()); m_config->setAltitude(options_page->altitude->text().toDouble()); m_config->setCacheOnly(options_page->useOnlyCache->isChecked()); + + m_config->setSpeedFactor(options_page->speedUnitCombo->itemData(options_page->speedUnitCombo->currentIndex()).toDouble()); + m_config->setAltitudeFactor(options_page->altUnitCombo->itemData(options_page->altUnitCombo->currentIndex()).toDouble()); } void PfdQmlGadgetOptionsPage::finish() diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui index 20d617e9b..bb136c6e1 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui @@ -6,8 +6,8 @@ 0 0 - 457 - 436 + 636 + 558
@@ -19,11 +19,11 @@ Form - + 0 - + QFrame::NoFrame @@ -39,15 +39,15 @@ 0 0 - 457 - 436 + 636 + 558 - + 0 - + 10 @@ -77,7 +77,7 @@ - + Use OpenGL @@ -87,7 +87,45 @@ - + + + + + + Speed Unit: + + + + + + + Altitude Unit: + + + + + + + + 150 + 16777215 + + + + + + + + + 150 + 16777215 + + + + + + + Show Terrain: @@ -223,7 +261,7 @@
- + Qt::Vertical diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp index 307347067..5e7683c7f 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp @@ -39,7 +39,11 @@ PfdQmlGadgetWidget::PfdQmlGadgetWidget(QWidget *parent) : m_actualPositionUsed(false), m_latitude(46.671478), m_longitude(10.158932), - m_altitude(2000) + m_altitude(2000), + m_speedUnit("m/s"), + m_speedFactor(1.0), + m_altitudeUnit("m"), + m_altitudeFactor(1.0) { setMinimumSize(64, 64); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); @@ -121,6 +125,38 @@ void PfdQmlGadgetWidget::setTerrainEnabled(bool arg) } } +void PfdQmlGadgetWidget::setSpeedUnit(QString unit) +{ + if (m_speedUnit != unit) { + m_speedUnit = unit; + emit speedUnitChanged(unit); + } +} + +void PfdQmlGadgetWidget::setSpeedFactor(double factor) +{ + if (m_speedFactor != factor) { + m_speedFactor = factor; + emit speedFactorChanged(factor); + } +} + +void PfdQmlGadgetWidget::setAltitudeUnit(QString unit) +{ + if (m_altitudeUnit != unit) { + m_altitudeUnit = unit; + emit altitudeUnitChanged(unit); + } +} + +void PfdQmlGadgetWidget::setAltitudeFactor(double factor) +{ + if (m_altitudeFactor != factor) { + m_altitudeFactor = factor; + emit altitudeFactorChanged(factor); + } +} + void PfdQmlGadgetWidget::setOpenGLEnabled(bool arg) { if (m_openGLEnabled != arg) { diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h index 77ab49f9d..46d540345 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h @@ -26,6 +26,11 @@ class PfdQmlGadgetWidget : public QDeclarativeView { Q_PROPERTY(bool actualPositionUsed READ actualPositionUsed WRITE setActualPositionUsed NOTIFY actualPositionUsedChanged) + Q_PROPERTY(QString speedUnit READ speedUnit WRITE setSpeedUnit NOTIFY speedUnitChanged) + Q_PROPERTY(double speedFactor READ speedFactor WRITE setSpeedFactor NOTIFY speedFactorChanged) + Q_PROPERTY(QString altitudeUnit READ altitudeUnit WRITE setAltitudeUnit NOTIFY altitudeUnitChanged) + Q_PROPERTY(double altitudeFactor READ altitudeFactor WRITE setAltitudeFactor NOTIFY altitudeFactorChanged) + // pre-defined fallback position Q_PROPERTY(double latitude READ latitude WRITE setLatitude NOTIFY latitudeChanged) Q_PROPERTY(double longitude READ longitude WRITE setLongitude NOTIFY longitudeChanged) @@ -45,6 +50,23 @@ public: return m_terrainEnabled && m_openGLEnabled; } + QString speedUnit() const + { + return m_speedUnit; + } + double speedFactor() const + { + return m_speedFactor; + } + QString altitudeUnit() const + { + return m_altitudeUnit; + } + double altitudeFactor() const + { + return m_altitudeFactor; + } + bool actualPositionUsed() const { return m_actualPositionUsed; @@ -65,6 +87,12 @@ public: public slots: void setEarthFile(QString arg); void setTerrainEnabled(bool arg); + + void setSpeedUnit(QString unit); + void setSpeedFactor(double factor); + void setAltitudeUnit(QString unit); + void setAltitudeFactor(double factor); + void setOpenGLEnabled(bool arg); void setLatitude(double arg); @@ -82,6 +110,11 @@ signals: void longitudeChanged(double arg); void altitudeChanged(double arg); + void speedUnitChanged(QString arg); + void speedFactorChanged(double arg); + void altitudeUnitChanged(QString arg); + void altitudeFactorChanged(double arg); + private: QString m_qmlFileName; QString m_earthFile; @@ -92,6 +125,11 @@ private: double m_latitude; double m_longitude; double m_altitude; + + QString m_speedUnit; + double m_speedFactor; + QString m_altitudeUnit; + double m_altitudeFactor; }; #endif /* PFDQMLGADGETWIDGET_H_ */ diff --git a/ground/openpilotgcs/src/plugins/plugins.pro b/ground/openpilotgcs/src/plugins/plugins.pro index 20b402704..73bea8c59 100644 --- a/ground/openpilotgcs/src/plugins/plugins.pro +++ b/ground/openpilotgcs/src/plugins/plugins.pro @@ -132,12 +132,6 @@ plugin_gpsdisplay.depends = plugin_coreplugin plugin_gpsdisplay.depends += plugin_uavobjects SUBDIRS += plugin_gpsdisplay -# Primary Flight Display (PFD) gadget -plugin_pfd.subdir = pfd -plugin_pfd.depends = plugin_coreplugin -plugin_pfd.depends += plugin_uavobjects -SUBDIRS += plugin_pfd - # QML viewer gadget plugin_qmlview.subdir = qmlview plugin_qmlview.depends = plugin_coreplugin @@ -150,7 +144,7 @@ plugin_pathactioneditor.depends = plugin_coreplugin plugin_pathactioneditor.depends += plugin_uavobjects SUBDIRS += plugin_pathactioneditor -# Primary Flight Display (PFD) gadget, QML version +# Primary Flight Display (PFD) gadget plugin_pfdqml.subdir = pfdqml plugin_pfdqml.depends = plugin_coreplugin plugin_pfdqml.depends += plugin_uavobjects @@ -244,8 +238,3 @@ plugin_setupwizard.depends += plugin_config plugin_setupwizard.depends += plugin_uploader SUBDIRS += plugin_setupwizard -# Junsi Powerlog plugin -#plugin_powerlog.subdir = powerlog -#plugin_powerlog.depends = plugin_coreplugin -#plugin_powerlog.depends += plugin_rawhid -#SUBDIRS += plugin_powerlog diff --git a/ground/openpilotgcs/src/plugins/powerlog/PowerLog.pluginspec b/ground/openpilotgcs/src/plugins/powerlog/PowerLog.pluginspec deleted file mode 100644 index 24ac39811..000000000 --- a/ground/openpilotgcs/src/plugins/powerlog/PowerLog.pluginspec +++ /dev/null @@ -1,11 +0,0 @@ - - The OpenPilot Project - (C) 2010 OpenPilot - The GNU Public License (GPL) Version 3 - A plugin that downloads the log from a Junsi PowerLog6S to a file - http://www.openpilot.org - - - - - diff --git a/ground/openpilotgcs/src/plugins/powerlog/powerlog.pro b/ground/openpilotgcs/src/plugins/powerlog/powerlog.pro deleted file mode 100644 index e521ad17c..000000000 --- a/ground/openpilotgcs/src/plugins/powerlog/powerlog.pro +++ /dev/null @@ -1,11 +0,0 @@ -TEMPLATE = lib -TARGET = PowerLog -DEFINES += POWERLOG_LIBRARY -include(../../openpilotgcsplugin.pri) -include(powerlog_dependencies.pri) -HEADERS += powerlogplugin.h - -SOURCES += powerlogplugin.cpp - -OTHER_FILES += PowerLog.pluginspec - diff --git a/ground/openpilotgcs/src/plugins/powerlog/powerlog_dependencies.pri b/ground/openpilotgcs/src/plugins/powerlog/powerlog_dependencies.pri deleted file mode 100644 index f77ee6b96..000000000 --- a/ground/openpilotgcs/src/plugins/powerlog/powerlog_dependencies.pri +++ /dev/null @@ -1,2 +0,0 @@ -include(../../plugins/coreplugin/coreplugin.pri) -include(../../plugins/rawhid/opHID.pri) diff --git a/ground/openpilotgcs/src/plugins/powerlog/powerlogplugin.cpp b/ground/openpilotgcs/src/plugins/powerlog/powerlogplugin.cpp deleted file mode 100644 index 5f0b9c820..000000000 --- a/ground/openpilotgcs/src/plugins/powerlog/powerlogplugin.cpp +++ /dev/null @@ -1,369 +0,0 @@ -/** - ****************************************************************************** - * - * @file powerlogplugin.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @see The GNU Public License (GPL) Version 3 - * @brief Junsi Powerlog utility Plugin - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup PowerLog - * @{ - * - *****************************************************************************/ -/* - * 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 "powerlogplugin.h" -#include "rawhid/usbmonitor.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - - -/** - * Sets the file to use for logging and takes the parent plugin - * to connect to stop logging signal - * @param[in] file File name to write to - * @param[in] parent plugin - */ -bool PowerlogThread::openFile(QString file, PowerlogPlugin *parent) -{ - logFile.setFileName(file); - logFile.open(QIODevice::WriteOnly); - fileStream.setDevice(&logFile); - - connect(parent, SIGNAL(stopLoggingSignal()), this, SLOT(stopLogging())); - - return true; -}; - -/** - * Get all logs from Powerlog - */ -void PowerlogThread::run() -{ - // TODO: pop up a dialog here! - - qDebug() << "Connect a Junsi PowerLog 6S and watch the logging output"; - opHID_hidapi hidHandle; - int numDevices = hidHandle.open(1, 0x0483, 0x5750, 0, 0); // 0xff9c,0x0001); - if (numDevices == 0) { - numDevices = hidHandle.open(1, 0x0483, 0, 0, 0); - } - - qDebug() << numDevices << " device(s) opened"; - if (numDevices == 0) { - return; - } - - // hidHandle.mytest(0); - - char buf[BUF_LEN]; - buf[0] = 2; - buf[1] = 0; - - fileStream << "Interval,Current,Volt,Cap,Cell1,Cell2,Cell3,Cell4,Cell5,Cell6,RPM,Temp0,Temp1,Temp2,Temp3,Period,Pulse\n"; - - while (int received = hidHandle.receive(0, buf, BUF_LEN, 3500)) { - ShowInf(buf); - fileStream.flush(); // Just to be sure... - } - - stopLogging(); -} - -/** - * Pass this command to the correct thread then close the file - */ -void PowerlogThread::stopLogging() -{ - QWriteLocker locker(&lock); - - fileStream.flush(); - logFile.close(); - quit(); -} - -/** - * Formats the content of the buffer we just read and write - * to the logfile - */ -void PowerlogThread::ShowInf(char *pBuf) -{ - POWERLOG_HID_PACK Inf; - int i; - int Count; - - Count = 0; - Inf.Len = pBuf[Count]; - Count += sizeof(Inf.Len); - - Inf.Type = pBuf[Count]; - Count += sizeof(Inf.Type); - - Inf.Interval = *((DWORD *)&pBuf[Count]); - fileStream << QString::number(Inf.Interval) << ","; - - Count += sizeof(Inf.Interval); - - Inf.LogState = pBuf[Count]; - Count += sizeof(Inf.LogState); - - if (((Inf.Type == TYPE_DATA_ONLINE) || (Inf.Type == TYPE_DATA_OFFLINE)) && (Inf.Len == 0x29)) { // 0x27 - Inf.Current = *((SHORT *)&pBuf[Count]); - Count += sizeof(Inf.Current); - GetShowValue(QString("Current"), Inf.Current, 5, 2); - - Inf.Volt = *((USHORT *)&pBuf[Count]); - Count += sizeof(Inf.Volt); - GetShowValue(QString("Voltage"), Inf.Volt, 5, 2); - - Inf.Cap = *((DWORD *)&pBuf[Count]); - Count += sizeof(Inf.Cap); - GetShowValue(QString("Cap"), Inf.Cap, 6, 0); - - for (i = 0; i < 6; i++) { - Inf.Cell[i] = *((SHORT *)&pBuf[Count]); - Count += sizeof(Inf.Cell[i]); - } - GetShowValue(QString("Cell 1"), Inf.Cell[0], 5, 3); - GetShowValue(QString("Cell 2"), Inf.Cell[1], 5, 3); - GetShowValue(QString("Cell 3"), Inf.Cell[2], 5, 3); - GetShowValue(QString("Cell 4"), Inf.Cell[3], 5, 3); - GetShowValue(QString("Cell 5"), Inf.Cell[4], 5, 3); - GetShowValue(QString("Cell 6"), Inf.Cell[5], 5, 3); - - Inf.RPM = *((USHORT *)&pBuf[Count]); - Count += sizeof(Inf.RPM); - GetShowValue(QString("RPM"), Inf.RPM, 6, 0); - - for (i = 0; i < 4; i++) { - Inf.Temp[i] = *((SHORT *)&pBuf[Count]); - Count += sizeof(Inf.Temp[i]); - } - GetShowValue(QString("Int Temp0"), Inf.Temp[0], 4, 1); - - if (Inf.Temp[1] == 0x7fff) { - fileStream << "0.0,"; - } else { - GetShowValue(QString("Ext temp1"), Inf.Temp[1], 4, 1); - } - - if (Inf.Temp[2] == 0x7fff) { - fileStream << "0.0,"; - } else { - GetShowValue(QString("Ext temp2"), Inf.Temp[2], 4, 1); - } - - if (Inf.Temp[3] == 0x7fff) { - fileStream << "0.0,"; - } else { - GetShowValue(QString("Ext temp3"), Inf.Temp[3], 4, 1); - } - - Inf.Period = *((USHORT *)&pBuf[Count]); - Count += sizeof(Inf.Period); - GetShowValue(QString("Period:"), Inf.Period, 6, 0); - - Inf.Pulse = *((USHORT *)&pBuf[Count]); - Count += sizeof(Inf.Pulse); - GetShowValue(QString("Pulse:"), Inf.Pulse, 6, 0); - - fileStream << "\n"; - } -} - -/** - * Formats a numeric value - */ -void PowerlogThread::GetShowValue(QString label, DWORD Value, WORD Len, WORD Dot) -{ - QString out; - - if (Value < 0) { - fileStream << "-"; - Value = -Value; - } - - if (Dot == 1) { - fileStream << Value / 10 << "." << Value % 10; // printf("%ld.%01lu",Value/10,Value%10); - } else if (Dot == 2) { - fileStream << Value / 100 << "." << Value % 100; // printf("%ld.%02lu",Value/100,Value%100); - } else if (Dot == 3) { - fileStream << Value / 1000 << "." << Value % 1000; // printf("%ld.%03lu",Value/1000,Value%1000); - } else if (Dot == 4) { - fileStream << Value / 10000 << "." << Value % 10000; // printf("%ld.%04lu",Value/10000,Value%10000); - } else { - fileStream << Value; // printf("%ld",Value); - } - fileStream << out << ","; -} - - -/**************************************************************** - Logging plugin - ********************************/ - - -PowerlogPlugin::PowerlogPlugin() : - devSerialNumber(""), - logging(false), - loggingThread(NULL) -{} - -PowerlogPlugin::~PowerlogPlugin() -{} - -/** - * Add Powerlog plugin entry to File menu - */ -bool PowerlogPlugin::initialize(const QStringList & args, QString *errMsg) -{ - Q_UNUSED(args); - Q_UNUSED(errMsg); - - - // Add Menu entry - Core::ActionManager *am = Core::ICore::instance()->actionManager(); - Core::ActionContainer *ac = am->actionContainer(Core::Constants::M_TOOLS); - - // Command to start logging - cmd = am->registerAction(new QAction(this), - "PowerlogPlugin.Transfer", - QList() << - Core::Constants::C_GLOBAL_ID); - cmd->action()->setText("Receive from PowerLog6S..."); - - ac->menu()->addSeparator(); - ac->appendGroup("Utilities"); - ac->addAction(cmd, "Utilities"); - - connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(receiveLog())); - - // At this stage we know that other plugins we depend upon are - // initialized, in prticular the USB Monitor is now running: - USBMonitor *mon = USBMonitor::instance(); - connect(mon, SIGNAL(deviceDiscovered(USBPortInfo)), this, SLOT(devConnected(USBPortInfo))); - connect(mon, SIGNAL(deviceRemoved(USBPortInfo)), this, SLOT(devRemoved(USBPortInfo))); - - return true; -} - -/** - * The action that is triggered by the menu item which opens the - * file and begins log reception if successful - */ -void PowerlogPlugin::receiveLog() -{ - if (logging) { - loggingThread->stopLogging(); - logging = false; - cmd->action()->setText("Receive from PowerLog6S..."); - } else { - QString fileName = QFileDialog::getSaveFileName(NULL, tr("Log filename"), - tr("PowerLog-%0.csv").arg(QDateTime::currentDateTime().toString("yyyy-MM-dd_hh-mm-ss")), - tr("Comma Separated Values (*.csv)")); - if (fileName.isEmpty()) { - return; - } - - loggingThread = new PowerlogThread(); - if (loggingThread->openFile(fileName, this)) { - loggingThread->start(); - cmd->action()->setText("Stop PowerLog6S reception"); - logging = true; - } - } -} - -/** - Device connected, check whether it is a powerlog & act accordingly - */ -void PowerlogPlugin::devConnected(USBPortInfo port) -{ - if (devSerialNumber.length() > 0) { - return; - } - if ((port.vendorID == 0x0483) && (port.productID == 0x5750)) { - devSerialNumber = port.serialNumber; - cmd->action()->setEnabled(true); - } -} - - -/** - Device Removed, check whether it is a powerlog & act accordingly. - As when the device is removed, we don't get the info on the device, - we have to list all available remaining devices and check if the serial - number of our device is missing... - */ -void PowerlogPlugin::devRemoved(USBPortInfo port) -{ - bool foundDevice; - - QList ports = USBMonitor::instance()->availableDevices(); - foreach(USBPortInfo port, ports) { - if ((port.vendorID == 0x0483) && (port.productID == 0x5750) && - (devSerialNumber == port.serialNumber)) { - foundDevice = true; - break; - } - } - if (!foundDevice) { - devSerialNumber = QString(""); - cmd->action()->setEnabled(false); - // Also stop logging in case we were logging: - if (loggingThread) { - loggingThread->stopLogging(); - } - } -} - - -void PowerlogPlugin::extensionsInitialized() -{ - cmd->action()->setEnabled(false); - QList ports = USBMonitor::instance()->availableDevices(); - foreach(USBPortInfo port, ports) { - if ((port.vendorID == 0x0483) && (port.productID == 0x5750)) { - devSerialNumber = port.serialNumber; - cmd->action()->setEnabled(true); - break; - } - } -} - -void PowerlogPlugin::shutdown() -{ - // Do nothing -} -Q_EXPORT_PLUGIN(PowerlogPlugin) - -/** - * @} - * @} - */ diff --git a/ground/openpilotgcs/src/plugins/powerlog/powerlogplugin.h b/ground/openpilotgcs/src/plugins/powerlog/powerlogplugin.h deleted file mode 100644 index 70054cfab..000000000 --- a/ground/openpilotgcs/src/plugins/powerlog/powerlogplugin.h +++ /dev/null @@ -1,135 +0,0 @@ -/** - ****************************************************************************** - * @file powerlogplugin.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @see The GNU Public License (GPL) Version 3 - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup powerlogplugin - * @{ - *****************************************************************************/ -/* - * 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 - */ - -#ifndef POWERLOGPLUGIN_H_ -#define POWERLOGPLUGIN_H_ - -#include -#include -#include -#include -#include -#include "opHID/inc/opHID_usbmon.h" -#include "opHID/inc/opHID_hidapi.h" - -#include -#include -#include - -using namespace std; - -typedef unsigned long ULONG; // 4 Bytes -typedef short SHORT; -typedef unsigned short USHORT; // 2 Bytes -typedef unsigned char BYTE; // 1 Byte -typedef unsigned short WORD; // 2 Bytes -typedef unsigned long DWORD; // 4 Bytes - - -#define BUF_LEN 64 -struct POWERLOG_HID_PACK { - BYTE Len; - BYTE Type; - DWORD Interval; - BYTE LogState; - SHORT Current; - USHORT Volt; - DWORD Cap; - SHORT Cell[6]; - USHORT RPM; - SHORT Temp[4]; - USHORT Period; - USHORT Pulse; -}; - -enum { - TYPE_DATA_ONLINE = 0x10, - TYPE_DATA_OFFLINE = 0x11, - TYPE_ORDER = 0x20, -}; - - -class PowerlogPlugin; - -class PowerlogThread : public QThread { - Q_OBJECT - -public: - bool openFile(QString file, PowerlogPlugin *parent); - -private slots: - -public slots: - void stopLogging(); - -protected: - void run(); - QReadWriteLock lock; - QFile logFile; - QTextStream fileStream; - -private: - void ShowInf(char *pBuf); - void GetShowValue(QString label, DWORD Value, WORD Len, WORD Dot); -}; - - -class PowerlogPlugin : public ExtensionSystem::IPlugin { - Q_OBJECT - - -public: - PowerlogPlugin(); - ~PowerlogPlugin(); - - void extensionsInitialized(); - bool initialize(const QStringList & arguments, QString *errorString); - void shutdown(); - - void setPowerlogMenuTitle(QString str); - - -signals: - void stopLoggingSignal(void); - -protected: - -private slots: - void receiveLog(); - void devConnected(USBPortInfo); - void devRemoved(USBPortInfo); - -private: - Core::Command *cmd; - QString devSerialNumber; - PowerlogThread *loggingThread; - bool logging; -}; -#endif /* POWERLOGPLUGIN_H_ */ -/** - * @} - * @} - */ diff --git a/package/osx/OpenPilot.dmg b/package/osx/OpenPilot.dmg index 66a3b882f..d53bf09b5 100644 Binary files a/package/osx/OpenPilot.dmg and b/package/osx/OpenPilot.dmg differ diff --git a/package/osx/package b/package/osx/package index 758038386..276e74f84 100755 --- a/package/osx/package +++ b/package/osx/package @@ -13,7 +13,7 @@ VOL_NAME="OpenPilot" rm -f "${TEMP_FILE}" rm -f "${OUT_FILE}" -# if the file doesn't exist, try to create folder +# if an OpenPilot volume is already mounted, unmount it if [ ! -f "/Volumes/${VOL_NAME}" ] then hdiutil unmount "/Volumes/${VOL_NAME}" diff --git a/package/winx86/openpilotgcs.nsi b/package/winx86/openpilotgcs.nsi index 0dc1f21b6..df5d34152 100644 --- a/package/winx86/openpilotgcs.nsi +++ b/package/winx86/openpilotgcs.nsi @@ -98,11 +98,25 @@ !define MUI_ICON "${NSIS_DATA_TREE}\resources\openpilot.ico" !define MUI_HEADERIMAGE !define MUI_HEADERIMAGE_BITMAP "${NSIS_DATA_TREE}\resources\header.bmp" - !define MUI_HEADERIMAGE_BITMAP_NOSTRETCH !define MUI_WELCOMEFINISHPAGE_BITMAP "${NSIS_DATA_TREE}\resources\welcome.bmp" - !define MUI_WELCOMEFINISHPAGE_BITMAP_NOSTRETCH !define MUI_UNWELCOMEFINISHPAGE_BITMAP "${NSIS_DATA_TREE}\resources\welcome.bmp" - !define MUI_UNWELCOMEFINISHPAGE_BITMAP_NOSTRETCH + + !define HEADER_BGCOLOR "0x8C8C8C" + !define HEADER_FGCOLOR "0x343434" + + !macro SetHeaderColors un + Function ${un}SetHeaderColors + GetDlgItem $r3 $HWNDPARENT 1034 + SetCtlColors $r3 ${HEADER_BGCOLOR} ${HEADER_FGCOLOR} + GetDlgItem $r3 $HWNDPARENT 1037 + SetCtlColors $r3 ${HEADER_BGCOLOR} ${HEADER_FGCOLOR} + GetDlgItem $r3 $HWNDPARENT 1038 + SetCtlColors $r3 ${HEADER_BGCOLOR} ${HEADER_FGCOLOR} + FunctionEnd + !macroend + + !insertmacro SetHeaderColors "" + !insertmacro SetHeaderColors "un." ;-------------------------------- ; Language selection dialog settings @@ -122,6 +136,8 @@ ;-------------------------------- ; Pages + !define MUI_PAGE_CUSTOMFUNCTION_PRE "SetHeaderColors" + !insertmacro MUI_PAGE_WELCOME !insertmacro MUI_PAGE_LICENSE "$(LicenseFile)" !insertmacro MUI_PAGE_COMPONENTS @@ -129,6 +145,8 @@ !insertmacro MUI_PAGE_INSTFILES !insertmacro MUI_PAGE_FINISH + !define MUI_PAGE_CUSTOMFUNCTION_PRE "un.SetHeaderColors" + !insertmacro MUI_UNPAGE_WELCOME !insertmacro MUI_UNPAGE_CONFIRM !insertmacro MUI_UNPAGE_COMPONENTS diff --git a/package/winx86/resources/header.bmp b/package/winx86/resources/header.bmp index 1c0f7dd1d..8f09ec6f3 100644 Binary files a/package/winx86/resources/header.bmp and b/package/winx86/resources/header.bmp differ diff --git a/package/winx86/resources/welcome.bmp b/package/winx86/resources/welcome.bmp index 712471060..b6384c6fd 100644 Binary files a/package/winx86/resources/welcome.bmp and b/package/winx86/resources/welcome.bmp differ diff --git a/shared/uavobjectdefinition/altitudeholdsettings.xml b/shared/uavobjectdefinition/altitudeholdsettings.xml index 25c75aca3..61f36d37f 100644 --- a/shared/uavobjectdefinition/altitudeholdsettings.xml +++ b/shared/uavobjectdefinition/altitudeholdsettings.xml @@ -1,9 +1,9 @@ Settings for the @ref AltitudeHold module - - - + + + diff --git a/shared/uavobjectdefinition/flightstatus.xml b/shared/uavobjectdefinition/flightstatus.xml index 765e15d66..24befac63 100644 --- a/shared/uavobjectdefinition/flightstatus.xml +++ b/shared/uavobjectdefinition/flightstatus.xml @@ -4,7 +4,7 @@ - + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index 0c627d92e..99c89e5bb 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -43,31 +43,31 @@ units="" type="enum" elements="6" - options="Manual,Stabilized1,Stabilized2,Stabilized3,Autotune,AltitudeHold,VelocityControl,PositionHold,ReturnToBase,Land,PathPlanner,POI" + options="Manual,Stabilized1,Stabilized2,Stabilized3,Autotune,AltitudeHold,AltitudeVario,VelocityControl,PositionHold,ReturnToBase,Land,PathPlanner,POI" defaultvalue="Stabilized1,Stabilized2,Stabilized3,AltitudeHold,PositionHold,Manual" limits="\ - %0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ \ - %0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ \ - %0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ \ - %0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ \ - %0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ \ - %0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ + %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI"/>