diff --git a/Makefile b/Makefile index 25142441b..58f849bf7 100644 --- a/Makefile +++ b/Makefile @@ -654,6 +654,7 @@ ut_$(1)_%: $$(UT_OUT_DIR) $(V1) cd $(ROOT_DIR)/flight/tests/$(1) && \ $$(MAKE) -r --no-print-directory \ BUILD_TYPE=ut \ + BOARD_SHORT_NAME=$(1) \ TOPDIR=$(ROOT_DIR)/flight/tests/$(1) \ OUTDIR="$(UT_OUT_DIR)/$(1)" \ TARGET=$(1) \ diff --git a/flight/libraries/insgps13state.c b/flight/libraries/insgps13state.c index 7eca68a51..b206f1772 100644 --- a/flight/libraries/insgps13state.c +++ b/flight/libraries/insgps13state.c @@ -32,6 +32,7 @@ #include "insgps.h" #include #include +#include // constants/macros/typdefs #define NUMX 13 // number of states, X is the state vector @@ -39,17 +40,11 @@ #define NUMV 10 // number of measurements, v is the measurement noise vector #define NUMU 6 // number of deterministic inputs, U is the input vector -#if defined(GENERAL_COV) -// This might trick people so I have a note here. There is a slower but bigger version of the -// code here but won't fit when debugging disabled (requires -Os) -#define COVARIANCE_PREDICTION_GENERAL -#endif - // Private functions void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], float Q[NUMW], float dT, float P[NUMX][NUMX]); void SerialUpdate(float H[NUMV][NUMX], float R[NUMV], float Z[NUMV], - float Y[NUMV], float P[NUMX][NUMX], float X[NUMX], + float Y[NUMV], float P[NUMX][NUMX], float X[NUMX], float K[NUMX][NUMV], uint16_t SensorsUsed); void RungeKutta(float X[NUMX], float U[NUMU], float dT); void StateEq(float X[NUMX], float U[NUMU], float Xdot[NUMX]); @@ -59,12 +54,51 @@ void MeasurementEq(float X[NUMX], float Be[3], float Y[NUMV]); void LinearizeH(float X[NUMX], float Be[3], float H[NUMV][NUMX]); // Private variables -float F[NUMX][NUMX], G[NUMX][NUMW], H[NUMV][NUMX]; // linearized system matrices - // global to init to zero and maintain zero elements -float Be[3]; // local magnetic unit vector in NED frame -float P[NUMX][NUMX], X[NUMX]; // covariance matrix and state vector -float Q[NUMW], R[NUMV]; // input noise and measurement noise variances -float K[NUMX][NUMV]; // feedback gain matrix + +// speed optimizations, describe matrix sparsity +// derived from state equations in +// LinearizeFG() and LinearizeH(): +// +// usage F: usage G: usage H: +// 0123456789abc 012345678 0123456789abc +// 0...X......... ......... X............ +// 1....X........ ......... .X........... +// 2.....X....... ......... ..X.......... +// 3......XXXX... ...XXX... ...X......... +// 4......XXXX... ...XXX... ....X........ +// 5......XXXX... ...XXX... .....X....... +// 6.......XXXXXX XXX...... ......XXXX... +// 7......X.XXXXX XXX...... ......XXXX... +// 8......XX.XXXX XXX...... ......XXXX... +// 9......XXX.XXX XXX...... ..X.......... +// a............. ......X.. +// b............. .......X. +// c............. ........X + +static const int8_t FrowMin[NUMX] = { 3, 4, 5, 6, 6, 6, 7, 6, 6, 6,13,13,13 }; +static const int8_t FrowMax[NUMX] = { 3, 4, 5, 9, 9, 9,12,12,12,12,-1,-1,-1 }; + +static const int8_t GrowMin[NUMX] = { 9, 9, 9, 3, 3, 3, 0, 0, 0, 0, 6, 7, 8 }; +static const int8_t GrowMax[NUMX] = { -1,-1,-1, 5, 5, 5, 2, 2, 2, 2, 6, 7, 8 }; + +static const int8_t HrowMin[NUMV] = { 0, 1, 2, 3, 4, 5, 6, 6, 6, 2 }; +static const int8_t HrowMax[NUMV] = { 0, 1, 2, 3, 4, 5, 9, 9, 9, 2 }; + +static struct EKFData { + // linearized system matrices + float F[NUMX][NUMX]; + float G[NUMX][NUMW]; + float H[NUMV][NUMX]; + // local magnetic unit vector in NED frame + float Be[3]; + // covariance matrix and state vector + float P[NUMX][NUMX]; + float X[NUMX]; + // input noise and measurement noise variances + float Q[NUMW]; + float R[NUMV]; + float K[NUMX][NUMV]; // feedback gain matrix +} ekf; // Global variables struct NavStruct Nav; @@ -79,52 +113,52 @@ uint16_t ins_get_num_states() void INSGPSInit() //pretty much just a place holder for now { - Be[0] = 1.0f; - Be[1] = 0.0f; - Be[2] = 0.0f; // local magnetic unit vector + ekf.Be[0] = 1.0f; + ekf.Be[1] = 0.0f; + ekf.Be[2] = 0.0f; // local magnetic unit vector for (int i = 0; i < NUMX; i++) { for (int j = 0; j < NUMX; j++) { - P[i][j] = 0.0f; // zero all terms - F[i][j] = 0.0f; + ekf.P[i][j] = 0.0f; // zero all terms + ekf.F[i][j] = 0.0f; } for (int j = 0; j < NUMW; j++) - G[i][j] = 0.0f; + ekf.G[i][j] = 0.0f; for (int j = 0; j < NUMV; j++) { - H[j][i] = 0.0f; - K[i][j] = 0.0f; + ekf.H[j][i] = 0.0f; + ekf.K[i][j] = 0.0f; } - X[i] = 0.0f; + ekf.X[i] = 0.0f; } for (int i = 0; i < NUMW; i++) - Q[i] = 0.0f; + ekf.Q[i] = 0.0f; for (int i = 0; i < NUMV; i++) - R[i] = 0.0f; + ekf.R[i] = 0.0f; - P[0][0] = P[1][1] = P[2][2] = 25.0f; // initial position variance (m^2) - P[3][3] = P[4][4] = P[5][5] = 5.0f; // initial velocity variance (m/s)^2 - P[6][6] = P[7][7] = P[8][8] = P[9][9] = 1e-5f; // initial quaternion variance - P[10][10] = P[11][11] = P[12][12] = 1e-9f; // initial gyro bias variance (rad/s)^2 + ekf.P[0][0] = ekf.P[1][1] = ekf.P[2][2] = 25.0f; // initial position variance (m^2) + ekf.P[3][3] = ekf.P[4][4] = ekf.P[5][5] = 5.0f; // initial velocity variance (m/s)^2 + ekf.P[6][6] = ekf.P[7][7] = ekf.P[8][8] = ekf.P[9][9] = 1e-5f; // initial quaternion variance + ekf.P[10][10] = ekf.P[11][11] = ekf.P[12][12] = 1e-9f; // initial gyro bias variance (rad/s)^2 - X[0] = X[1] = X[2] = X[3] = X[4] = X[5] = 0.0f; // initial pos and vel (m) - X[6] = 1.0f; - X[7] = X[8] = X[9] = 0.0f; // initial quaternion (level and North) (m/s) - X[10] = X[11] = X[12] = 0.0f; // initial gyro bias (rad/s) + ekf.X[0] = ekf.X[1] = ekf.X[2] = ekf.X[3] = ekf.X[4] = ekf.X[5] = 0.0f; // initial pos and vel (m) + ekf.X[6] = 1.0f; + ekf.X[7] = ekf.X[8] = ekf.X[9] = 0.0f; // initial quaternion (level and North) (m/s) + ekf.X[10] = ekf.X[11] = ekf.X[12] = 0.0f; // initial gyro bias (rad/s) - Q[0] = Q[1] = Q[2] = 50e-4f; // gyro noise variance (rad/s)^2 - Q[3] = Q[4] = Q[5] = 0.00001f; // accelerometer noise variance (m/s^2)^2 - Q[6] = Q[7] = Q[8] = 2e-8f; // gyro bias random walk variance (rad/s^2)^2 + ekf.Q[0] = ekf.Q[1] = ekf.Q[2] = 50e-4f; // gyro noise variance (rad/s)^2 + ekf.Q[3] = ekf.Q[4] = ekf.Q[5] = 0.00001f; // accelerometer noise variance (m/s^2)^2 + ekf.Q[6] = ekf.Q[7] = ekf.Q[8] = 2e-8f; // gyro bias random walk variance (rad/s^2)^2 - R[0] = R[1] = 0.004f; // High freq GPS horizontal position noise variance (m^2) - R[2] = 0.036f; // High freq GPS vertical position noise variance (m^2) - R[3] = R[4] = 0.004f; // High freq GPS horizontal velocity noise variance (m/s)^2 - R[5] = 100.0f; // High freq GPS vertical velocity noise variance (m/s)^2 - R[6] = R[7] = R[8] = 0.005f; // magnetometer unit vector noise variance - R[9] = .25f; // High freq altimeter noise variance (m^2) + ekf.R[0] = ekf.R[1] = 0.004f; // High freq GPS horizontal position noise variance (m^2) + ekf.R[2] = 0.036f; // High freq GPS vertical position noise variance (m^2) + ekf.R[3] = ekf.R[4] = 0.004f; // High freq GPS horizontal velocity noise variance (m/s)^2 + ekf.R[5] = 100.0f; // High freq GPS vertical velocity noise variance (m/s)^2 + ekf.R[6] = ekf.R[7] = ekf.R[8] = 0.005f; // magnetometer unit vector noise variance + ekf.R[9] = .25f; // High freq altimeter noise variance (m^2) } void INSResetP(float PDiag[NUMX]) @@ -135,8 +169,8 @@ void INSResetP(float PDiag[NUMX]) for (i=0;i -#include "CoordinateConversions.h" -#include "altholdsmoothed.h" -#include "attitudeactual.h" -#include "altitudeholdsettings.h" -#include "altitudeholddesired.h" // object that will be updated by the module -#include "baroaltitude.h" -#include "positionactual.h" -#include "flightstatus.h" -#include "stabilizationdesired.h" -#include "accels.h" -#include "taskinfo.h" - +#include +#include +#include +#include +#include +#include // object that will be updated by the module +#include +#include +#include +#include +#include +#include +#include // Private constants #define MAX_QUEUE_SIZE 2 #define STACK_SIZE_BYTES 1024 @@ -340,7 +341,8 @@ static void altitudeHoldTask(__attribute__((unused)) void *parameters) // Verify that we are in altitude hold mode FlightStatusData flightStatus; FlightStatusGet(&flightStatus); - if(flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) { + if(flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD || + flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED) { running = false; } diff --git a/flight/modules/Fault/Fault.c b/flight/modules/Fault/Fault.c index b707ed5a5..33b15f7cb 100644 --- a/flight/modules/Fault/Fault.c +++ b/flight/modules/Fault/Fault.c @@ -112,7 +112,7 @@ static int32_t fault_start(void) } MODULE_INITCALL(fault_initialize, fault_start) -static void fault_task(void *parameters) +static void fault_task(__attribute__((unused))void *parameters) { switch (active_fault) { case FAULTSETTINGS_ACTIVATEFAULT_RUNAWAYTASK: diff --git a/flight/modules/FirmwareIAP/firmwareiap.c b/flight/modules/FirmwareIAP/firmwareiap.c index 46fdd4861..992971b3c 100644 --- a/flight/modules/FirmwareIAP/firmwareiap.c +++ b/flight/modules/FirmwareIAP/firmwareiap.c @@ -191,9 +191,9 @@ static void FirmwareIAPCallback(UAVObjEvent* ev) /* Note: Cant just wait timeout value, because first time is randomized */ reset_count = 0; lastResetSysTime = xTaskGetTickCount(); - UAVObjEvent * ev = pvPortMalloc(sizeof(UAVObjEvent)); - memset(ev,0,sizeof(UAVObjEvent)); - EventPeriodicCallbackCreate(ev, resetTask, 100); + UAVObjEvent *event = pvPortMalloc(sizeof(UAVObjEvent)); + memset(event, 0, sizeof(UAVObjEvent)); + EventPeriodicCallbackCreate(event, resetTask, 100); iap_state = IAP_STATE_RESETTING; } else { iap_state = IAP_STATE_READY; diff --git a/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c b/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c index 68d6a71bb..66e69f4c5 100644 --- a/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c +++ b/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c @@ -377,7 +377,6 @@ static uint8_t updateFixedDesiredAttitude() StabilizationDesiredData stabDesired; AttitudeActualData attitudeActual; AccelsData accels; - FixedWingPathFollowerSettingsData fixedwingpathfollowerSettings; StabilizationSettingsData stabSettings; FixedWingPathFollowerStatusData fixedwingpathfollowerStatus; AirspeedActualData airspeedActual; @@ -397,8 +396,6 @@ static uint8_t updateFixedDesiredAttitude() float bearingError; float bearingCommand; - FixedWingPathFollowerSettingsGet(&fixedwingpathfollowerSettings); - FixedWingPathFollowerStatusGet(&fixedwingpathfollowerStatus); VelocityActualGet(&velocityActual); diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index eff39dcae..91bac9c0e 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -51,7 +51,8 @@ #include "stabilizationdesired.h" #include "receiveractivity.h" #include "systemsettings.h" -#include "taskinfo.h" +#include +#include #if defined(PIOS_INCLUDE_USB_RCTX) #include "pios_usb_rctx.h" @@ -137,7 +138,9 @@ int32_t ManualControlStart() // Start main task xTaskCreate(manualControlTask, (signed char *) "ManualControl", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle); PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_MANUALCONTROL, taskHandle); +#ifdef PIOS_INCLUDE_WDG PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL); +#endif return 0; } @@ -202,12 +205,16 @@ static void manualControlTask(__attribute__((unused)) void *parameters) // Main task loop lastSysTime = xTaskGetTickCount(); + + float scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM] = {0}; + while (1) { - float scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM]; // Wait until next update vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD_MS / portTICK_RATE_MS); +#ifdef PIOS_INCLUDE_WDG PIOS_WDG_UpdateFlag(PIOS_WDG_MANUAL); +#endif // Read settings ManualControlSettingsGet(&settings); @@ -764,9 +771,9 @@ static void updateLandDesired(__attribute__((unused)) ManualControlCommandData * portTickType thisSysTime; float dT; - thisSysTime = xTaskGetTickCount(); + thisSysTime = xTaskGetTickCount(); dT = ((thisSysTime == lastSysTime)? 0.001f : (thisSysTime - lastSysTime) * portTICK_RATE_MS * 0.001f); - lastSysTime = thisSysTime; + lastSysTime = thisSysTime; */ PositionActualData positionActual; @@ -797,48 +804,59 @@ static void updateLandDesired(__attribute__((unused)) ManualControlCommandData * */ static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed) { - const float DEADBAND_HIGH = 0.55f; - const float DEADBAND_LOW = 0.45f; + const float DEADBAND = 0.10f; + const float DEADBAND_HIGH = 1.0f / 2 + DEADBAND / 2; + const float DEADBAND_LOW = 1.0f / 2 - DEADBAND / 2; - static portTickType lastSysTime; + // this is the max speed in m/s at the extents of throttle + uint8_t throttleRate; + uint8_t throttleExp; + + static portTickType lastSysTimeAH; static bool zeroed = false; portTickType thisSysTime; float dT; - AltitudeHoldDesiredData altitudeHoldDesired; - AltitudeHoldDesiredGet(&altitudeHoldDesired); + + AltitudeHoldDesiredData altitudeHoldDesiredData; + AltitudeHoldDesiredGet(&altitudeHoldDesiredData); + + AltitudeHoldSettingsThrottleExpGet(&throttleExp); + AltitudeHoldSettingsThrottleRateGet(&throttleRate); StabilizationSettingsData stabSettings; StabilizationSettingsGet(&stabSettings); - thisSysTime = xTaskGetTickCount(); - dT = ((thisSysTime == lastSysTime)? 0.001f : (thisSysTime - lastSysTime) * portTICK_RATE_MS * 0.001f); - lastSysTime = thisSysTime; + thisSysTime = xTaskGetTickCount(); + dT = ((thisSysTime == lastSysTimeAH)? 0.001f : (thisSysTime - lastSysTimeAH) * portTICK_RATE_MS * 0.001f); + lastSysTimeAH = thisSysTime; - altitudeHoldDesired.Roll = cmd->Roll * stabSettings.RollMax; - altitudeHoldDesired.Pitch = cmd->Pitch * stabSettings.PitchMax; - altitudeHoldDesired.Yaw = cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW]; + altitudeHoldDesiredData.Roll = cmd->Roll * stabSettings.RollMax; + altitudeHoldDesiredData.Pitch = cmd->Pitch * stabSettings.PitchMax; + altitudeHoldDesiredData.Yaw = cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW]; float currentDown; PositionActualDownGet(¤tDown); if(changed) { // After not being in this mode for a while init at current height - altitudeHoldDesired.Altitude = 0; + altitudeHoldDesiredData.Altitude = 0; zeroed = false; } else if (cmd->Throttle > DEADBAND_HIGH && zeroed) { - altitudeHoldDesired.Altitude += (cmd->Throttle - DEADBAND_HIGH) * dT; + // 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 + altitudeHoldDesiredData.Altitude += (throttleExp * powf((cmd->Throttle - DEADBAND_HIGH) / (DEADBAND_LOW), 3) + (256 - throttleExp)) / 256 * throttleRate * dT; } else if (cmd->Throttle < DEADBAND_LOW && zeroed) { - altitudeHoldDesired.Altitude += (cmd->Throttle - DEADBAND_LOW) * dT; + 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) { // Require the stick to enter the dead band before they can move height zeroed = true; } - AltitudeHoldDesiredSet(&altitudeHoldDesired); + AltitudeHoldDesiredSet(&altitudeHoldDesiredData); } #else // TODO: These functions should never be accessible on CC. Any configuration that -// could allow them to be called sholud already throw an error to prevent this happening +// could allow them to be called should already throw an error to prevent this happening // in flight static void updatePathDesired(__attribute__((unused)) ManualControlCommandData * cmd, __attribute__((unused)) bool changed, @@ -892,7 +910,7 @@ static float scaleChannel(int16_t value, int16_t max, int16_t min, int16_t neutr } static uint32_t timeDifferenceMs(portTickType start_time, portTickType end_time) { - return (end_time - start_time) * portTICK_RATE_MS; + return (end_time - start_time) * portTICK_RATE_MS; } /** @@ -903,6 +921,7 @@ static bool okToArm(void) { // read alarms SystemAlarmsData alarms; + SystemAlarmsGet(&alarms); // Check each alarm @@ -911,11 +930,23 @@ static bool okToArm(void) if (i == SYSTEMALARMS_ALARM_GPS || i == SYSTEMALARMS_ALARM_TELEMETRY) { continue; } + return false; } } + uint8_t flightMode; + FlightStatusFlightModeGet(&flightMode); + switch(flightMode) { + case FLIGHTSTATUS_FLIGHTMODE_MANUAL: + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1: + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2: + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3: return true; + default: + return false; + + } } /** * @brief Determine if the aircraft is forced to disarm by an explicit alarm diff --git a/flight/modules/Osd/osdgen/osdgen.c b/flight/modules/Osd/osdgen/osdgen.c index e67580bcd..9e9d94d8a 100644 --- a/flight/modules/Osd/osdgen/osdgen.c +++ b/flight/modules/Osd/osdgen/osdgen.c @@ -1063,7 +1063,7 @@ int fetch_font_info(uint8_t ch, int font, struct FontEntry *font_info, char *loo void write_char16(char ch, unsigned int x, unsigned int y, int font) { unsigned int yy, addr_temp, row, row_temp, xshift; - uint16_t and_mask, or_mask, level_bits; + uint16_t and_mask, or_mask, levels; struct FontEntry font_info; //char lookup = 0; fetch_font_info(0, font, &font_info, NULL); @@ -1103,17 +1103,17 @@ void write_char16(char ch, unsigned int x, unsigned int y, int font) addr = addr_temp; for (yy = y; yy < y + font_info.height; yy++) { if (font == 3) { - level_bits = font_frame12x18[row]; + levels = font_frame12x18[row]; //if(!(flags & FONT_INVERT)) // data is normally inverted - level_bits = ~level_bits; + levels = ~levels; or_mask = font_mask12x18[row] << xshift; - and_mask = (font_mask12x18[row] & level_bits) << xshift; + and_mask = (font_mask12x18[row] & levels) << xshift; } else { - level_bits = font_frame8x10[row]; + levels = font_frame8x10[row]; //if(!(flags & FONT_INVERT)) // data is normally inverted - level_bits = ~level_bits; + levels = ~levels; or_mask = font_mask8x10[row] << xshift; - and_mask = (font_mask8x10[row] & level_bits) << xshift; + and_mask = (font_mask8x10[row] & levels) << xshift; } write_word_misaligned_OR(draw_buffer_level, or_mask, addr, wbit); // If we're not bold write the AND mask. @@ -1139,7 +1139,7 @@ void write_char16(char ch, unsigned int x, unsigned int y, int font) void write_char(char ch, unsigned int x, unsigned int y, int flags, int font) { unsigned int yy, addr_temp, row, row_temp, xshift; - uint16_t and_mask, or_mask, level_bits; + uint16_t and_mask, or_mask, levels; struct FontEntry font_info; char lookup = 0; fetch_font_info(ch, font, &font_info, &lookup); @@ -1178,13 +1178,13 @@ void write_char(char ch, unsigned int x, unsigned int y, int flags, int font) row = row_temp; addr = addr_temp; for (yy = y; yy < y + font_info.height; yy++) { - level_bits = font_info.data[row + font_info.height]; + levels = font_info.data[row + font_info.height]; if (!(flags & FONT_INVERT)) { // data is normally inverted - level_bits = ~level_bits; + levels = ~levels; } or_mask = font_info.data[row] << xshift; - and_mask = (font_info.data[row] & level_bits) << xshift; + and_mask = (font_info.data[row] & levels) << xshift; write_word_misaligned_OR(draw_buffer_level, or_mask, addr, wbit); // If we're not bold write the AND mask. //if(!(flags & FONT_BOLD)) diff --git a/flight/modules/PathPlanner/pathplanner.c b/flight/modules/PathPlanner/pathplanner.c index 530cc6ca8..d9bd44724 100644 --- a/flight/modules/PathPlanner/pathplanner.c +++ b/flight/modules/PathPlanner/pathplanner.c @@ -215,29 +215,29 @@ void updatePathDesired(__attribute__((unused)) UAVObjEvent * ev) { // use local variables, dont use stack since this is huge and a callback, // dont use the globals because we cant use mutexes here - static WaypointActiveData waypointActive; - static PathActionData pathAction; - static WaypointData waypoint; + static WaypointActiveData waypointActiveData; + static PathActionData pathActionData; + static WaypointData waypointData; static PathDesiredData pathDesired; // find out current waypoint - WaypointActiveGet(&waypointActive); + WaypointActiveGet(&waypointActiveData); - WaypointInstGet(waypointActive.Index,&waypoint); - PathActionInstGet(waypoint.Action, &pathAction); + WaypointInstGet(waypointActiveData.Index,&waypointData); + PathActionInstGet(waypointData.Action, &pathActionData); - pathDesired.End[PATHDESIRED_END_NORTH] = waypoint.Position[WAYPOINT_POSITION_NORTH]; - pathDesired.End[PATHDESIRED_END_EAST] = waypoint.Position[WAYPOINT_POSITION_EAST]; - pathDesired.End[PATHDESIRED_END_DOWN] = waypoint.Position[WAYPOINT_POSITION_DOWN]; - pathDesired.EndingVelocity = waypoint.Velocity; - pathDesired.Mode = pathAction.Mode; - pathDesired.ModeParameters[0] = pathAction.ModeParameters[0]; - pathDesired.ModeParameters[1] = pathAction.ModeParameters[1]; - pathDesired.ModeParameters[2] = pathAction.ModeParameters[2]; - pathDesired.ModeParameters[3] = pathAction.ModeParameters[3]; - pathDesired.UID = waypointActive.Index; + pathDesired.End[PATHDESIRED_END_NORTH] = waypointData.Position[WAYPOINT_POSITION_NORTH]; + pathDesired.End[PATHDESIRED_END_EAST] = waypointData.Position[WAYPOINT_POSITION_EAST]; + pathDesired.End[PATHDESIRED_END_DOWN] = waypointData.Position[WAYPOINT_POSITION_DOWN]; + pathDesired.EndingVelocity = waypointData.Velocity; + pathDesired.Mode = pathActionData.Mode; + pathDesired.ModeParameters[0] = pathActionData.ModeParameters[0]; + pathDesired.ModeParameters[1] = pathActionData.ModeParameters[1]; + pathDesired.ModeParameters[2] = pathActionData.ModeParameters[2]; + pathDesired.ModeParameters[3] = pathActionData.ModeParameters[3]; + pathDesired.UID = waypointActiveData.Index; - if(waypointActive.Index == 0) { + if(waypointActiveData.Index == 0) { PositionActualData positionActual; PositionActualGet(&positionActual); // First waypoint has itself as start point (used to be home position but that proved dangerous when looping) @@ -260,7 +260,6 @@ void updatePathDesired(__attribute__((unused)) UAVObjEvent * ev) { pathDesired.StartingVelocity = waypointPrev.Velocity; } PathDesiredSet(&pathDesired); - } // helper function to go to a specific waypoint diff --git a/flight/modules/Sensors/sensors.c b/flight/modules/Sensors/sensors.c index 86829956e..feefbe1e2 100644 --- a/flight/modules/Sensors/sensors.c +++ b/flight/modules/Sensors/sensors.c @@ -487,7 +487,7 @@ static void magOffsetEstimation(MagnetometerData *mag) const float Rz = homeLocation.Be[2]; const float rate = cal.MagBiasNullingRate; - float R[3][3]; + float Rot[3][3]; float B_e[3]; float xy[2]; float delta[3]; @@ -496,9 +496,9 @@ static void magOffsetEstimation(MagnetometerData *mag) Quaternion2R(&attitude.q1, R); // Rotate the mag into the NED frame - B_e[0] = R[0][0] * mag->x + R[1][0] * mag->y + R[2][0] * mag->z; - B_e[1] = R[0][1] * mag->x + R[1][1] * mag->y + R[2][1] * mag->z; - B_e[2] = R[0][2] * mag->x + R[1][2] * mag->y + R[2][2] * mag->z; + B_e[0] = Rot[0][0] * mag->x + Rot[1][0] * mag->y + Rot[2][0] * mag->z; + B_e[1] = Rot[0][1] * mag->x + Rot[1][1] * mag->y + Rot[2][1] * mag->z; + B_e[2] = Rot[0][2] * mag->x + Rot[1][2] * mag->y + Rot[2][2] * mag->z; float cy = cosf(DEG2RAD(attitude.Yaw)); float sy = sinf(DEG2RAD(attitude.Yaw)); diff --git a/flight/modules/Stabilization/stabilization.c b/flight/modules/Stabilization/stabilization.c index b417864e6..d9b17f1c2 100644 --- a/flight/modules/Stabilization/stabilization.c +++ b/flight/modules/Stabilization/stabilization.c @@ -113,7 +113,9 @@ int32_t StabilizationStart() // Start main task xTaskCreate(stabilizationTask, (signed char*)"Stabilization", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_STABILIZATION, taskHandle); +#ifdef PIOS_INCLUDE_WDG PIOS_WDG_RegisterFlag(PIOS_WDG_STABILIZATION); +#endif return 0; } @@ -161,7 +163,9 @@ static void stabilizationTask(__attribute__((unused)) void* parameters) while(1) { float dT; +#ifdef PIOS_INCLUDE_WDG PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION); +#endif // Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe if ( xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE ) diff --git a/flight/modules/VtolPathFollower/vtolpathfollower.c b/flight/modules/VtolPathFollower/vtolpathfollower.c index 8d1d21484..f18be2605 100644 --- a/flight/modules/VtolPathFollower/vtolpathfollower.c +++ b/flight/modules/VtolPathFollower/vtolpathfollower.c @@ -566,7 +566,6 @@ static void updateVtolDesiredAttitude(bool yaw_attitude) StabilizationDesiredData stabDesired; AttitudeActualData attitudeActual; NedAccelData nedAccel; - VtolPathFollowerSettingsData vtolpathfollowerSettings; StabilizationSettingsData stabSettings; SystemSettingsData systemSettings; @@ -580,8 +579,6 @@ static void updateVtolDesiredAttitude(bool yaw_attitude) float downCommand; SystemSettingsGet(&systemSettings); - VtolPathFollowerSettingsGet(&vtolpathfollowerSettings); - VelocityActualGet(&velocityActual); VelocityDesiredGet(&velocityDesired); StabilizationDesiredGet(&stabDesired); diff --git a/flight/pios/common/pios_adxl345.c b/flight/pios/common/pios_adxl345.c index f8e23e8d3..0b2b08a97 100644 --- a/flight/pios/common/pios_adxl345.c +++ b/flight/pios/common/pios_adxl345.c @@ -70,13 +70,13 @@ static struct adxl345_dev * PIOS_ADXL345_alloc(void) * @brief Validate the handle to the spi device * @returns 0 for valid device or -1 otherwise */ -static int32_t PIOS_ADXL345_Validate(struct adxl345_dev * dev) +static int32_t PIOS_ADXL345_Validate(struct adxl345_dev *vdev) { - if (dev == NULL) + if (vdev == NULL) return -1; - if (dev->magic != PIOS_ADXL345_DEV_MAGIC) + if (vdev->magic != PIOS_ADXL345_DEV_MAGIC) return -2; - if (dev->spi_id == 0) + if (vdev->spi_id == 0) return -3; return 0; } diff --git a/flight/pios/common/pios_bma180.c b/flight/pios/common/pios_bma180.c index 35fd09d2f..c6a7210b5 100644 --- a/flight/pios/common/pios_bma180.c +++ b/flight/pios/common/pios_bma180.c @@ -86,13 +86,13 @@ static struct bma180_dev * PIOS_BMA180_alloc(void) * @brief Validate the handle to the spi device * @returns 0 for valid device or -1 otherwise */ -static int32_t PIOS_BMA180_Validate(struct bma180_dev * dev) +static int32_t PIOS_BMA180_Validate(struct bma180_dev *vdev) { - if (dev == NULL) + if (vdev == NULL) return -1; - if (dev->magic != PIOS_BMA180_DEV_MAGIC) + if (vdev->magic != PIOS_BMA180_DEV_MAGIC) return -2; - if (dev->spi_id == 0) + if (vdev->spi_id == 0) return -3; return 0; } @@ -128,10 +128,11 @@ int32_t PIOS_BMA180_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_ */ int32_t PIOS_BMA180_ClaimBus() { - if(PIOS_BMA180_Validate(dev) != 0) + if (PIOS_BMA180_Validate(dev) != 0) { return -1; + } - if(PIOS_SPI_ClaimBus(dev->spi_id) != 0) { + if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) { return -1; } @@ -141,19 +142,22 @@ int32_t PIOS_BMA180_ClaimBus() } /** - * @brief Claim the SPI bus for the accel communications and select this chip + * @brief Claim the SPI bus for the accel communications and select this chip. Call from an ISR. + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * @return 0 if successful, -1 if unable to claim bus */ -int32_t PIOS_BMA180_ClaimBusISR() +int32_t PIOS_BMA180_ClaimBusISR(bool *woken) { - if(PIOS_BMA180_Validate(dev) != 0) - return -1; - - if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) { + if (PIOS_BMA180_Validate(dev) != 0) { return -1; } - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + if (PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) { + return -1; + } + + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0); return 0; } @@ -162,13 +166,29 @@ int32_t PIOS_BMA180_ClaimBusISR() * @return 0 if successful */ int32_t PIOS_BMA180_ReleaseBus() +{ + if (PIOS_BMA180_Validate(dev) != 0) { + return -1; + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); + + return PIOS_SPI_ReleaseBus(dev->spi_id); +} + +/** + * @brief Release the SPI bus for the accel communications and end the transaction. Call from an ISR + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged + * @return 0 if successful + */ +int32_t PIOS_BMA180_ReleaseBusISR(bool *woken) { if(PIOS_BMA180_Validate(dev) != 0) return -1; - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,1); + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); - return PIOS_SPI_ReleaseBus(dev->spi_id); + return PIOS_SPI_ReleaseBusISR(dev->spi_id, woken); } /** @@ -431,19 +451,21 @@ int32_t PIOS_BMA180_Test() } /** - * @brief IRQ Handler. Read data from the BMA180 FIFO and push onto a local fifo. + * @brief EXTI IRQ Handler. Read data from the BMA180 FIFO and push onto a local fifo. + * @return a boolean to the EXTI IRQ Handler wrapper indicating if a + * higher priority task is now eligible to run */ int32_t bma180_irqs = 0; bool PIOS_BMA180_IRQHandler(void) { - bma180_irqs++; - + bool woken = false; static const uint8_t pios_bma180_req_buf[7] = {BMA_X_LSB_ADDR | 0x80,0,0,0,0,0}; uint8_t pios_bma180_dmabuf[8]; - + bma180_irqs++; + // If we can't get the bus then just move on for efficiency - if(PIOS_BMA180_ClaimBusISR() != 0) { - return false; // Something else is using bus, miss this data + if (PIOS_BMA180_ClaimBusISR(&woken) != 0) { + return woken; // Something else is using bus, miss this data } PIOS_SPI_TransferBlock(dev->spi_id,pios_bma180_req_buf,(uint8_t *) pios_bma180_dmabuf, @@ -453,11 +475,12 @@ bool PIOS_BMA180_IRQHandler(void) struct pios_bma180_data data; // Don't release bus till data has copied - PIOS_BMA180_ReleaseBus(); + PIOS_BMA180_ReleaseBusISR(&woken); // Must not return before releasing bus - if(fifoBuf_getFree(&dev->fifo) < sizeof(data)) - return false; + if (fifoBuf_getFree(&dev->fifo) < sizeof(data)) { + return woken; + } // Bottom two bits indicate new data and are constant zeros. Don't right // shift because it drops sign bit @@ -471,7 +494,7 @@ bool PIOS_BMA180_IRQHandler(void) fifoBuf_putData(&dev->fifo, (uint8_t *) &data, sizeof(data)); - return false; + return woken; } #endif /* PIOS_INCLUDE_BMA180 */ diff --git a/flight/pios/common/pios_flashfs_logfs.c b/flight/pios/common/pios_flashfs_logfs.c index 0e54dd9e9..ed6b95131 100644 --- a/flight/pios/common/pios_flashfs_logfs.c +++ b/flight/pios/common/pios_flashfs_logfs.c @@ -29,13 +29,12 @@ #ifdef PIOS_INCLUDE_FLASH -#include "openpilot.h" +#include +#include +#include #include "pios_flashfs_logfs_priv.h" -#include - - /* * Filesystem state data tracked in RAM */ diff --git a/flight/pios/common/pios_l3gd20.c b/flight/pios/common/pios_l3gd20.c index 6ca37a2d1..fb621fffd 100644 --- a/flight/pios/common/pios_l3gd20.c +++ b/flight/pios/common/pios_l3gd20.c @@ -60,9 +60,11 @@ static int32_t PIOS_L3GD20_Validate(struct l3gd20_dev * dev); static void PIOS_L3GD20_Config(struct pios_l3gd20_cfg const * cfg); static int32_t PIOS_L3GD20_SetReg(uint8_t address, uint8_t buffer); static int32_t PIOS_L3GD20_GetReg(uint8_t address); +static int32_t PIOS_L3GD20_GetRegISR(uint8_t address, bool *woken); static int32_t PIOS_L3GD20_ClaimBus(); -static int32_t PIOS_L3GD20_ClaimBusIsr(); +static int32_t PIOS_L3GD20_ClaimBusISR(bool *woken); static int32_t PIOS_L3GD20_ReleaseBus(); +static int32_t PIOS_L3GD20_ReleaseBusISR(bool *woken); volatile bool l3gd20_configured = false; @@ -93,13 +95,13 @@ static struct l3gd20_dev * PIOS_L3GD20_alloc(void) * @brief Validate the handle to the spi device * @returns 0 for valid device or -1 otherwise */ -static int32_t PIOS_L3GD20_Validate(struct l3gd20_dev * dev) +static int32_t PIOS_L3GD20_Validate(struct l3gd20_dev *vdev) { - if (dev == NULL) + if (vdev == NULL) return -1; - if (dev->magic != PIOS_L3GD20_DEV_MAGIC) + if (vdev->magic != PIOS_L3GD20_DEV_MAGIC) return -2; - if (dev->spi_id == 0) + if (vdev->spi_id == 0) return -3; return 0; } @@ -191,17 +193,19 @@ static int32_t PIOS_L3GD20_ClaimBus() /** * @brief Claim the SPI bus for the accel communications and select this chip + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * @return 0 if successful, -1 for invalid device, -2 if unable to claim bus */ -static int32_t PIOS_L3GD20_ClaimBusIsr() +static int32_t PIOS_L3GD20_ClaimBusISR(bool *woken) { - if(PIOS_L3GD20_Validate(dev) != 0) + if(PIOS_L3GD20_Validate(dev) != 0) { return -1; - - if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) + } + if(PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) { return -2; - - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0); return 0; } @@ -211,14 +215,28 @@ static int32_t PIOS_L3GD20_ClaimBusIsr() */ int32_t PIOS_L3GD20_ReleaseBus() { - if(PIOS_L3GD20_Validate(dev) != 0) + if(PIOS_L3GD20_Validate(dev) != 0) { return -1; - - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,1); - + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); return PIOS_SPI_ReleaseBus(dev->spi_id); } +/** + * @brief Release the SPI bus for the accel communications and end the transaction + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged + * @return 0 if successful, -1 for invalid device + */ +int32_t PIOS_L3GD20_ReleaseBusISR(bool *woken) +{ + if(PIOS_L3GD20_Validate(dev) != 0) { + return -1; + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); + return PIOS_SPI_ReleaseBusISR(dev->spi_id, woken); +} + /** * @brief Read a register from L3GD20 * @returns The register value or -1 if failure to get bus @@ -238,6 +256,26 @@ static int32_t PIOS_L3GD20_GetReg(uint8_t reg) return data; } +/** + * @brief Read a register from L3GD20 in an ISR context + * @param reg[in] Register address to be read + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged + * @return The register value or -1 if failure to get bus + */ +static int32_t PIOS_L3GD20_GetRegISR(uint8_t reg, bool *woken) +{ + uint8_t data; + + if(PIOS_L3GD20_ClaimBusISR(woken) != 0) { + return -1; + } + PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte + data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response + PIOS_L3GD20_ReleaseBusISR(woken); + return data; +} + /** * @brief Writes one byte to the L3GD20 * \param[in] reg Register address @@ -349,34 +387,38 @@ uint8_t PIOS_L3GD20_Test(void) } /** -* @brief IRQ Handler. Read all the data from onboard buffer +* @brief EXTI IRQ Handler. Read all the data from onboard buffer + * @return a boolean to the EXTI IRQ Handler wrapper indicating if a + * higher priority task is now eligible to run */ bool PIOS_L3GD20_IRQHandler(void) { - l3gd20_irq++; - + bool woken = false; struct pios_l3gd20_data data; uint8_t buf[7] = {PIOS_L3GD20_GYRO_X_OUT_LSB | 0x80 | 0x40, 0, 0, 0, 0, 0, 0}; uint8_t rec[7]; + l3gd20_irq++; + /* This code duplicates ReadGyros above but uses ClaimBusIsr */ - if(PIOS_L3GD20_ClaimBusIsr() != 0) - return false; - - if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) { - PIOS_L3GD20_ReleaseBus(); - return false; + if (PIOS_L3GD20_ClaimBusISR(&woken) != 0) { + return woken; } - PIOS_L3GD20_ReleaseBus(); + if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) { + PIOS_L3GD20_ReleaseBusISR(&woken); + return woken; + } + + PIOS_L3GD20_ReleaseBusISR(&woken); memcpy((uint8_t *) &(data.gyro_x), &rec[1], 6); - data.temperature = PIOS_L3GD20_GetReg(PIOS_L3GD20_OUT_TEMP); + data.temperature = PIOS_L3GD20_GetRegISR(PIOS_L3GD20_OUT_TEMP, &woken); - portBASE_TYPE xHigherPriorityTaskWoken; - xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken); + signed portBASE_TYPE higherPriorityTaskWoken; + xQueueSendToBackFromISR(dev->queue, (void *) &data, &higherPriorityTaskWoken); - return xHigherPriorityTaskWoken == pdTRUE; + return (woken || higherPriorityTaskWoken == pdTRUE); } #endif /* PIOS_INCLUDE_L3GD20 */ diff --git a/flight/pios/common/pios_mpu6000.c b/flight/pios/common/pios_mpu6000.c index 2b2d06b0b..acbc9d4c5 100644 --- a/flight/pios/common/pios_mpu6000.c +++ b/flight/pios/common/pios_mpu6000.c @@ -91,13 +91,13 @@ static struct mpu6000_dev * PIOS_MPU6000_alloc(void) * @brief Validate the handle to the spi device * @returns 0 for valid device or -1 otherwise */ -static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev * dev) +static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev *vdev) { - if (dev == NULL) + if (vdev == NULL) return -1; - if (dev->magic != PIOS_MPU6000_DEV_MAGIC) + if (vdev->magic != PIOS_MPU6000_DEV_MAGIC) return -2; - if (dev->spi_id == 0) + if (vdev->spi_id == 0) return -3; return 0; } @@ -197,7 +197,12 @@ int32_t PIOS_MPU6000_ConfigureRanges( { if(dev == NULL) return -1; + + // TODO: check that changing the SPI clock speed is safe + // to do here given that interrupts are enabled and the bus has + // not been claimed/is not claimed during this call PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_256); + // update filter settings while (PIOS_MPU6000_SetReg(PIOS_MPU6000_DLPF_CFG_REG, filterSetting) != 0); @@ -225,39 +230,63 @@ int32_t PIOS_MPU6000_ConfigureRanges( /** * @brief Claim the SPI bus for the accel communications and select this chip * @return 0 if successful, -1 for invalid device, -2 if unable to claim bus - * @param fromIsr[in] Tells if the function is being called from a ISR or not */ -static int32_t PIOS_MPU6000_ClaimBus(bool fromIsr) +static int32_t PIOS_MPU6000_ClaimBus() { - if(PIOS_MPU6000_Validate(dev) != 0) + if(PIOS_MPU6000_Validate(dev) != 0) { return -1; - if(fromIsr){ - if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) - return -2; - } else { - if(PIOS_SPI_ClaimBus(dev->spi_id) != 0) - return -2; } - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) { + return -2; + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0); + return 0; +} + +/** + * @brief Claim the SPI bus for the accel communications and select this chip + * @return 0 if successful, -1 for invalid device, -2 if unable to claim bus + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged + */ +static int32_t PIOS_MPU6000_ClaimBusISR(bool *woken) +{ + if (PIOS_MPU6000_Validate(dev) != 0) { + return -1; + } + if (PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) { + return -2; + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0); return 0; } /** * @brief Release the SPI bus for the accel communications and end the transaction * @return 0 if successful - * @param fromIsr[in] Tells if the function is being called from a ISR or not */ -int32_t PIOS_MPU6000_ReleaseBus(bool fromIsr) +static int32_t PIOS_MPU6000_ReleaseBus() { - if(PIOS_MPU6000_Validate(dev) != 0) + if(PIOS_MPU6000_Validate(dev) != 0) { return -1; - - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,1); - if(fromIsr){ - return PIOS_SPI_ReleaseBusISR(dev->spi_id); - } else { - return PIOS_SPI_ReleaseBus(dev->spi_id); } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); + return PIOS_SPI_ReleaseBus(dev->spi_id); +} + +/** + * @brief Release the SPI bus for the accel communications and end the transaction + * @return 0 if successful + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged + */ +static int32_t PIOS_MPU6000_ReleaseBusISR(bool *woken) +{ + if(PIOS_MPU6000_Validate(dev) != 0) { + return -1; + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); + return PIOS_SPI_ReleaseBusISR(dev->spi_id, woken); } /** @@ -269,13 +298,14 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg) { uint8_t data; - if(PIOS_MPU6000_ClaimBus(false) != 0) + if(PIOS_MPU6000_ClaimBus() != 0) { return -1; + } PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response - PIOS_MPU6000_ReleaseBus(false); + PIOS_MPU6000_ReleaseBus(); return data; } @@ -289,20 +319,21 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg) */ static int32_t PIOS_MPU6000_SetReg(uint8_t reg, uint8_t data) { - if(PIOS_MPU6000_ClaimBus(false) != 0) + if (PIOS_MPU6000_ClaimBus() != 0) { return -1; + } - if(PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg) != 0) { - PIOS_MPU6000_ReleaseBus(false); + if (PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg) != 0) { + PIOS_MPU6000_ReleaseBus(); return -2; } - if(PIOS_SPI_TransferByte(dev->spi_id, data) != 0) { - PIOS_MPU6000_ReleaseBus(false); + if (PIOS_SPI_TransferByte(dev->spi_id, data) != 0) { + PIOS_MPU6000_ReleaseBus(); return -3; } - - PIOS_MPU6000_ReleaseBus(false); + + PIOS_MPU6000_ReleaseBus(); return 0; } @@ -318,13 +349,15 @@ int32_t PIOS_MPU6000_ReadGyros(struct pios_mpu6000_data * data) uint8_t buf[7] = {PIOS_MPU6000_GYRO_X_OUT_MSB | 0x80, 0, 0, 0, 0, 0, 0}; uint8_t rec[7]; - if(PIOS_MPU6000_ClaimBus(false) != 0) + if (PIOS_MPU6000_ClaimBus() != 0) { return -1; + } - if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) + if (PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) { return -2; - - PIOS_MPU6000_ReleaseBus(false); + } + + PIOS_MPU6000_ReleaseBus(); data->gyro_x = rec[1] << 8 | rec[2]; data->gyro_y = rec[3] << 8 | rec[4]; @@ -407,31 +440,34 @@ int32_t PIOS_MPU6000_Test(void) } /** - * @brief Run self-test operation. - * \return 0 if test succeeded - * \return non-zero value if test succeeded - * @param fromIsr[in] Tells if the function is being called from a ISR or not + * @brief Obtains the number of bytes in the FIFO. Call from ISR only. + * @return the number of bytes in the FIFO + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged */ -static int32_t PIOS_MPU6000_FifoDepth(bool fromIsr) +static int32_t PIOS_MPU6000_FifoDepthISR(bool *woken) { uint8_t mpu6000_send_buf[3] = {PIOS_MPU6000_FIFO_CNT_MSB | 0x80, 0, 0}; uint8_t mpu6000_rec_buf[3]; - if(PIOS_MPU6000_ClaimBus(fromIsr) != 0) - return -1; - - if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { - PIOS_MPU6000_ReleaseBus(fromIsr); + if(PIOS_MPU6000_ClaimBusISR(woken) != 0) { return -1; } - PIOS_MPU6000_ReleaseBus(fromIsr); + if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { + PIOS_MPU6000_ReleaseBusISR(woken); + return -1; + } + + PIOS_MPU6000_ReleaseBusISR(woken); return (mpu6000_rec_buf[1] << 8) | mpu6000_rec_buf[2]; } /** -* @brief IRQ Handler. Read all the data from onboard buffer +* @brief EXTI IRQ Handler. Read all the data from onboard buffer +* @return a boolean to the EXTI IRQ Handler wrapper indicating if a +* higher priority task is now eligible to run */ uint32_t mpu6000_irq = 0; int32_t mpu6000_count; @@ -446,46 +482,50 @@ uint32_t mpu6000_transfer_size; bool PIOS_MPU6000_IRQHandler(void) { + bool woken = false; static uint32_t timeval; mpu6000_interval_us = PIOS_DELAY_DiffuS(timeval); timeval = PIOS_DELAY_GetRaw(); - if (!mpu6000_configured) + if (!mpu6000_configured) { return false; + } - mpu6000_count = PIOS_MPU6000_FifoDepth(true); - if (mpu6000_count < (int32_t)sizeof(struct pios_mpu6000_data)) - return false; + mpu6000_count = PIOS_MPU6000_FifoDepthISR(&woken); + if (mpu6000_count < (int32_t)sizeof(struct pios_mpu6000_data)) { + return woken; + } - if (PIOS_MPU6000_ClaimBus(true) != 0) - return false; + if (PIOS_MPU6000_ClaimBusISR(&woken) != 0) { + return woken; + } static uint8_t mpu6000_send_buf[1 + sizeof(struct pios_mpu6000_data) ] = {PIOS_MPU6000_FIFO_REG | 0x80, 0, 0, 0, 0, 0, 0, 0, 0}; static uint8_t mpu6000_rec_buf[1 + sizeof(struct pios_mpu6000_data) ]; if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { - PIOS_MPU6000_ReleaseBus(true); + PIOS_MPU6000_ReleaseBusISR(&woken); mpu6000_fails++; - return false; + return woken; } - PIOS_MPU6000_ReleaseBus(true); + PIOS_MPU6000_ReleaseBusISR(&woken); static struct pios_mpu6000_data data; // In the case where extras samples backed up grabbed an extra if (mpu6000_count >= (int32_t)(sizeof(data) * 2)) { mpu6000_fifo_backup++; - if (PIOS_MPU6000_ClaimBus(true) != 0) - return false; + if (PIOS_MPU6000_ClaimBusISR(&woken) != 0) + return woken; if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { - PIOS_MPU6000_ReleaseBus(true); + PIOS_MPU6000_ReleaseBusISR(&woken); mpu6000_fails++; - return false; + return woken; } - PIOS_MPU6000_ReleaseBus(true); + PIOS_MPU6000_ReleaseBusISR(&woken); } // Rotate the sensor to OP convention. The datasheet defines X as towards the right @@ -548,14 +588,14 @@ bool PIOS_MPU6000_IRQHandler(void) data.temperature = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; #endif - portBASE_TYPE xHigherPriorityTaskWoken; - xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken); + signed portBASE_TYPE higherPriorityTaskWoken; + xQueueSendToBackFromISR(dev->queue, (void *) &data, &higherPriorityTaskWoken); mpu6000_irq++; mpu6000_time_us = PIOS_DELAY_DiffuS(timeval); - return xHigherPriorityTaskWoken == pdTRUE; + return (woken || higherPriorityTaskWoken == pdTRUE); } #endif /* PIOS_INCLUDE_MPU6000 */ diff --git a/flight/pios/common/pios_rfm22b.c b/flight/pios/common/pios_rfm22b.c index 203d8b1bb..a3542d946 100644 --- a/flight/pios/common/pios_rfm22b.c +++ b/flight/pios/common/pios_rfm22b.c @@ -2017,6 +2017,7 @@ static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *radio_d #endif #if defined(PIOS_INCLUDE_RFM22B_RCVR) ppm_output = true; + radio_dev->ppm_fresh = true; for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) { radio_dev->ppm_channel[i] = ppmp->channels[i]; } diff --git a/flight/pios/common/pios_rfm22b_rcvr.c b/flight/pios/common/pios_rfm22b_rcvr.c index faa21b604..e718e8481 100644 --- a/flight/pios/common/pios_rfm22b_rcvr.c +++ b/flight/pios/common/pios_rfm22b_rcvr.c @@ -102,7 +102,7 @@ static void PIOS_RFM22B_RCVR_Supervisor(uint32_t rcvr_id) { } // RTC runs at 625Hz. - if (++(rfm22b_dev->ppm_supv_timer) < (PIOS_RFM22B_RCVR_TIMEOUT_MS * 1000 / 625)) { + if (++(rfm22b_dev->ppm_supv_timer) < (PIOS_RFM22B_RCVR_TIMEOUT_MS * 625 / 1000)) { return; } rfm22b_dev->ppm_supv_timer = 0; @@ -110,7 +110,7 @@ static void PIOS_RFM22B_RCVR_Supervisor(uint32_t rcvr_id) { // Have we received fresh values since the last update? if (!rfm22b_dev->ppm_fresh) { for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) { - rfm22b_dev->ppm_channel[i] = 0; + rfm22b_dev->ppm_channel[i] = PIOS_RCVR_TIMEOUT; } } rfm22b_dev->ppm_fresh = false; diff --git a/flight/pios/inc/pios_rcvr_priv.h b/flight/pios/inc/pios_rcvr_priv.h index 7b41d2764..46ced2e24 100644 --- a/flight/pios/inc/pios_rcvr_priv.h +++ b/flight/pios/inc/pios_rcvr_priv.h @@ -33,8 +33,6 @@ #include -extern uint32_t pios_rcvr_max_channel; - extern int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id); extern void PIOS_RCVR_IRQ_Handler(uint32_t rcvr_id); diff --git a/flight/pios/inc/pios_spi.h b/flight/pios/inc/pios_spi.h index 951459b94..5740e1e67 100644 --- a/flight/pios/inc/pios_spi.h +++ b/flight/pios/inc/pios_spi.h @@ -49,9 +49,9 @@ extern int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b); extern int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback); extern int32_t PIOS_SPI_Busy(uint32_t spi_id); extern int32_t PIOS_SPI_ClaimBus(uint32_t spi_id); -extern int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id); +extern int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id, bool *woken); extern int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id); -extern int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id); +extern int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id, bool *woken); extern void PIOS_SPI_IRQ_Handler(uint32_t spi_id); extern void PIOS_SPI_SetPrescalar(uint32_t spi_id, uint32_t prescalar); diff --git a/flight/pios/inc/pios_usb_priv.h b/flight/pios/inc/pios_usb_priv.h index 76b430a99..ee3c26bd9 100644 --- a/flight/pios/inc/pios_usb_priv.h +++ b/flight/pios/inc/pios_usb_priv.h @@ -37,6 +37,7 @@ struct pios_usb_cfg { struct stm32_irq irq; struct stm32_gpio vsense; + bool vsense_active_low; }; extern int32_t PIOS_USB_Init(uint32_t * usb_id, const struct pios_usb_cfg * cfg); diff --git a/flight/pios/stm32f10x/pios_i2c.c b/flight/pios/stm32f10x/pios_i2c.c index f61d00c14..054cc1454 100644 --- a/flight/pios/stm32f10x/pios_i2c.c +++ b/flight/pios/stm32f10x/pios_i2c.c @@ -126,7 +126,7 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter); static void i2c_adapter_log_fault(enum pios_i2c_error_type type); -const static struct i2c_adapter_transition i2c_adapter_transitions[I2C_STATE_NUM_STATES] = { +static const struct i2c_adapter_transition i2c_adapter_transitions[I2C_STATE_NUM_STATES] = { [I2C_STATE_FSM_FAULT] = { .entry_fn = go_fsm_fault, .next_state = { @@ -607,9 +607,6 @@ static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum * guarantee that the entry function never depends on the previous * state. This way, it cannot ever know what the previous state was. */ - enum i2c_adapter_state prev_state = i2c_adapter->curr_state; - if (prev_state) ; - i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[event]; /* Call the entry function (if any) for the next state. */ @@ -626,10 +623,6 @@ static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum static void i2c_adapter_process_auto(struct pios_i2c_adapter *i2c_adapter) { PIOS_IRQ_Disable(); - - enum i2c_adapter_state prev_state = i2c_adapter->curr_state; - if (prev_state) ; - while (i2c_adapter_transitions[i2c_adapter->curr_state].next_state[I2C_EVENT_AUTO]) { i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[I2C_EVENT_AUTO]; @@ -659,7 +652,7 @@ static bool i2c_adapter_wait_for_stopped(struct pios_i2c_adapter *i2c_adapter) * in spinning on this bit in the ISR forever. */ #define I2C_CR1_STOP_REQUESTED 0x0200 - for (guard = 1e6; /* FIXME: should use the configured bus timeout */ + for (guard = 1000000; /* FIXME: should use the configured bus timeout */ guard && (i2c_adapter->cfg->regs->CR1 & I2C_CR1_STOP_REQUESTED); guard--) continue; if (!guard) { diff --git a/flight/pios/stm32f10x/pios_ppm.c b/flight/pios/stm32f10x/pios_ppm.c index 2088e426e..8933d9a46 100644 --- a/flight/pios/stm32f10x/pios_ppm.c +++ b/flight/pios/stm32f10x/pios_ppm.c @@ -50,7 +50,7 @@ const struct pios_rcvr_driver pios_ppm_rcvr_driver = { #define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds /* Local Variables */ -static TIM_ICInitTypeDef TIM_ICInitStructure; +//static TIM_ICInitTypeDef TIM_ICInitStructure; static void PIOS_PPM_Supervisor(uint32_t ppm_id); @@ -156,12 +156,13 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) return -1; } + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + /* Configure the channels to be in capture/compare mode */ for (uint8_t i = 0; i < cfg->num_channels; i++) { const struct pios_tim_channel * chan = &cfg->channels[i]; /* Configure timer for input capture */ - TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; TIM_ICInitStructure.TIM_Channel = chan->timer_chan; TIM_ICInit(chan->timer, &TIM_ICInitStructure); @@ -182,12 +183,6 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) } } - /* Setup local variable which stays in this scope */ - /* Doing this here and using a local variable saves doing it in the ISR */ - TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; - TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; - TIM_ICInitStructure.TIM_ICFilter = 0x0; - ppm_dev->supv_timer = 0; if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) { PIOS_DEBUG_Assert(0); diff --git a/flight/pios/stm32f10x/pios_spi.c b/flight/pios/stm32f10x/pios_spi.c index 4e001b775..6b8d2c88e 100644 --- a/flight/pios/stm32f10x/pios_spi.c +++ b/flight/pios/stm32f10x/pios_spi.c @@ -265,22 +265,33 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id) /** * Claim the SPI bus semaphore from an ISR. Has no timeout. * \param[in] spi SPI number (0 or 1) + * \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * \return 0 if no error * \return -1 if timeout before claiming semaphore */ -int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id) +int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id, bool *woken) { #if defined(PIOS_INCLUDE_FREERTOS) - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE; + bool valid = PIOS_SPI_validate(spi_dev); PIOS_Assert(valid) - if (xSemaphoreTakeFromISR(spi_dev->busy, NULL) != pdTRUE){ + if (xSemaphoreTakeFromISR(spi_dev->busy, &higherPriorityTaskWoken) != pdTRUE){ return -1; } -#endif + if (woken) { + *woken = *woken || (higherPriorityTaskWoken == pdTRUE); + } return 0; +#else + if (woken) { + *woken = false; + } + return PIOS_SPI_ClaimBus(spi_id); +#endif } /** @@ -302,7 +313,6 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) PIOS_IRQ_Disable(); spi_dev->busy = 0; PIOS_IRQ_Enable(); - #endif return 0; } @@ -310,25 +320,30 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) /** * Release the SPI bus semaphore from ISR. Calling the SPI functions does not require this * \param[in] spi SPI number (0 or 1) + * \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * \return 0 if no error */ -int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id) +int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id, bool *woken) { #if defined(PIOS_INCLUDE_FREERTOS) struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE; bool valid = PIOS_SPI_validate(spi_dev); PIOS_Assert(valid) - xSemaphoreGiveFromISR(spi_dev->busy, NULL); + xSemaphoreGiveFromISR(spi_dev->busy, &higherPriorityTaskWoken); + if (woken) { + *woken = *woken || (higherPriorityTaskWoken == pdTRUE); + } + return 0; #else - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - PIOS_IRQ_Disable(); - spi_dev->busy = 0; - PIOS_IRQ_Enable(); - + if (woken) { + *woken = false; + } + return PIOS_SPI_ReleaseBus(spi_id); #endif - return 0; } diff --git a/flight/pios/stm32f10x/pios_usb.c b/flight/pios/stm32f10x/pios_usb.c index 13fb8c3c5..bfecbe3ff 100644 --- a/flight/pios/stm32f10x/pios_usb.c +++ b/flight/pios/stm32f10x/pios_usb.c @@ -215,7 +215,7 @@ bool PIOS_USB_CableConnected(__attribute__((unused)) uint8_t id) if (PIOS_USB_validate(usb_dev) != 0) return false; - return usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin; + return ((usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin) != 0) ^ usb_dev->cfg->vsense_active_low; } /** diff --git a/flight/pios/stm32f4xx/libraries/CMSIS2/Device/ST/STM32F4xx/Source/revoproto/system_stm32f4xx.c b/flight/pios/stm32f4xx/libraries/CMSIS2/Device/ST/STM32F4xx/Source/revoproto/system_stm32f4xx.c index f98b4a14b..bb7776d4b 100644 --- a/flight/pios/stm32f4xx/libraries/CMSIS2/Device/ST/STM32F4xx/Source/revoproto/system_stm32f4xx.c +++ b/flight/pios/stm32f4xx/libraries/CMSIS2/Device/ST/STM32F4xx/Source/revoproto/system_stm32f4xx.c @@ -393,7 +393,7 @@ static void SetSysClock(void) } /* Configure Flash prefetch, Instruction cache, Data cache and wait state */ - FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS; + FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS; /* Select the main PLL as system clock source */ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); diff --git a/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/src/usb_core.c b/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/src/usb_core.c index cdb9992c3..4fe99965c 100644 --- a/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/src/usb_core.c +++ b/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/src/usb_core.c @@ -1330,7 +1330,6 @@ USB_OTG_STS USB_OTG_CoreInitDev (USB_OTG_CORE_HANDLE *pdev) } for (i = 0; i < pdev->cfg.dev_endpoints; i++) { - USB_OTG_DEPCTL_TypeDef depctl; depctl.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[i]->DOEPCTL); if (depctl.b.epena) { diff --git a/flight/pios/stm32f4xx/pios_ppm.c b/flight/pios/stm32f4xx/pios_ppm.c index fad9a22e3..9d976320b 100644 --- a/flight/pios/stm32f4xx/pios_ppm.c +++ b/flight/pios/stm32f4xx/pios_ppm.c @@ -48,9 +48,6 @@ const struct pios_rcvr_driver pios_ppm_rcvr_driver = { #define PIOS_PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds #define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds -/* Local Variables */ -static TIM_ICInitTypeDef TIM_ICInitStructure; - static void PIOS_PPM_Supervisor(uint32_t ppm_id); enum pios_ppm_dev_magic { @@ -155,12 +152,13 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) return -1; } + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + /* Configure the channels to be in capture/compare mode */ for (uint8_t i = 0; i < cfg->num_channels; i++) { const struct pios_tim_channel * chan = &cfg->channels[i]; /* Configure timer for input capture */ - TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; TIM_ICInitStructure.TIM_Channel = chan->timer_chan; TIM_ICInit(chan->timer, &TIM_ICInitStructure); @@ -181,12 +179,6 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) } } - /* Setup local variable which stays in this scope */ - /* Doing this here and using a local variable saves doing it in the ISR */ - TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; - TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; - TIM_ICInitStructure.TIM_ICFilter = 0x0; - if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) { PIOS_DEBUG_Assert(0); } diff --git a/flight/pios/stm32f4xx/pios_spi.c b/flight/pios/stm32f4xx/pios_spi.c index 56134c165..bc8304596 100644 --- a/flight/pios/stm32f4xx/pios_spi.c +++ b/flight/pios/stm32f4xx/pios_spi.c @@ -257,6 +257,18 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id) if (xSemaphoreTake(spi_dev->busy, 0xffff) != pdTRUE) return -1; +#else + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + uint32_t timeout = 0xffff; + while((PIOS_SPI_Busy(spi_id) || spi_dev->busy) && --timeout); + if(timeout == 0) //timed out + return -1; + + PIOS_IRQ_Disable(); + if(spi_dev->busy) + return -1; + spi_dev->busy = 1; + PIOS_IRQ_Enable(); #endif return 0; } @@ -264,25 +276,35 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id) /** * Claim the SPI bus semaphore from an ISR. Has no timeout. * \param[in] spi SPI number (0 or 1) + * \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * \return 0 if no error * \return -1 if timeout before claiming semaphore */ -int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id) +int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id, bool *woken) { #if defined(PIOS_INCLUDE_FREERTOS) - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE; + bool valid = PIOS_SPI_validate(spi_dev); PIOS_Assert(valid) - if (xSemaphoreTakeFromISR(spi_dev->busy, NULL) != pdTRUE){ + if (xSemaphoreTakeFromISR(spi_dev->busy, &higherPriorityTaskWoken) != pdTRUE){ return -1; } -#endif + if (woken) { + *woken = *woken || (higherPriorityTaskWoken == pdTRUE); + } return 0; +#else + if (woken) { + *woken = false; + } + return PIOS_SPI_ClaimBus(spi_id); +#endif } - /** * Release the SPI bus semaphore. Calling the SPI functions does not require this * \param[in] spi SPI number (0 or 1) @@ -297,6 +319,11 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) PIOS_Assert(valid) xSemaphoreGive(spi_dev->busy); +#else + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + PIOS_IRQ_Disable(); + spi_dev->busy = 0; + PIOS_IRQ_Enable(); #endif return 0; } @@ -304,21 +331,33 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) /** * Release the SPI bus semaphore from ISR. Calling the SPI functions does not require this * \param[in] spi SPI number (0 or 1) + * \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * \return 0 if no error */ -int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id) +int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id, bool *woken) { #if defined(PIOS_INCLUDE_FREERTOS) struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE; bool valid = PIOS_SPI_validate(spi_dev); PIOS_Assert(valid) - xSemaphoreGiveFromISR(spi_dev->busy, NULL); + xSemaphoreGiveFromISR(spi_dev->busy, &higherPriorityTaskWoken); + if (woken) { + *woken = *woken || (higherPriorityTaskWoken == pdTRUE); + } + return 0; +#else + if (woken) { + *woken = false; + } + return PIOS_SPI_ReleaseBus(spi_id); #endif - return 0; } + /** * Controls the RC (Register Clock alias Chip Select) pin of a SPI port * \param[in] spi SPI number (0 or 1) diff --git a/flight/pios/stm32f4xx/pios_usb.c b/flight/pios/stm32f4xx/pios_usb.c index d0592a815..6666e120d 100644 --- a/flight/pios/stm32f4xx/pios_usb.c +++ b/flight/pios/stm32f4xx/pios_usb.c @@ -162,7 +162,7 @@ bool PIOS_USB_CheckAvailable(__attribute__((unused)) uint32_t id) if(!PIOS_USB_validate(usb_dev)) return false; - usb_found = (usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin); + usb_found = ((usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin) != 0) ^ usb_dev->cfg->vsense_active_low; return usb_found; return usb_found != 0 && transfer_possible ? 1 : 0; } diff --git a/flight/targets/boards/coptercontrol/board_hw_defs.c b/flight/targets/boards/coptercontrol/board_hw_defs.c index b4f83f541..ad042fada 100644 --- a/flight/targets/boards/coptercontrol/board_hw_defs.c +++ b/flight/targets/boards/coptercontrol/board_hw_defs.c @@ -1431,7 +1431,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg_cc = { .GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Mode = GPIO_Mode_AF_OD, }, - } + }, + .vsense_active_low = false }; static const struct pios_usb_cfg pios_usb_main_cfg_cc3d = { @@ -1450,7 +1451,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg_cc3d = { .GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Mode = GPIO_Mode_AF_OD, }, - } + }, + .vsense_active_low = false }; #include "pios_usb_board_data_priv.h" diff --git a/flight/targets/boards/oplinkmini/board_hw_defs.c b/flight/targets/boards/oplinkmini/board_hw_defs.c index dc3f135de..d3d34cdd6 100644 --- a/flight/targets/boards/oplinkmini/board_hw_defs.c +++ b/flight/targets/boards/oplinkmini/board_hw_defs.c @@ -582,8 +582,6 @@ const struct pios_ppm_cfg pios_ppm_main_cfg = { #if defined(PIOS_INCLUDE_PPM_OUT) #include -uint32_t pios_ppm_id; - static const struct pios_tim_channel pios_tim_ppmout[] = { { .timer = TIM2, @@ -640,7 +638,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { .GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Mode = GPIO_Mode_AF_OD, }, - } + }, + .vsense_active_low = false }; #include "pios_usb_board_data_priv.h" diff --git a/flight/targets/boards/oplinkmini/firmware/pios_board.c b/flight/targets/boards/oplinkmini/firmware/pios_board.c index c3bd75b71..92569c0b9 100644 --- a/flight/targets/boards/oplinkmini/firmware/pios_board.c +++ b/flight/targets/boards/oplinkmini/firmware/pios_board.c @@ -218,10 +218,9 @@ void PIOS_Board_Init(void) { /* Initalize the RFM22B radio COM device. */ #if defined(PIOS_INCLUDE_RFM22B) { - extern const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision); const struct pios_board_info * bdinfo = &pios_board_info_blob; - const struct pios_rfm22b_cfg *pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) { + const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); + if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) { PIOS_Assert(0); } diff --git a/flight/targets/boards/osd/board_hw_defs.c b/flight/targets/boards/osd/board_hw_defs.c index 674fcbf17..49e3c83db 100644 --- a/flight/targets/boards/osd/board_hw_defs.c +++ b/flight/targets/boards/osd/board_hw_defs.c @@ -502,7 +502,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, }, - } + }, + .vsense_active_low = false }; #include "pios_usb_board_data_priv.h" diff --git a/flight/targets/boards/osd/firmware/pios_board.c b/flight/targets/boards/osd/firmware/pios_board.c index 5aba31dc1..a241c27e9 100644 --- a/flight/targets/boards/osd/firmware/pios_board.c +++ b/flight/targets/boards/osd/firmware/pios_board.c @@ -343,10 +343,10 @@ PIOS_FLASHFS_Logfs_Init(&fs_id, &flashfs_internal_cfg, &pios_internal_flash_driv PIOS_Assert(0); } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); - PIOS_Assert(rx_buffer); + uint8_t *gps_rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); + PIOS_Assert(gps_rx_buffer); if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, - rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, + gps_rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, NULL, 0)) { PIOS_Assert(0); } @@ -361,14 +361,14 @@ PIOS_FLASHFS_Logfs_Init(&fs_id, &flashfs_internal_cfg, &pios_internal_flash_driv PIOS_DEBUG_Assert(0); } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); + uint8_t *aux_rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_RX_BUF_LEN); + uint8_t *aux_tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_TX_BUF_LEN); + PIOS_Assert(aux_rx_buffer); + PIOS_Assert(aux_tx_buffer); if (PIOS_COM_Init(&pios_com_aux_id, &pios_usart_com_driver, pios_usart_aux_id, - rx_buffer, PIOS_COM_AUX_RX_BUF_LEN, - tx_buffer, PIOS_COM_AUX_TX_BUF_LEN)) { + aux_rx_buffer, PIOS_COM_AUX_RX_BUF_LEN, + aux_tx_buffer, PIOS_COM_AUX_TX_BUF_LEN)) { PIOS_DEBUG_Assert(0); } } @@ -383,13 +383,13 @@ PIOS_FLASHFS_Logfs_Init(&fs_id, &flashfs_internal_cfg, &pios_internal_flash_driv PIOS_Assert(0); } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); + uint8_t *telem_rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); + uint8_t *telem_tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); + PIOS_Assert(telem_rx_buffer); + PIOS_Assert(telem_tx_buffer); if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id, - rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { + telem_rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, + telem_tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { PIOS_Assert(0); } } diff --git a/flight/targets/boards/revolution/board_hw_defs.c b/flight/targets/boards/revolution/board_hw_defs.c index 052caaa4c..60ecfb964 100644 --- a/flight/targets/boards/revolution/board_hw_defs.c +++ b/flight/targets/boards/revolution/board_hw_defs.c @@ -1837,7 +1837,8 @@ static const struct pios_usb_cfg pios_usb_main_rm1_cfg = { .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, }, - } + }, + .vsense_active_low = false }; static const struct pios_usb_cfg pios_usb_main_rm2_cfg = { @@ -1857,7 +1858,8 @@ static const struct pios_usb_cfg pios_usb_main_rm2_cfg = { .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, }, - } + }, + .vsense_active_low = false }; const struct pios_usb_cfg * PIOS_BOARD_HW_DEFS_GetUsbCfg (uint32_t board_revision) diff --git a/flight/targets/boards/revolution/firmware/pios_board.c b/flight/targets/boards/revolution/firmware/pios_board.c index 91db49136..79e966398 100644 --- a/flight/targets/boards/revolution/firmware/pios_board.c +++ b/flight/targets/boards/revolution/firmware/pios_board.c @@ -272,7 +272,7 @@ static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg } static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, - const struct pios_com_driver *pios_usart_com_driver,enum pios_dsm_proto *proto, + const struct pios_com_driver *usart_com_driver,enum pios_dsm_proto *proto, ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) { uint32_t pios_usart_dsm_id; @@ -281,7 +281,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm } uint32_t pios_dsm_id; - if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, + if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, usart_com_driver, pios_usart_dsm_id, *proto, *bind)) { PIOS_Assert(0); } @@ -293,11 +293,11 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; } -static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pios_pwm_cfg) +static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg) { /* Set up the receiver port. Later this should be optional */ uint32_t pios_pwm_id; - PIOS_PWM_Init(&pios_pwm_id, pios_pwm_cfg); + PIOS_PWM_Init(&pios_pwm_id, pwm_cfg); uint32_t pios_pwm_rcvr_id; if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { @@ -306,10 +306,10 @@ static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pios_pwm_cfg) pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; } -static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *pios_ppm_cfg) +static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *ppm_cfg) { uint32_t pios_ppm_id; - PIOS_PPM_Init(&pios_ppm_id, pios_ppm_cfg); + PIOS_PPM_Init(&pios_ppm_id, ppm_cfg); uint32_t pios_ppm_rcvr_id; if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { @@ -712,10 +712,8 @@ void PIOS_Board_Init(void) { break; case HWSETTINGS_RADIOPORT_TELEMETRY: { - extern const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision); - const struct pios_board_info * bdinfo = &pios_board_info_blob; - const struct pios_rfm22b_cfg *pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) { + const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); + if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) { PIOS_Assert(0); } diff --git a/flight/targets/boards/revoproto/board_hw_defs.c b/flight/targets/boards/revoproto/board_hw_defs.c index 9577f1596..05f4f8853 100644 --- a/flight/targets/boards/revoproto/board_hw_defs.c +++ b/flight/targets/boards/revoproto/board_hw_defs.c @@ -2003,7 +2003,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, }, - } + }, + .vsense_active_low = false }; #include "pios_usb_board_data_priv.h" diff --git a/flight/targets/boards/revoproto/firmware/pios_board.c b/flight/targets/boards/revoproto/firmware/pios_board.c index 03f532b65..5c5a5e3b6 100644 --- a/flight/targets/boards/revoproto/firmware/pios_board.c +++ b/flight/targets/boards/revoproto/firmware/pios_board.c @@ -339,7 +339,7 @@ static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg } static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, - const struct pios_com_driver *pios_usart_com_driver,enum pios_dsm_proto *proto, + const struct pios_com_driver *usart_com_driver,enum pios_dsm_proto *proto, ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) { uint32_t pios_usart_dsm_id; @@ -348,7 +348,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm } uint32_t pios_dsm_id; - if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, + if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, usart_com_driver, pios_usart_dsm_id, *proto, *bind)) { PIOS_Assert(0); } diff --git a/flight/uavobjects/eventdispatcher.c b/flight/uavobjects/eventdispatcher.c index e56e916b3..962298980 100644 --- a/flight/uavobjects/eventdispatcher.c +++ b/flight/uavobjects/eventdispatcher.c @@ -68,11 +68,11 @@ struct PeriodicObjectListStruct { typedef struct PeriodicObjectListStruct PeriodicObjectList; // Private variables -static PeriodicObjectList* objList; -static xQueueHandle queue; -static xTaskHandle eventTaskHandle; -static xSemaphoreHandle mutex; -static EventStats stats; +static PeriodicObjectList* mObjList; +static xQueueHandle mQueue; +static xTaskHandle mEventTaskHandle; +static xSemaphoreHandle mMutex; +static EventStats mStats; // Private functions static int32_t processPeriodicUpdates(); @@ -89,19 +89,19 @@ static uint16_t randomizePeriod(uint16_t periodMs); int32_t EventDispatcherInitialize() { // Initialize variables - objList = NULL; - memset(&stats, 0, sizeof(EventStats)); + mObjList = NULL; + memset(&mStats, 0, sizeof(EventStats)); - // Create mutex - mutex = xSemaphoreCreateRecursiveMutex(); - if (mutex == NULL) + // Create mMutex + mMutex = xSemaphoreCreateRecursiveMutex(); + if (mMutex == NULL) return -1; // Create event queue - queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(EventCallbackInfo)); + mQueue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(EventCallbackInfo)); // Create task - xTaskCreate( eventTask, (signed char*)"Event", STACK_SIZE, NULL, TASK_PRIORITY, &eventTaskHandle ); + xTaskCreate(eventTask, (signed char*)"Event", STACK_SIZE, NULL, TASK_PRIORITY, &mEventTaskHandle); // Done return 0; @@ -113,9 +113,9 @@ int32_t EventDispatcherInitialize() */ void EventGetStats(EventStats* statsOut) { - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - memcpy(statsOut, &stats, sizeof(EventStats)); - xSemaphoreGiveRecursive(mutex); + xSemaphoreTakeRecursive(mMutex, portMAX_DELAY); + memcpy(statsOut, &mStats, sizeof(EventStats)); + xSemaphoreGiveRecursive(mMutex); } /** @@ -123,9 +123,9 @@ void EventGetStats(EventStats* statsOut) */ void EventClearStats() { - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - memset(&stats, 0, sizeof(EventStats)); - xSemaphoreGiveRecursive(mutex); + xSemaphoreTakeRecursive(mMutex, portMAX_DELAY); + memset(&mStats, 0, sizeof(EventStats)); + xSemaphoreGiveRecursive(mMutex); } /** @@ -143,7 +143,7 @@ int32_t EventCallbackDispatch(UAVObjEvent* ev, UAVObjEventCallback cb) evInfo.cb = cb; evInfo.queue = 0; // Push to queue - return xQueueSend(queue, &evInfo, 0); // will not block if queue is full + return xQueueSend(mQueue, &evInfo, 0); // will not block if queue is full } /** @@ -204,26 +204,26 @@ int32_t EventPeriodicQueueUpdate(UAVObjEvent* ev, xQueueHandle queue, uint16_t p */ static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQueueHandle queue, uint16_t periodMs) { - PeriodicObjectList* objEntry; + PeriodicObjectList *objEntry; // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + xSemaphoreTakeRecursive(mMutex, portMAX_DELAY); // Check that the object is not already connected - LL_FOREACH(objList, objEntry) - { + LL_FOREACH(mObjList, objEntry) { if (objEntry->evInfo.cb == cb && objEntry->evInfo.queue == queue && objEntry->evInfo.ev.obj == ev->obj && objEntry->evInfo.ev.instId == ev->instId && - objEntry->evInfo.ev.event == ev->event) - { + objEntry->evInfo.ev.event == ev->event) { // Already registered, do nothing - xSemaphoreGiveRecursive(mutex); + xSemaphoreGiveRecursive(mMutex); return -1; } } // Create handle objEntry = (PeriodicObjectList*)pvPortMalloc(sizeof(PeriodicObjectList)); - if (objEntry == NULL) return -1; + if (objEntry == NULL) { + return -1; + } objEntry->evInfo.ev.obj = ev->obj; objEntry->evInfo.ev.instId = ev->instId; objEntry->evInfo.ev.event = ev->event; @@ -232,9 +232,9 @@ static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQue objEntry->updatePeriodMs = periodMs; objEntry->timeToNextUpdateMs = randomizePeriod(periodMs); // avoid bunching of updates // Add to list - LL_APPEND(objList, objEntry); + LL_APPEND(mObjList, objEntry); // Release lock - xSemaphoreGiveRecursive(mutex); + xSemaphoreGiveRecursive(mMutex); return 0; } @@ -250,26 +250,24 @@ static int32_t eventPeriodicUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, xQue { PeriodicObjectList* objEntry; // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + xSemaphoreTakeRecursive(mMutex, portMAX_DELAY); // Find object - LL_FOREACH(objList, objEntry) - { + LL_FOREACH(mObjList, objEntry) { if (objEntry->evInfo.cb == cb && objEntry->evInfo.queue == queue && objEntry->evInfo.ev.obj == ev->obj && objEntry->evInfo.ev.instId == ev->instId && - objEntry->evInfo.ev.event == ev->event) - { + objEntry->evInfo.ev.event == ev->event) { // Object found, update period objEntry->updatePeriodMs = periodMs; objEntry->timeToNextUpdateMs = randomizePeriod(periodMs); // avoid bunching of updates // Release lock - xSemaphoreGiveRecursive(mutex); + xSemaphoreGiveRecursive(mMutex); return 0; } } // If this point is reached the object was not found - xSemaphoreGiveRecursive(mutex); + xSemaphoreGiveRecursive(mMutex); return -1; } @@ -283,7 +281,7 @@ static void eventTask() EventCallbackInfo evInfo; /* Must do this in task context to ensure that TaskMonitor has already finished its init */ - PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_EVENTDISPATCHER, eventTaskHandle); + PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_EVENTDISPATCHER, mEventTaskHandle); // Initialize time timeToNextUpdateMs = xTaskGetTickCount()*portTICK_RATE_MS; @@ -295,7 +293,7 @@ static void eventTask() delayMs = timeToNextUpdateMs - (xTaskGetTickCount() * portTICK_RATE_MS); // Wait for queue message - if ( xQueueReceive(queue, &evInfo, delayMs/portTICK_RATE_MS) == pdTRUE ) + if ( xQueueReceive(mQueue, &evInfo, delayMs/portTICK_RATE_MS) == pdTRUE ) { // Invoke callback, if one if ( evInfo.cb != 0) @@ -324,49 +322,43 @@ static int32_t processPeriodicUpdates() int32_t offset; // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + xSemaphoreTakeRecursive(mMutex, portMAX_DELAY); // Iterate through each object and update its timer, if zero then transmit object. // Also calculate smallest delay to next update. timeToNextUpdate = xTaskGetTickCount()*portTICK_RATE_MS + MAX_UPDATE_PERIOD_MS; - LL_FOREACH(objList, objEntry) - { + LL_FOREACH(mObjList, objEntry) { // If object is configured for periodic updates - if (objEntry->updatePeriodMs > 0) - { + if (objEntry->updatePeriodMs > 0) { // Check if time for the next update timeNow = xTaskGetTickCount()*portTICK_RATE_MS; - if (objEntry->timeToNextUpdateMs <= timeNow) - { + if (objEntry->timeToNextUpdateMs <= timeNow) { // Reset timer - offset = ( timeNow - objEntry->timeToNextUpdateMs ) % objEntry->updatePeriodMs; + offset = (timeNow - objEntry->timeToNextUpdateMs) % objEntry->updatePeriodMs; objEntry->timeToNextUpdateMs = timeNow + objEntry->updatePeriodMs - offset; // Invoke callback, if one - if ( objEntry->evInfo.cb != 0) - { + if (objEntry->evInfo.cb != 0) { objEntry->evInfo.cb(&objEntry->evInfo.ev); // the function is expected to copy the event information } // Push event to queue, if one - if ( objEntry->evInfo.queue != 0) - { - if ( xQueueSend(objEntry->evInfo.queue, &objEntry->evInfo.ev, 0) != pdTRUE ) // do not block if queue is full - { - if (objEntry->evInfo.ev.obj != NULL) - stats.lastErrorID = UAVObjGetID(objEntry->evInfo.ev.obj); - ++stats.eventErrors; + if (objEntry->evInfo.queue != 0) { + if (xQueueSend(objEntry->evInfo.queue, &objEntry->evInfo.ev, 0) != pdTRUE ) { // do not block if queue is full + if (objEntry->evInfo.ev.obj != NULL) { + mStats.lastErrorID = UAVObjGetID(objEntry->evInfo.ev.obj); + } + ++mStats.eventErrors; } } } // Update minimum delay - if (objEntry->timeToNextUpdateMs < timeToNextUpdate) - { + if (objEntry->timeToNextUpdateMs < timeToNextUpdate) { timeToNextUpdate = objEntry->timeToNextUpdateMs; } } } // Done - xSemaphoreGiveRecursive(mutex); + xSemaphoreGiveRecursive(mMutex); return timeToNextUpdate; } diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss index 0f100f1cc..873b2f7de 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss @@ -23,13 +23,27 @@ QSlider::add-page:horizontal { border-radius: 4px; } +QSlider::add-page:horizontal:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + QSlider::sub-page:horizontal { - background: rgb(249, 117, 76); + background: rgb(78, 147, 246); border: 1px solid #777; height: 1px; border-radius: 4px; } +QSlider::sub-page:horizontal:disabled { + background: #ccc; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + QSlider::handle:horizontal { background: rgb(196, 196, 196); width: 18px; @@ -56,13 +70,27 @@ QSlider::sub-page:vertical { border-radius: 4px; } +QSlider::sub-page:vertical:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + QSlider::add-page:vertical { - background: rgb(249, 117, 76); + background: rgb(78, 147, 246); border: 1px solid #777; width: 1px; border-radius: 4px; } +QSlider::add-page:vertical:disabled { + background: #ccc; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + QSlider::handle:vertical { background: rgb(196, 196, 196); width: 18px; diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss index e378375c0..e426d3f2c 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss @@ -1,18 +1 @@ /* Windows styles */ - -QGroupBox { - border: 1px solid gray; - border-radius: 3px; - margin-top: 1ex; - padding: 1ex 0px 0px 0px; - font-size: 11px; - font-weight: bold; -} - -QGroupBox::title { - subcontrol-origin: margin; - subcontrol-position: top left; - left: 7px; - top: -1ex; - padding: 0px 3px; -} diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp index 639052e57..a9610c0e5 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp @@ -91,6 +91,13 @@ void MyTabbedStackWidget::removeTab(int index) delete item; } +void MyTabbedStackWidget::setWidgetsEnabled(bool enabled) +{ + for(int i = 0; i < m_stackWidget->count(); i++) { + m_stackWidget->widget(i)->setEnabled(enabled); + } +} + int MyTabbedStackWidget::currentIndex() const { return m_listWidget->currentRow(); diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h index 5faad8222..7307673b1 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h @@ -47,6 +47,8 @@ public: void removeTab(int index); void setIconSize(int size) { m_listWidget->setIconSize(QSize(size, size)); } + void setWidgetsEnabled(bool enabled); + int currentIndex() const; void insertCornerWidget(int index, QWidget *widget); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp index 6e764dc41..abab410fd 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp @@ -308,7 +308,9 @@ void ConfigCcpmWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->SwashLvlPositionSlider); parent.addWidget(m_aircraft->SwashLvlPositionSpinBox); parent.addWidget(m_aircraft->ThrottleCurve->getCurveWidget()); - parent.addWidget(m_aircraft->PitchCurve->getCurveWidget()); + parent.addWidget(m_aircraft->PitchCurve); + parent.addWidget(m_aircraft->ThrottleCurve->getCurveWidget()); + parent.addWidget(m_aircraft->PitchCurve); parent.addWidget(m_aircraft->ccpmAdvancedSettingsTable); } diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configcustomwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configcustomwidget.cpp index 684435b0a..192a20ed1 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configcustomwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configcustomwidget.cpp @@ -68,7 +68,6 @@ ConfigCustomWidget::ConfigCustomWidget(QWidget *parent) : for (int i = 1; i < (int) VehicleConfig::CHANNEL_NUMELEM; i++) { m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd); } - } ConfigCustomWidget::~ConfigCustomWidget() @@ -84,7 +83,9 @@ void ConfigCustomWidget::setupUI(QString frameType) void ConfigCustomWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->customMixerTable); parent.addWidget(m_aircraft->customThrottle1Curve->getCurveWidget()); + parent.addWidget(m_aircraft->customThrottle1Curve); parent.addWidget(m_aircraft->customThrottle2Curve->getCurveWidget()); + parent.addWidget(m_aircraft->customThrottle2Curve); } void ConfigCustomWidget::resetActuators(GUIConfigDataUnion *configData) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index a2b7bf79f..da2575637 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -87,11 +87,9 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : m_aircraft->fixedWingType->addItems(fixedWingTypes); // Set default model to "Elevator aileron rudder" - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); - - //setupUI(m_aircraft->fixedWingType->currentText()); - connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); + m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); + setupUI(m_aircraft->fixedWingType->currentText()); } ConfigFixedWingWidget::~ConfigFixedWingWidget() @@ -109,64 +107,61 @@ void ConfigFixedWingWidget::setupUI(QString frameType) if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") { setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder")); m_aircraft->fwRudder1ChannelBox->setEnabled(true); - m_aircraft->fwRudder1Label->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); - m_aircraft->fwRudder2Label->setEnabled(true); m_aircraft->fwElevator1ChannelBox->setEnabled(true); - m_aircraft->fwElevator1Label->setEnabled(true); m_aircraft->fwElevator2ChannelBox->setEnabled(true); - m_aircraft->fwElevator2Label->setEnabled(true); m_aircraft->fwAileron1ChannelBox->setEnabled(true); - m_aircraft->fwAileron1Label->setEnabled(true); m_aircraft->fwAileron2ChannelBox->setEnabled(true); - m_aircraft->fwAileron2Label->setEnabled(true); m_aircraft->fwAileron1Label->setText("Aileron 1"); m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); - m_aircraft->elevonMixBox->setHidden(true); - + + m_aircraft->elevonSlider1->setEnabled(false); + m_aircraft->elevonSlider2->setEnabled(false); + } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); m_aircraft->fwAileron1Label->setText("Elevon 1"); m_aircraft->fwAileron2Label->setText("Elevon 2"); m_aircraft->fwElevator1ChannelBox->setEnabled(false); - m_aircraft->fwElevator1Label->setEnabled(false); m_aircraft->fwElevator2ChannelBox->setEnabled(false); - m_aircraft->fwElevator2Label->setEnabled(false); m_aircraft->fwRudder1ChannelBox->setEnabled(true); - m_aircraft->fwRudder1Label->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); - m_aircraft->fwRudder2Label->setEnabled(true); + m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); - m_aircraft->elevonMixBox->setHidden(false); m_aircraft->elevonLabel1->setText("Roll"); m_aircraft->elevonLabel2->setText("Pitch"); - + + m_aircraft->elevonSlider1->setEnabled(true); + m_aircraft->elevonSlider2->setEnabled(true); + } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); m_aircraft->fwRudder1ChannelBox->setEnabled(false); - m_aircraft->fwRudder1Label->setEnabled(false); m_aircraft->fwRudder2ChannelBox->setEnabled(false); - m_aircraft->fwRudder2Label->setEnabled(false); - m_aircraft->fwElevator1ChannelBox->setEnabled(true); - m_aircraft->fwElevator1Label->setEnabled(true); + m_aircraft->fwElevator1Label->setText("Vtail 1"); + m_aircraft->fwElevator1ChannelBox->setEnabled(true); + m_aircraft->fwElevator2Label->setText("Vtail 2"); - m_aircraft->elevonMixBox->setHidden(false); m_aircraft->fwElevator2ChannelBox->setEnabled(true); - m_aircraft->fwElevator2Label->setEnabled(true); + m_aircraft->fwAileron1Label->setText("Aileron 1"); m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->elevonLabel1->setText("Rudder"); m_aircraft->elevonLabel2->setText("Pitch"); - } + + m_aircraft->elevonSlider1->setEnabled(true); + m_aircraft->elevonSlider2->setEnabled(true); + } } void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->fixedWingThrottle->getCurveWidget()); + parent.addWidget(m_aircraft->fixedWingThrottle); parent.addWidget(m_aircraft->fixedWingType); parent.addWidget(m_aircraft->fwEngineChannelBox); @@ -508,6 +503,14 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) return true; } +void ConfigFixedWingWidget::enableControls(bool enable) +{ + ConfigTaskWidget::enableControls(enable); + if(enable) { + setupUI(m_aircraft->fixedWingType->currentText()); + } +} + /** This function displays text and color formatting in order to help the user understand what channels have not yet been configured. */ diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index c738920d9..3a0d45883 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -64,6 +64,9 @@ private: bool setupFrameElevon(QString airframeType); bool setupFrameVtail(QString airframeType); +protected: + void enableControls(bool enable); + private slots: virtual void setupUI(QString airframeType); virtual bool throwConfigError(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp index 771a2afb5..d37b58695 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp @@ -79,11 +79,9 @@ ConfigGroundVehicleWidget::ConfigGroundVehicleWidget(QWidget *parent) : m_aircraft->groundVehicleType->addItems(groundVehicleTypes); // Set default model to "Turnable (car)" - m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Turnable (car)")); - - //setupUI(m_aircraft->groundVehicleType->currentText()); - connect(m_aircraft->groundVehicleType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); + m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Turnable (car)")); + setupUI(m_aircraft->groundVehicleType->currentText()); } ConfigGroundVehicleWidget::~ConfigGroundVehicleWidget() @@ -96,42 +94,32 @@ ConfigGroundVehicleWidget::~ConfigGroundVehicleWidget() */ void ConfigGroundVehicleWidget::setupUI(QString frameType) { - m_aircraft->differentialSteeringMixBox->setHidden(true); - //STILL NEEDS WORK - // Setup the UI m_aircraft->gvEngineChannelBox->setEnabled(false); - m_aircraft->gvEngineLabel->setEnabled(false); - m_aircraft->gvAileron1ChannelBox->setEnabled(false); - m_aircraft->gvAileron1Label->setEnabled(false); - m_aircraft->gvAileron2ChannelBox->setEnabled(false); - m_aircraft->gvAileron2Label->setEnabled(false); + + m_aircraft->differentialSteeringSlider1->setEnabled(false); + m_aircraft->differentialSteeringSlider2->setEnabled(false); if (frameType == "GroundVehicleDifferential" || frameType == "Differential (tank)") { // Tank setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Differential (tank)")); m_aircraft->gvMotor1ChannelBox->setEnabled(true); - m_aircraft->gvMotor1Label->setEnabled(true); - m_aircraft->gvMotor2ChannelBox->setEnabled(true); - m_aircraft->gvMotor2Label->setEnabled(true); m_aircraft->gvMotor1Label->setText("Left motor"); m_aircraft->gvMotor2Label->setText("Right motor"); m_aircraft->gvSteering1ChannelBox->setEnabled(false); - m_aircraft->gvSteering1Label->setEnabled(false); - m_aircraft->gvSteering2ChannelBox->setEnabled(false); - m_aircraft->gvSteering2Label->setEnabled(false); m_aircraft->gvSteering2Label->setText("Rear steering"); - m_aircraft->differentialSteeringMixBox->setHidden(false); + m_aircraft->differentialSteeringSlider1->setEnabled(true); + m_aircraft->differentialSteeringSlider2->setEnabled(true); m_aircraft->gvThrottleCurve1GroupBox->setTitle("Left throttle curve"); m_aircraft->gvThrottleCurve2GroupBox->setTitle("Right throttle curve"); @@ -140,24 +128,16 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType) // Motorcycle setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Motorcycle")); m_aircraft->gvMotor1ChannelBox->setEnabled(false); - m_aircraft->gvMotor1Label->setEnabled(false); - m_aircraft->gvMotor2ChannelBox->setEnabled(true); - m_aircraft->gvMotor2Label->setEnabled(true); m_aircraft->gvMotor1Label->setText("Front motor"); m_aircraft->gvMotor2Label->setText("Rear motor"); m_aircraft->gvSteering1ChannelBox->setEnabled(true); - m_aircraft->gvSteering1Label->setEnabled(true); - m_aircraft->gvSteering2ChannelBox->setEnabled(true); - m_aircraft->gvSteering2Label->setEnabled(true); m_aircraft->gvSteering2Label->setText("Balancing"); - m_aircraft->differentialSteeringMixBox->setHidden(true); - m_aircraft->gvThrottleCurve1GroupBox->setTitle("Front throttle curve"); m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve"); } else { @@ -165,31 +145,40 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType) setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Turnable (car)")); m_aircraft->gvMotor1ChannelBox->setEnabled(true); - m_aircraft->gvMotor1Label->setEnabled(true); - m_aircraft->gvMotor2ChannelBox->setEnabled(true); - m_aircraft->gvMotor2Label->setEnabled(true); m_aircraft->gvMotor1Label->setText("Front motor"); m_aircraft->gvMotor2Label->setText("Rear motor"); m_aircraft->gvSteering1ChannelBox->setEnabled(true); - m_aircraft->gvSteering1Label->setEnabled(true); - m_aircraft->gvSteering2ChannelBox->setEnabled(true); - m_aircraft->gvSteering2Label->setEnabled(true); - - m_aircraft->differentialSteeringMixBox->setHidden(true); m_aircraft->gvThrottleCurve1GroupBox->setTitle("Front throttle curve"); m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve"); } } +void ConfigGroundVehicleWidget::enableControls(bool enable) +{ + ConfigTaskWidget::enableControls(enable); + if(enable) { + setupUI(m_aircraft->groundVehicleType->currentText()); + } +} + void ConfigGroundVehicleWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->groundVehicleThrottle1->getCurveWidget()); + parent.addWidget(m_aircraft->groundVehicleThrottle1); parent.addWidget(m_aircraft->groundVehicleThrottle2->getCurveWidget()); + parent.addWidget(m_aircraft->groundVehicleThrottle2); parent.addWidget(m_aircraft->groundVehicleType); + parent.addWidget(m_aircraft->gvEngineChannelBox); + parent.addWidget(m_aircraft->gvAileron1ChannelBox); + parent.addWidget(m_aircraft->gvAileron2ChannelBox); + parent.addWidget(m_aircraft->gvMotor1ChannelBox); + parent.addWidget(m_aircraft->gvMotor2ChannelBox); + parent.addWidget(m_aircraft->gvSteering1ChannelBox); + parent.addWidget(m_aircraft->gvSteering2ChannelBox); } void ConfigGroundVehicleWidget::resetActuators(GUIConfigDataUnion *configData) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h index 475f54a19..0a7abd858 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h @@ -54,6 +54,9 @@ public: virtual void refreshWidgetsValues(QString frameType); virtual QString updateConfigObjectsFromWidgets(); +protected: + void enableControls(bool enable); + private: Ui_GroundConfigWidget *m_aircraft; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 7fc9d46a5..a51cf370b 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -122,6 +122,7 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) : // Connect the multirotor motor reverse checkbox connect(m_aircraft->MultirotorRevMixerCheckBox, SIGNAL(clicked(bool)), this, SLOT(reverseMultirotorMotor())); + updateEnableControls(); } ConfigMultiRotorWidget::~ConfigMultiRotorWidget() @@ -134,6 +135,81 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) Q_ASSERT(m_aircraft); Q_ASSERT(quad); + if (frameType == "Tri" || frameType == "Tricopter Y") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y")); + + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(100); + setYawMixLevel(50); + } else if (frameType == "QuadX" || frameType == "Quad X") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); + + // init mixer levels + m_aircraft->mrRollMixLevel->setValue(50); + m_aircraft->mrPitchMixLevel->setValue(50); + setYawMixLevel(50); + } else if (frameType == "QuadP" || frameType == "Quad +") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); + + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(100); + setYawMixLevel(50); + } else if (frameType == "Hexa" || frameType == "Hexacopter") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter")); + + m_aircraft->mrRollMixLevel->setValue(50); + m_aircraft->mrPitchMixLevel->setValue(33); + setYawMixLevel(33); + } else if (frameType == "HexaX" || frameType == "Hexacopter X") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, + m_aircraft->multirotorFrameType->findText("Hexacopter X")); + + m_aircraft->mrRollMixLevel->setValue(33); + m_aircraft->mrPitchMixLevel->setValue(50); + setYawMixLevel(33); + } else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, + m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); + + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(50); + setYawMixLevel(66); + } else if (frameType == "Octo" || frameType == "Octocopter") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter")); + + m_aircraft->mrRollMixLevel->setValue(33); + m_aircraft->mrPitchMixLevel->setValue(33); + setYawMixLevel(25); + } else if (frameType == "OctoV" || frameType == "Octocopter V") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, + m_aircraft->multirotorFrameType->findText("Octocopter V")); + + m_aircraft->mrRollMixLevel->setValue(25); + m_aircraft->mrPitchMixLevel->setValue(25); + setYawMixLevel(25); + } else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +")); + + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(100); + setYawMixLevel(50); + } else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X")); + + m_aircraft->mrRollMixLevel->setValue(50); + m_aircraft->mrPitchMixLevel->setValue(50); + setYawMixLevel(50); + } + + // Enable/Disable controls + setupEnabledControls(frameType); + + // Draw the appropriate airframe + updateAirframe(frameType); +} + +void ConfigMultiRotorWidget::setupEnabledControls(QString frameType) +{ // disable triyaw channel m_aircraft->triYawChannelBox->setEnabled(false); @@ -148,109 +224,32 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) } if (frameType == "Tri" || frameType == "Tricopter Y") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 3, true); - - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(100); - setYawMixLevel(50); - m_aircraft->triYawChannelBox->setEnabled(true); } else if (frameType == "QuadX" || frameType == "Quad X") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 4, true); - - // init mixer levels - m_aircraft->mrRollMixLevel->setValue(50); - m_aircraft->mrPitchMixLevel->setValue(50); - setYawMixLevel(50); } else if (frameType == "QuadP" || frameType == "Quad +") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 4, true); - - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(100); - setYawMixLevel(50); } else if (frameType == "Hexa" || frameType == "Hexacopter") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 6, true); - - m_aircraft->mrRollMixLevel->setValue(50); - m_aircraft->mrPitchMixLevel->setValue(33); - setYawMixLevel(33); } else if (frameType == "HexaX" || frameType == "Hexacopter X") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, - m_aircraft->multirotorFrameType->findText("Hexacopter X")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 6, true); - - m_aircraft->mrRollMixLevel->setValue(33); - m_aircraft->mrPitchMixLevel->setValue(50); - setYawMixLevel(33); } else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, - m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 6, true); - - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(50); - setYawMixLevel(66); } else if (frameType == "Octo" || frameType == "Octocopter") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter")); - - // Enable all necessary motor channel boxes enableComboBoxes(this, CHANNELBOXNAME, 8, true); - - m_aircraft->mrRollMixLevel->setValue(33); - m_aircraft->mrPitchMixLevel->setValue(33); - setYawMixLevel(25); } else if (frameType == "OctoV" || frameType == "Octocopter V") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, - m_aircraft->multirotorFrameType->findText("Octocopter V")); - - // Enable all necessary motor channel boxes enableComboBoxes(this, CHANNELBOXNAME, 8, true); - - m_aircraft->mrRollMixLevel->setValue(25); - m_aircraft->mrPitchMixLevel->setValue(25); - setYawMixLevel(25); } else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +")); - - // Enable all necessary motor channel boxes enableComboBoxes(this, CHANNELBOXNAME, 8, true); - - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(100); - setYawMixLevel(50); } else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X")); - - // Enable all necessary motor channel boxes enableComboBoxes(this, CHANNELBOXNAME, 8, true); - - m_aircraft->mrRollMixLevel->setValue(50); - m_aircraft->mrPitchMixLevel->setValue(50); - setYawMixLevel(50); } - - // Draw the appropriate airframe - updateAirframe(frameType); } void ConfigMultiRotorWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->multiThrottleCurve->getCurveWidget()); + parent.addWidget(m_aircraft->multiThrottleCurve); parent.addWidget(m_aircraft->multirotorFrameType); parent.addWidget(m_aircraft->multiMotorChannelBox1); parent.addWidget(m_aircraft->multiMotorChannelBox2); @@ -264,6 +263,7 @@ void ConfigMultiRotorWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->mrRollMixLevel); parent.addWidget(m_aircraft->mrYawMixLevel); parent.addWidget(m_aircraft->triYawChannelBox); + parent.addWidget(m_aircraft->MultirotorRevMixerCheckBox); } void ConfigMultiRotorWidget::resetActuators(GUIConfigDataUnion *configData) @@ -1048,3 +1048,11 @@ void ConfigMultiRotorWidget::resizeEvent(QResizeEvent *event) Q_UNUSED(event); m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio); } + +void ConfigMultiRotorWidget::enableControls(bool enable) +{ + ConfigTaskWidget::enableControls(enable); + if(enable) { + setupEnabledControls(m_aircraft->multirotorFrameType->currentText()); + } +} diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h index 9361c0755..75c251777 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h @@ -58,6 +58,7 @@ public: protected: void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); + void enableControls(bool enable); private: Ui_MultiRotorConfigWidget *m_aircraft; @@ -77,6 +78,7 @@ private: void setYawMixLevel(int); void updateAirframe(QString multiRotorType); + void setupEnabledControls(QString multiRotorType); private slots: virtual void setupUI(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 621c5b032..4b8e445e5 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -43,24 +43,24 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) { - m_camerastabilization = new Ui_CameraStabilizationWidget(); - m_camerastabilization->setupUi(this); + ui = new Ui_CameraStabilizationWidget(); + ui->setupUi(this); - addApplySaveButtons(m_camerastabilization->camerastabilizationSaveRAM,m_camerastabilization->camerastabilizationSaveSD); + addApplySaveButtons(ui->camerastabilizationSaveRAM,ui->camerastabilizationSaveSD); ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); Core::Internal::GeneralSettings * settings=pm->getObject(); if(!settings->useExpertMode()) - m_camerastabilization->camerastabilizationSaveRAM->setVisible(false); + ui->camerastabilizationSaveRAM->setVisible(false); // These widgets don't have direct relation to UAVObjects // and need special processing QComboBox *outputs[] = { - m_camerastabilization->rollChannel, - m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel, + ui->rollChannel, + ui->pitchChannel, + ui->yawChannel, }; const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); @@ -78,10 +78,10 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent autoLoadWidgets(); // Add some widgets to track their UI dirty state and handle smartsave - addWidget(m_camerastabilization->enableCameraStabilization); - addWidget(m_camerastabilization->rollChannel); - addWidget(m_camerastabilization->pitchChannel); - addWidget(m_camerastabilization->yawChannel); + addWidget(ui->enableCameraStabilization); + addWidget(ui->rollChannel); + addWidget(ui->pitchChannel); + addWidget(ui->yawChannel); // Add some UAVObjects to monitor their changes in addition to autoloaded ones. // Note also that we want to reload some UAVObjects by "Reload" button and have @@ -97,6 +97,7 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent connect(this, SIGNAL(defaultRequested(int)), this, SLOT(defaultRequestedSlot(int))); disableMouseWheelEvents(); + updateEnableControls(); } ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget() @@ -120,7 +121,7 @@ void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj) HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); HwSettings::DataFields hwSettingsData = hwSettings->getData(); - m_camerastabilization->enableCameraStabilization->setChecked( + ui->enableCameraStabilization->setChecked( hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED); // Load mixer outputs which are mapped to camera controls @@ -144,9 +145,9 @@ void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj) const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]); QComboBox *outputs[] = { - m_camerastabilization->rollChannel, - m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel + ui->rollChannel, + ui->pitchChannel, + ui->yawChannel }; const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); @@ -175,7 +176,7 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() // Save state of the module enable checkbox first. // Do not use setData() member on whole object, if possible, since it triggers // unnessesary UAVObect update. - quint8 enableModule = m_camerastabilization->enableCameraStabilization->isChecked() ? + quint8 enableModule = ui->enableCameraStabilization->isChecked() ? HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED; HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_CAMERASTAB, enableModule); @@ -202,13 +203,13 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]); QComboBox *outputs[] = { - m_camerastabilization->rollChannel, - m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel + ui->rollChannel, + ui->pitchChannel, + ui->yawChannel }; const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); - m_camerastabilization->message->setText(""); + ui->message->setText(""); bool widgetUpdated; do { widgetUpdated = false; @@ -223,7 +224,7 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() // If the mixer channel already mapped to something, it should not be // used for camera output, we reset it to none outputs[i]->setCurrentIndex(0); - m_camerastabilization->message->setText("One of the channels is already assigned, reverted to none"); + ui->message->setText("One of the channels is already assigned, reverted to none"); // Loop again or we may have inconsistent widget and UAVObject widgetUpdated = true; @@ -270,9 +271,9 @@ void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group) // For outputs we set them all to none, so don't use any UAVObject to get defaults QComboBox *outputs[] = { - m_camerastabilization->rollChannel, - m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel, + ui->rollChannel, + ui->pitchChannel, + ui->yawChannel, }; const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); @@ -280,8 +281,3 @@ void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group) outputs[i]->setCurrentIndex(0); } } - -/** - @} - @} - */ diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h index 871193e82..2715daa77 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h @@ -43,7 +43,7 @@ public: ~ConfigCameraStabilizationWidget(); private: - Ui_CameraStabilizationWidget *m_camerastabilization; + Ui_CameraStabilizationWidget *ui; void refreshWidgetsValues(UAVObject *obj); void updateObjectsFromWidgets(); diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index febfcf4e6..cd840e93e 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -216,15 +216,9 @@ void ConfigCCAttitudeWidget::setAccelFiltering(bool active) void ConfigCCAttitudeWidget::enableControls(bool enable) { - if(ui->zeroBias) { - ui->zeroBias->setEnabled(enable); - } - if(ui->zeroGyroBiasOnArming) { - ui->zeroGyroBiasOnArming->setEnabled(enable); - } - if(ui->accelTauSpinbox) { - ui->accelTauSpinbox->setEnabled(enable); - } + ui->zeroBias->setEnabled(enable); + ui->zeroGyroBiasOnArming->setEnabled(enable); + ui->accelTauSpinbox->setEnabled(enable); ConfigTaskWidget::enableControls(enable); } diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index 3c6fa9569..5f2f268ba 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -49,8 +49,6 @@ #include #include - - ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) { setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); @@ -69,49 +67,49 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) QIcon *icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new DefaultHwSettingsWidget(this); + qwd = new DefaultHwSettingsWidget(this); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); icon = new QIcon(); icon->addFile(":/configgadget/images/vehicle_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/vehicle_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigVehicleTypeWidget(this); + qwd = new ConfigVehicleTypeWidget(this); ftw->insertTab(ConfigGadgetWidget::aircraft, qwd, *icon, QString("Vehicle")); icon = new QIcon(); icon->addFile(":/configgadget/images/input_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/input_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigInputWidget(this); + qwd = new ConfigInputWidget(this); ftw->insertTab(ConfigGadgetWidget::input, qwd, *icon, QString("Input")); icon = new QIcon(); icon->addFile(":/configgadget/images/output_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/output_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigOutputWidget(this); + qwd = new ConfigOutputWidget(this); ftw->insertTab(ConfigGadgetWidget::output, qwd, *icon, QString("Output")); icon = new QIcon(); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new DefaultAttitudeWidget(this); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS")); + qwd = new DefaultAttitudeWidget(this); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); icon = new QIcon(); icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/stabilization_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigStabilizationWidget(this); + qwd = new ConfigStabilizationWidget(this); ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, *icon, QString("Stabilization")); icon = new QIcon(); icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigCameraStabilizationWidget(this); - ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Camera Stab")); + qwd = new ConfigCameraStabilizationWidget(this); + ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Gimbal")); icon = new QIcon(); icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/txpid_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigTxPIDWidget(this); + qwd = new ConfigTxPIDWidget(this); ftw->insertTab(ConfigGadgetWidget::txpid, qwd, *icon, QString("TxPID")); ftw->setCurrentIndex(ConfigGadgetWidget::hardware); @@ -119,29 +117,29 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) // Listen to autopilot connection events ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - TelemetryManager* telMngr = pm->getObject(); + TelemetryManager *telMngr = pm->getObject(); connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect())); connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); // And check whether by any chance we are not already connected if (telMngr->isConnected()) { - onAutopilotConnect(); + onAutopilotConnect(); } help = 0; - connect(ftw,SIGNAL(currentAboutToShow(int,bool*)), this, SLOT(tabAboutToChange(int,bool*))); + connect(ftw, SIGNAL(currentAboutToShow(int, bool *)), this, SLOT(tabAboutToChange(int, bool *))); // Connect to the PipXStatus object updates UAVObjectManager *objManager = pm->getObject(); - oplinkStatusObj = dynamic_cast(objManager->getObject("OPLinkStatus")); - if (oplinkStatusObj != NULL ) { - connect(oplinkStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateOPLinkStatus(UAVObject*))); + oplinkStatusObj = dynamic_cast(objManager->getObject("OPLinkStatus")); + if (oplinkStatusObj != NULL) { + connect(oplinkStatusObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateOPLinkStatus(UAVObject *))); } else { - qDebug() << "Error: Object is unknown (OPLinkStatus)."; + qDebug() << "Error: Object is unknown (OPLinkStatus)."; } // Create the timer that is used to timeout the connection to the OPLink. - oplinkTimeout = new QTimer(this); + oplinkTimeout = new QTimer(this); connect(oplinkTimeout, SIGNAL(timeout()), this, SLOT(onOPLinkDisconnect())); oplinkConnected = false; } @@ -154,7 +152,7 @@ ConfigGadgetWidget::~ConfigGadgetWidget() void ConfigGadgetWidget::startInputWizard() { ftw->setCurrentIndex(ConfigGadgetWidget::input); - ConfigInputWidget* inputWidget = dynamic_cast(ftw->getWidget(ConfigGadgetWidget::input)); + ConfigInputWidget *inputWidget = dynamic_cast(ftw->getWidget(ConfigGadgetWidget::input)); Q_ASSERT(inputWidget); inputWidget->startInputWizard(); } @@ -164,20 +162,22 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event) QWidget::resizeEvent(event); } -void ConfigGadgetWidget::onAutopilotDisconnect() { +void ConfigGadgetWidget::onAutopilotDisconnect() +{ int selectedIndex = ftw->currentIndex(); QIcon *icon = new QIcon(); + icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new DefaultAttitudeWidget(this); ftw->removeTab(ConfigGadgetWidget::sensors); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new DefaultHwSettingsWidget(this); + qwd = new DefaultHwSettingsWidget(this); ftw->removeTab(ConfigGadgetWidget::hardware); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); @@ -186,74 +186,72 @@ void ConfigGadgetWidget::onAutopilotDisconnect() { emit autopilotDisconnected(); } -void ConfigGadgetWidget::onAutopilotConnect() { - - qDebug()<<"ConfigGadgetWidget onAutopilotConnect"; +void ConfigGadgetWidget::onAutopilotConnect() +{ + qDebug() << "ConfigGadgetWidget onAutopilotConnect"; // First of all, check what Board type we are talking to, and // if necessary, remove/add tabs in the config gadget: ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectUtilManager* utilMngr = pm->getObject(); + UAVObjectUtilManager *utilMngr = pm->getObject(); if (utilMngr) { int selectedIndex = ftw->currentIndex(); int board = utilMngr->getBoardModel(); if ((board & 0xff00) == 1024) { // CopterControl family - QIcon *icon = new QIcon(); + QIcon *icon = new QIcon(); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new ConfigCCAttitudeWidget(this); ftw->removeTab(ConfigGadgetWidget::sensors); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("CopterControl")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigCCHWWidget(this); + qwd = new ConfigCCHWWidget(this); ftw->removeTab(ConfigGadgetWidget::hardware); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); - } else if ((board & 0xff00) == 0x0900) { // Revolution family - QIcon *icon = new QIcon(); + QIcon *icon = new QIcon(); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new ConfigRevoWidget(this); ftw->removeTab(ConfigGadgetWidget::sensors); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Revolution")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigRevoHWWidget(this); + qwd = new ConfigRevoHWWidget(this); ftw->removeTab(ConfigGadgetWidget::hardware); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); - } else { - //Unknown board + // Unknown board qDebug() << "Unknown board " << board; } ftw->setCurrentIndex(selectedIndex); } + emit autopilotConnected(); } -void ConfigGadgetWidget::tabAboutToChange(int i, bool * proceed) +void ConfigGadgetWidget::tabAboutToChange(int i, bool *proceed) { Q_UNUSED(i); *proceed = true; - ConfigTaskWidget * wid = qobject_cast(ftw->currentWidget()); - if(!wid) { + ConfigTaskWidget *wid = qobject_cast(ftw->currentWidget()); + if (!wid) { return; } - if(wid->isDirty()) - { - int ans=QMessageBox::warning(this,tr("Unsaved changes"),tr("The tab you are leaving has unsaved changes," - "if you proceed they will be lost." - "Do you still want to proceed?"),QMessageBox::Yes,QMessageBox::No); - if(ans==QMessageBox::No) { - *proceed=false; + if (wid->isDirty()) { + int ans = QMessageBox::warning(this, tr("Unsaved changes"), tr("The tab you are leaving has unsaved changes," + "if you proceed they will be lost." + "Do you still want to proceed?"), QMessageBox::Yes, QMessageBox::No); + if (ans == QMessageBox::No) { + *proceed = false; } else { wid->setDirty(false); } @@ -261,14 +259,13 @@ void ConfigGadgetWidget::tabAboutToChange(int i, bool * proceed) } /*! - \brief Called by updates to @OPLinkStatus - */ + \brief Called by updates to @OPLinkStatus + */ void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *) { // Restart the disconnection timer. oplinkTimeout->start(5000); - if (!oplinkConnected) - { + if (!oplinkConnected) { qDebug() << "ConfigGadgetWidget onOPLinkConnect"; QIcon *icon = new QIcon(); @@ -281,9 +278,10 @@ void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *) } } -void ConfigGadgetWidget::onOPLinkDisconnect() { - qDebug()<<"ConfigGadgetWidget onOPLinkDisconnect"; - oplinkTimeout->stop(); - ftw->removeTab(ConfigGadgetWidget::oplink); - oplinkConnected = false; +void ConfigGadgetWidget::onOPLinkDisconnect() +{ + qDebug() << "ConfigGadgetWidget onOPLinkDisconnect"; + oplinkTimeout->stop(); + ftw->removeTab(ConfigGadgetWidget::oplink); + oplinkConnected = false; } diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 67083b941..505c3a125 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -63,17 +63,17 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager()); flightStatusObj = FlightStatus::GetInstance(getObjectManager()); receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager()); - m_config = new Ui_InputWidget(); - m_config->setupUi(this); + ui = new Ui_InputWidget(); + ui->setupUi(this); - addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); + addApplySaveButtons(ui->saveRCInputToRAM,ui->saveRCInputToSD); ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); Core::Internal::GeneralSettings * settings=pm->getObject(); if(!settings->useExpertMode()) - m_config->saveRCInputToRAM->setVisible(false); + ui->saveRCInputToRAM->setVisible(false); - addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); + addApplySaveButtons(ui->saveRCInputToRAM,ui->saveRCInputToSD); //Generate the rows of buttons in the input channel form GUI unsigned int index=0; @@ -82,13 +82,16 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : { Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM); inputChannelForm * inpForm=new inputChannelForm(this,index==0); - m_config->channelSettings->layout()->addWidget(inpForm); //Add the row to the UI + ui->channelSettings->layout()->addWidget(inpForm); //Add the row to the UI inpForm->setName(name); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inpForm->ui->channelGroup,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inpForm->ui->channelNumber,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inpForm->ui->channelMin,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inpForm->ui->channelNeutral,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inpForm->ui->channelMax,index); + addWidget(inpForm->ui->channelNumberDropdown); + addWidget(inpForm->ui->channelRev); + addWidget(inpForm->ui->channelResponseTime); // Input filter response time fields supported for some channels only switch (index) { @@ -114,51 +117,53 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ++index; } - addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", m_config->deadband, 0, 0.01f); + addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", ui->deadband, 0, 0.01f); - connect(m_config->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard())); - connect(m_config->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int))); - connect(m_config->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool))); + connect(ui->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard())); + connect(ui->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int))); + connect(ui->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool))); - connect(m_config->wzNext,SIGNAL(clicked()),this,SLOT(wzNext())); - connect(m_config->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel())); - connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack())); + connect(ui->wzNext,SIGNAL(clicked()),this,SLOT(wzNext())); + connect(ui->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel())); + connect(ui->wzBack,SIGNAL(clicked()),this,SLOT(wzBack())); - m_config->stackedWidget->setCurrentIndex(0); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos1, 0, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos2, 1, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos3, 2, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos4, 3, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos5, 4, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos6, 5, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", m_config->fmsPosNum); + ui->stackedWidget->setCurrentIndex(0); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos1, 0, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos2, 1, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos3, 2, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos4, 3, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos5, 4, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos6, 5, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", ui->fmsPosNum); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Roll, "Roll", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Roll, "Roll", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Roll, "Roll", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Pitch, "Pitch", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Pitch, "Pitch", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Pitch, "Pitch", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Yaw, "Yaw", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Yaw, "Yaw", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Yaw, "Yaw", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Roll, "Roll", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Roll, "Roll", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Roll, "Roll", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Pitch, "Pitch", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Pitch, "Pitch", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Pitch, "Pitch", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Yaw, "Yaw", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl); - addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000); + addUAVObjectToWidgetRelation("ManualControlSettings","Arming",ui->armControl); + addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",ui->armTimeout,0,1000); connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider())); connect( ManualControlSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(updatePositionSlider())); - enableControls(false); + + addWidget(ui->configurationWizard); + addWidget(ui->runCalibration); populateWidgets(); refreshWidgetsValues(); // Connect the help button - connect(m_config->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + connect(ui->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - m_config->graphicsView->setScene(new QGraphicsScene(this)); - m_config->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate); + ui->graphicsView->setScene(new QGraphicsScene(this)); + ui->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate); m_renderer = new QSvgRenderer(); - QGraphicsScene *l_scene = m_config->graphicsView->scene(); - m_config->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); + QGraphicsScene *l_scene = ui->graphicsView->scene(); + ui->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); if (QFile::exists(":/configgadget/images/TX2.svg") && m_renderer->load(QString(":/configgadget/images/TX2.svg")) && m_renderer->isValid()) { l_scene->clear(); // Deletes all items contained in the scene as well. @@ -271,7 +276,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : m_txAccess2Orig.translate(orig.x(),orig.y()); m_txAccess2->setTransform(m_txAccess2Orig,true); } - m_config->graphicsView->fitInView(m_txMainBody, Qt::KeepAspectRatio ); + ui->graphicsView->fitInView(m_txMainBody, Qt::KeepAspectRatio ); animate=new QTimer(this); connect(animate,SIGNAL(timeout()),this,SLOT(moveTxControls())); @@ -293,7 +298,10 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ManualControlSettings::CHANNELGROUPS_ACCESSORY0 << ManualControlSettings::CHANNELGROUPS_ACCESSORY1 << ManualControlSettings::CHANNELGROUPS_ACCESSORY2; + + updateEnableControls(); } + void ConfigInputWidget::resetTxControls() { @@ -312,10 +320,19 @@ ConfigInputWidget::~ConfigInputWidget() } +void ConfigInputWidget::enableControls(bool enable) +{ + ConfigTaskWidget::enableControls(enable); + + if(enable) { + updatePositionSlider(); + } +} + void ConfigInputWidget::resizeEvent(QResizeEvent *event) { QWidget::resizeEvent(event); - m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); + ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); } void ConfigInputWidget::openHelp() @@ -335,8 +352,8 @@ void ConfigInputWidget::goToWizard() msgBox.exec(); // Set correct tab visible before starting wizard. - if(m_config->tabWidget->currentIndex() != 0) { - m_config->tabWidget->setCurrentIndex(0); + if(ui->tabWidget->currentIndex() != 0) { + ui->tabWidget->setCurrentIndex(0); } // Stash current manual settings data in case the wizard is @@ -351,27 +368,27 @@ void ConfigInputWidget::goToWizard() // start the wizard wizardSetUpStep(wizardWelcome); - m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio); + ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio); } void ConfigInputWidget::disableWizardButton(int value) { if(value!=0) - m_config->groupBox_3->setVisible(false); + ui->groupBox_3->setVisible(false); else - m_config->groupBox_3->setVisible(true); + ui->groupBox_3->setVisible(true); } void ConfigInputWidget::wzCancel() { dimOtherControls(false); manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata()); - m_config->stackedWidget->setCurrentIndex(0); + ui->stackedWidget->setCurrentIndex(0); if(wizardStep != wizardNone) wizardTearDownStep(wizardStep); wizardStep=wizardNone; - m_config->stackedWidget->setCurrentIndex(0); + ui->stackedWidget->setCurrentIndex(0); // Load settings back from beginning of wizard manualSettingsObj->setData(previousManualSettingsData); @@ -433,8 +450,8 @@ void ConfigInputWidget::wzNext() } manualSettingsObj->setData(manualSettingsData); // move to Arming Settings tab - m_config->stackedWidget->setCurrentIndex(0); - m_config->tabWidget->setCurrentIndex(2); + ui->stackedWidget->setCurrentIndex(0); + ui->tabWidget->setCurrentIndex(2); break; default: Q_ASSERT(0); @@ -481,7 +498,7 @@ void ConfigInputWidget::wzBack() void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) { - m_config->wzText2->clear(); + ui->wzText2->clear(); switch(step) { case wizardWelcome: @@ -491,22 +508,22 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) delete wd; } extraWidgets.clear(); - m_config->graphicsView->setVisible(false); + ui->graphicsView->setVisible(false); setTxMovement(nothing); - m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\n\n" + ui->wzText->setText(tr("Welcome to the inputs configuration wizard.\n\n" "Please follow the instructions on the screen and only move your controls when asked to.\n" "Make sure you already configured your hardware settings on the proper tab and restarted your board.\n\n" "You can press 'back' at any time to return to the previous screen or press 'Cancel' to quit the wizard.\n")); - m_config->stackedWidget->setCurrentIndex(1); - m_config->wzBack->setEnabled(false); + ui->stackedWidget->setCurrentIndex(1); + ui->wzBack->setEnabled(false); break; case wizardChooseType: { - m_config->graphicsView->setVisible(true); - m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio); + ui->graphicsView->setVisible(true); + ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio); setTxMovement(nothing); - m_config->wzText->setText(tr("Please choose your transmitter type:")); - m_config->wzBack->setEnabled(true); + ui->wzText->setText(tr("Please choose your transmitter type:")); + ui->wzBack->setEnabled(true); QRadioButton * typeAcro=new QRadioButton(tr("Acro: normal transmitter for fixed-wing or quad"),this); QRadioButton * typeHeli=new QRadioButton(tr("Helicopter: has collective pitch and throttle input"),this); if (transmitterType == heli) { @@ -515,20 +532,20 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) else { typeAcro->setChecked(true); } - m_config->wzText2->setText(tr("If selecting the Helicopter option, please engage throttle hold now.")); + ui->wzText2->setText(tr("If selecting the Helicopter option, please engage throttle hold now.")); extraWidgets.clear(); extraWidgets.append(typeAcro); extraWidgets.append(typeHeli); - m_config->radioButtonsLayout->layout()->addWidget(typeAcro); - m_config->radioButtonsLayout->layout()->addWidget(typeHeli); + ui->radioButtonsLayout->layout()->addWidget(typeAcro); + ui->radioButtonsLayout->layout()->addWidget(typeHeli); } break; case wizardChooseMode: { - m_config->wzBack->setEnabled(true); + ui->wzBack->setEnabled(true); extraWidgets.clear(); - m_config->wzText->setText(tr("Please choose your transmitter mode:")); + ui->wzText->setText(tr("Please choose your transmitter mode:")); for (int i = 0; i <= mode4; ++i) { QString label; txMode mode = static_cast(i); @@ -548,14 +565,14 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) case mode4: label = tr("Mode 4: Throttle and Ailerons on the left, Elevator and Rudder on the right"); break; default: Q_ASSERT(0); break; } - m_config->wzText2->setText(tr("For a Quad: Elevator is Pitch, Ailerons are Roll, and Rudder is Yaw.")); + ui->wzText2->setText(tr("For a Quad: Elevator is Pitch, Ailerons are Roll, and Rudder is Yaw.")); } QRadioButton * modeButton = new QRadioButton(label, this); if (transmitterMode == mode) { modeButton->setChecked(true); } extraWidgets.append(modeButton); - m_config->radioButtonsLayout->layout()->addWidget(modeButton); + ui->radioButtonsLayout->layout()->addWidget(modeButton); } } break; @@ -565,11 +582,11 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) nextChannel(); manualSettingsData=manualSettingsObj->getData(); connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); - m_config->wzNext->setEnabled(false); + ui->wzNext->setEnabled(false); break; case wizardIdentifyCenter: setTxMovement(centerAll); - m_config->wzText->setText(QString(tr("Please center all controls and trims and press Next when ready.\n\n" + ui->wzText->setText(QString(tr("Please center all controls and trims and press Next when ready.\n\n" "If your FlightMode switch has only two positions, leave it in either position."))); break; case wizardIdentifyLimits: @@ -578,7 +595,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1); accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2); setTxMovement(nothing); - m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions.\n\nPress Next when ready."))); + ui->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions.\n\nPress Next when ready."))); fastMdata(); manualSettingsData=manualSettingsObj->getData(); for(uint i=0;isetChecked(manualSettingsData.ChannelMax[index] < manualSettingsData.ChannelMin[index]); - dynamic_cast(m_config->checkBoxesLayout->layout())->addWidget(cb, extraWidgets.size()/4, extraWidgets.size()%4); + dynamic_cast(ui->checkBoxesLayout->layout())->addWidget(cb, extraWidgets.size()/4, extraWidgets.size()%4); extraWidgets.append(cb); connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls())); } } connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); - m_config->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement. Press Next when ready."))); + ui->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement. Press Next when ready."))); fastMdata(); break; case wizardFinish: @@ -626,7 +643,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); - m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n\n" + ui->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n\n" "IMPORTANT: These new settings have not been saved to the board yet. After pressing Next you will go to the Arming Settings " "tab where you can set your desired arming sequence and save the configuration."))); fastMdata(); @@ -666,7 +683,7 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step) break; case wizardIdentifySticks: disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); - m_config->wzNext->setEnabled(true); + ui->wzNext->setEnabled(true); setTxMovement(nothing); break; case wizardIdentifyCenter: @@ -742,21 +759,21 @@ void ConfigInputWidget::restoreMdata() void ConfigInputWidget::setChannel(int newChan) { if(newChan == ManualControlSettings::CHANNELGROUPS_COLLECTIVE) - m_config->wzText->setText(QString(tr("Please enable throttle hold mode.\n\nMove the Collective Pitch stick."))); + ui->wzText->setText(QString(tr("Please enable throttle hold mode.\n\nMove the Collective Pitch stick."))); else if (newChan == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE) - m_config->wzText->setText(QString(tr("Please toggle the Flight Mode switch.\n\nFor switches you may have to repeat this rapidly."))); + ui->wzText->setText(QString(tr("Please toggle the Flight Mode switch.\n\nFor switches you may have to repeat this rapidly."))); else if((transmitterType == heli) && (newChan == ManualControlSettings::CHANNELGROUPS_THROTTLE)) - m_config->wzText->setText(QString(tr("Please disable throttle hold mode.\n\nMove the Throttle stick."))); + ui->wzText->setText(QString(tr("Please disable throttle hold mode.\n\nMove the Throttle stick."))); else - m_config->wzText->setText(QString(tr("Please move each control one at a time according to the instructions and picture below.\n\n" + ui->wzText->setText(QString(tr("Please move each control one at a time according to the instructions and picture below.\n\n" "Move the %1 stick.")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan))); if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory") || manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) { - m_config->wzNext->setEnabled(true); - m_config->wzText->setText(m_config->wzText->text() + tr(" Alternatively, click Next to skip this channel.")); + ui->wzNext->setEnabled(true); + ui->wzText->setText(ui->wzText->text() + tr(" Alternatively, click Next to skip this channel.")); } else - m_config->wzNext->setEnabled(false); + ui->wzNext->setEnabled(false); setMoveFromCommand(newChan); @@ -1249,15 +1266,6 @@ void ConfigInputWidget::dimOtherControls(bool value) m_txFlightMode->setOpacity(opac); } -void ConfigInputWidget::enableControls(bool enable) -{ - m_config->configurationWizard->setEnabled(enable); - m_config->runCalibration->setEnabled(enable); - - ConfigTaskWidget::enableControls(enable); - -} - void ConfigInputWidget::invertControls() { manualSettingsData=manualSettingsObj->getData(); @@ -1318,7 +1326,7 @@ void ConfigInputWidget::moveFMSlider() uint8_t pos = ((int16_t)(valueScaled * 256) + 256) * manualSettingsDataPriv.FlightModeNumber >> 9; if (pos >= manualSettingsDataPriv.FlightModeNumber) pos = manualSettingsDataPriv.FlightModeNumber - 1; - m_config->fmsSlider->setValue(pos); + ui->fmsSlider->setValue(pos); } void ConfigInputWidget::updatePositionSlider() @@ -1328,22 +1336,22 @@ void ConfigInputWidget::updatePositionSlider() switch(manualSettingsDataPriv.FlightModeNumber) { default: case 6: - m_config->fmsModePos6->setEnabled(true); + ui->fmsModePos6->setEnabled(true); // pass through case 5: - m_config->fmsModePos5->setEnabled(true); + ui->fmsModePos5->setEnabled(true); // pass through case 4: - m_config->fmsModePos4->setEnabled(true); + ui->fmsModePos4->setEnabled(true); // pass through case 3: - m_config->fmsModePos3->setEnabled(true); + ui->fmsModePos3->setEnabled(true); // pass through case 2: - m_config->fmsModePos2->setEnabled(true); + ui->fmsModePos2->setEnabled(true); // pass through case 1: - m_config->fmsModePos1->setEnabled(true); + ui->fmsModePos1->setEnabled(true); // pass through case 0: break; @@ -1351,22 +1359,22 @@ void ConfigInputWidget::updatePositionSlider() switch(manualSettingsDataPriv.FlightModeNumber) { case 0: - m_config->fmsModePos1->setEnabled(false); + ui->fmsModePos1->setEnabled(false); // pass through case 1: - m_config->fmsModePos2->setEnabled(false); + ui->fmsModePos2->setEnabled(false); // pass through case 2: - m_config->fmsModePos3->setEnabled(false); + ui->fmsModePos3->setEnabled(false); // pass through case 3: - m_config->fmsModePos4->setEnabled(false); + ui->fmsModePos4->setEnabled(false); // pass through case 4: - m_config->fmsModePos5->setEnabled(false); + ui->fmsModePos5->setEnabled(false); // pass through case 5: - m_config->fmsModePos6->setEnabled(false); + ui->fmsModePos6->setEnabled(false); // pass through case 6: default: @@ -1395,7 +1403,7 @@ void ConfigInputWidget::updateCalibration() void ConfigInputWidget::simpleCalibration(bool enable) { if (enable) { - m_config->configurationWizard->setEnabled(false); + ui->configurationWizard->setEnabled(false); QMessageBox msgBox; msgBox.setText(tr("Arming Settings are now set to 'Always Disarmed' for your safety.")); @@ -1421,7 +1429,7 @@ void ConfigInputWidget::simpleCalibration(bool enable) connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration())); } else { - m_config->configurationWizard->setEnabled(true); + ui->configurationWizard->setEnabled(true); manualCommandData = manualCommandObj->getData(); manualSettingsData = manualSettingsObj->getData(); diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.h b/ground/openpilotgcs/src/plugins/config/configinputwidget.h index 47705aa82..be8adedb8 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.h @@ -61,6 +61,7 @@ public: enum txMovementType{vertical,horizontal,jump,mix}; enum txType {acro, heli}; void startInputWizard() { goToWizard(); } + void enableControls(bool enable); private: bool growing; @@ -68,7 +69,7 @@ private: txMovements currentMovement; int movePos; void setTxMovement(txMovements movement); - Ui_InputWidget *m_config; + Ui_InputWidget *ui; wizardSteps wizardStep; QList > extraWidgets; txMode transmitterMode; @@ -166,7 +167,6 @@ private slots: protected: void resizeEvent(QResizeEvent *event); - virtual void enableControls(bool enable); }; #endif diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index c1e364b86..d71918aba 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -51,46 +51,51 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false) { - m_config = new Ui_OutputWidget(); - m_config->setupUi(this); + ui = new Ui_OutputWidget(); + ui->setupUi(this); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); Core::Internal::GeneralSettings *settings = pm->getObject(); if(!settings->useExpertMode()) { - m_config->saveRCOutputToRAM->setVisible(false); + ui->saveRCOutputToRAM->setVisible(false); } UAVSettingsImportExportFactory *importexportplugin = pm->getObject(); connect(importexportplugin, SIGNAL(importAboutToBegin()), this, SLOT(stopTests())); - // NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10. - // Register for ActuatorSettings changes: - for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) { - OutputChannelForm *form = new OutputChannelForm(i, this, i == 0); - connect(m_config->channelOutTest, SIGNAL(toggled(bool)), form, SLOT(enableChannelTest(bool))); - connect(form, SIGNAL(channelChanged(int,int)), this, SLOT(sendChannelTest(int,int))); - m_config->channelLayout->addWidget(form); - } - - connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool))); + connect(ui->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool))); // Configure the task widget // Connect the help button - connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + connect(ui->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); + addApplySaveButtons(ui->saveRCOutputToRAM, ui->saveRCOutputToSD); // Track the ActuatorSettings object addUAVObject("ActuatorSettings"); + // NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10. + // Register for ActuatorSettings changes: + for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) { + OutputChannelForm *form = new OutputChannelForm(i, this, i == 0); + connect(ui->channelOutTest, SIGNAL(toggled(bool)), form, SLOT(enableChannelTest(bool))); + connect(form, SIGNAL(channelChanged(int,int)), this, SLOT(sendChannelTest(int,int))); + ui->channelLayout->addWidget(form); + addWidget(form->ui.actuatorMin); + addWidget(form->ui.actuatorNeutral); + addWidget(form->ui.actuatorMax); + addWidget(form->ui.actuatorRev); + addWidget(form->ui.actuatorLink); + } + // Associate the buttons with their UAVO fields - addWidget(m_config->cb_outputRate6); - addWidget(m_config->cb_outputRate5); - addWidget(m_config->cb_outputRate4); - addWidget(m_config->cb_outputRate3); - addWidget(m_config->cb_outputRate2); - addWidget(m_config->cb_outputRate1); - addWidget(m_config->spinningArmed); + addWidget(ui->cb_outputRate6); + addWidget(ui->cb_outputRate5); + addWidget(ui->cb_outputRate4); + addWidget(ui->cb_outputRate3); + addWidget(ui->cb_outputRate2); + addWidget(ui->cb_outputRate1); + addWidget(ui->spinningArmed); disconnect(this, SLOT(refreshWidgetsValues(UAVObject*))); @@ -102,15 +107,16 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren connect(obj,SIGNAL(objectUpdated(UAVObject*)), this, SLOT(disableIfNotMe(UAVObject*))); refreshWidgetsValues(); + updateEnableControls(); } void ConfigOutputWidget::enableControls(bool enable) { ConfigTaskWidget::enableControls(enable); if(!enable) { - m_config->channelOutTest->setChecked(false); + ui->channelOutTest->setChecked(false); } - m_config->channelOutTest->setEnabled(enable); + ui->channelOutTest->setEnabled(enable); } ConfigOutputWidget::~ConfigOutputWidget() @@ -136,7 +142,7 @@ void ConfigOutputWidget::runChannelTests(bool state) // Unfortunately must cache this since callback will reoccur accInitialData = ActuatorCommand::GetInstance(getObjectManager())->getMetadata(); - m_config->channelOutTest->setChecked(false); + ui->channelOutTest->setChecked(false); return; } @@ -149,7 +155,7 @@ void ConfigOutputWidget::runChannelTests(bool state) if(retval != QMessageBox::Yes) { state = false; qDebug() << "Cancelled"; - m_config->channelOutTest->setChecked(false); + ui->channelOutTest->setChecked(false); return; } } @@ -209,7 +215,7 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str) */ void ConfigOutputWidget::sendChannelTest(int index, int value) { - if (!m_config->channelOutTest->isChecked()) { + if (!ui->channelOutTest->isChecked()) { return; } @@ -260,47 +266,47 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj) } // Get the SpinWhileArmed setting - m_config->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE); + ui->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE); // Setup output rates for all banks - if(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])) == -1) { - m_config->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])); + if(ui->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])) == -1) { + ui->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])); } - if(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])) == -1) { - m_config->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])); + if(ui->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])) == -1) { + ui->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])); } - if(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]) )== -1) { - m_config->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])); + if(ui->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]) )== -1) { + ui->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])); } - if(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])) == -1) { - m_config->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])); + if(ui->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])) == -1) { + ui->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])); } - if(m_config->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])) == -1) { - m_config->cb_outputRate5->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])); + if(ui->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])) == -1) { + ui->cb_outputRate5->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])); } - if(m_config->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])) == -1) { - m_config->cb_outputRate6->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])); + if(ui->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])) == -1) { + ui->cb_outputRate6->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])); } - m_config->cb_outputRate1->setCurrentIndex(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))); - m_config->cb_outputRate2->setCurrentIndex(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))); - m_config->cb_outputRate3->setCurrentIndex(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]))); - m_config->cb_outputRate4->setCurrentIndex(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]))); - m_config->cb_outputRate5->setCurrentIndex(m_config->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4]))); - m_config->cb_outputRate6->setCurrentIndex(m_config->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5]))); + ui->cb_outputRate1->setCurrentIndex(ui->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))); + ui->cb_outputRate2->setCurrentIndex(ui->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))); + ui->cb_outputRate3->setCurrentIndex(ui->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]))); + ui->cb_outputRate4->setCurrentIndex(ui->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]))); + ui->cb_outputRate5->setCurrentIndex(ui->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4]))); + ui->cb_outputRate6->setCurrentIndex(ui->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5]))); // Reset to all disabled - m_config->chBank1->setText("-"); - m_config->chBank2->setText("-"); - m_config->chBank3->setText("-"); - m_config->chBank4->setText("-"); - m_config->chBank5->setText("-"); - m_config->chBank6->setText("-"); - m_config->cb_outputRate1->setEnabled(false); - m_config->cb_outputRate2->setEnabled(false); - m_config->cb_outputRate3->setEnabled(false); - m_config->cb_outputRate4->setEnabled(false); - m_config->cb_outputRate5->setEnabled(false); - m_config->cb_outputRate6->setEnabled(false); + ui->chBank1->setText("-"); + ui->chBank2->setText("-"); + ui->chBank3->setText("-"); + ui->chBank4->setText("-"); + ui->chBank5->setText("-"); + ui->chBank6->setText("-"); + ui->cb_outputRate1->setEnabled(false); + ui->cb_outputRate2->setEnabled(false); + ui->cb_outputRate3->setEnabled(false); + ui->cb_outputRate4->setEnabled(false); + ui->cb_outputRate5->setEnabled(false); + ui->cb_outputRate6->setEnabled(false); // Get connected board model ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); @@ -313,29 +319,29 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj) // Setup labels and combos for banks according to board type if ((board & 0xff00) == 0x0400) { // Coptercontrol family of boards 4 timer banks - m_config->chBank1->setText("1-3"); - m_config->chBank2->setText("4"); - m_config->chBank3->setText("5,7-8"); - m_config->chBank4->setText("6,9-10"); - m_config->cb_outputRate1->setEnabled(true); - m_config->cb_outputRate2->setEnabled(true); - m_config->cb_outputRate3->setEnabled(true); - m_config->cb_outputRate4->setEnabled(true); + ui->chBank1->setText("1-3"); + ui->chBank2->setText("4"); + ui->chBank3->setText("5,7-8"); + ui->chBank4->setText("6,9-10"); + ui->cb_outputRate1->setEnabled(true); + ui->cb_outputRate2->setEnabled(true); + ui->cb_outputRate3->setEnabled(true); + ui->cb_outputRate4->setEnabled(true); } else if((board & 0xff00) == 0x0900) { // Revolution family of boards 6 timer banks - m_config->chBank1->setText("1-2"); - m_config->chBank2->setText("3"); - m_config->chBank3->setText("4"); - m_config->chBank4->setText("5-6"); - m_config->chBank5->setText("7-8"); - m_config->chBank6->setText("9-10"); - m_config->cb_outputRate1->setEnabled(true); - m_config->cb_outputRate2->setEnabled(true); - m_config->cb_outputRate3->setEnabled(true); - m_config->cb_outputRate4->setEnabled(true); - m_config->cb_outputRate5->setEnabled(true); - m_config->cb_outputRate6->setEnabled(true); + ui->chBank1->setText("1-2"); + ui->chBank2->setText("3"); + ui->chBank3->setText("4"); + ui->chBank4->setText("5-6"); + ui->chBank5->setText("7-8"); + ui->chBank6->setText("9-10"); + ui->cb_outputRate1->setEnabled(true); + ui->cb_outputRate2->setEnabled(true); + ui->cb_outputRate3->setEnabled(true); + ui->cb_outputRate4->setEnabled(true); + ui->cb_outputRate5->setEnabled(true); + ui->cb_outputRate6->setEnabled(true); } } @@ -371,14 +377,14 @@ void ConfigOutputWidget::updateObjectsFromWidgets() } // Set update rates - actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[4] = m_config->cb_outputRate5->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[5] = m_config->cb_outputRate6->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[0] = ui->cb_outputRate1->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[1] = ui->cb_outputRate2->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[2] = ui->cb_outputRate3->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[3] = ui->cb_outputRate4->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[4] = ui->cb_outputRate5->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[5] = ui->cb_outputRate6->currentText().toUInt(); - actuatorSettingsData.MotorsSpinWhileArmed = m_config->spinningArmed->isChecked() ? + actuatorSettingsData.MotorsSpinWhileArmed = ui->spinningArmed->isChecked() ? ActuatorSettings::MOTORSSPINWHILEARMED_TRUE : ActuatorSettings::MOTORSSPINWHILEARMED_FALSE; @@ -394,7 +400,7 @@ void ConfigOutputWidget::openHelp() void ConfigOutputWidget::stopTests() { - m_config->channelOutTest->setChecked(false); + ui->channelOutTest->setChecked(false); } void ConfigOutputWidget::disableIfNotMe(UAVObject* obj) diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h index 9a347d3f9..1d15c8de5 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h @@ -50,7 +50,7 @@ public: private: - Ui_OutputWidget *m_config; + Ui_OutputWidget *ui; QList sliders; diff --git a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui index fb81114bd..a8b3f65dd 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui +++ b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui @@ -20,6 +20,9 @@ 0 + + true + HW settings @@ -119,7 +122,7 @@ 12 - + @@ -399,11 +402,11 @@ - - - - - + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index c346f5f97..b28693c09 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -61,8 +61,7 @@ const double ConfigRevoWidget::maxVarValue = 0.1; // ***************** -class Thread : public QThread -{ +class Thread : public QThread { public: static void usleep(unsigned long usecs) { @@ -74,9 +73,10 @@ public: ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : ConfigTaskWidget(parent), - collectingData(false), m_ui(new Ui_RevoSensorsWidget()), - position(-1) + collectingData(false), + position(-1), + isBoardRotationStored(false) { m_ui->setupUi(this); @@ -105,9 +105,9 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : // Initialize the 9 bargraph values: QMatrix lineMatrix = renderer->matrixForElement("accel_x"); - QRectF rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_x")); + QRectF rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_x")); qreal startX = rect.x(); - qreal startY = rect.y()+ rect.height(); + qreal startY = rect.y() + rect.height(); // maxBarHeight will be used for scaling it later. maxBarHeight = rect.height(); // Then once we have the initial location, we can put it @@ -119,101 +119,103 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : accel_x->setElementId("accel_x"); m_ui->sensorsBargraph->scene()->addItem(accel_x); accel_x->setPos(startX, startY); - accel_x->setTransform(QTransform::fromScale(1,0),true); + accel_x->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("accel_y"); rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_y")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - accel_y = new QGraphicsSvgItem(); + startX = rect.x(); + startY = rect.y() + rect.height(); + accel_y = new QGraphicsSvgItem(); accel_y->setSharedRenderer(renderer); accel_y->setElementId("accel_y"); m_ui->sensorsBargraph->scene()->addItem(accel_y); - accel_y->setPos(startX,startY); - accel_y->setTransform(QTransform::fromScale(1,0),true); + accel_y->setPos(startX, startY); + accel_y->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("accel_z"); rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_z")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - accel_z = new QGraphicsSvgItem(); + startX = rect.x(); + startY = rect.y() + rect.height(); + accel_z = new QGraphicsSvgItem(); accel_z->setSharedRenderer(renderer); accel_z->setElementId("accel_z"); m_ui->sensorsBargraph->scene()->addItem(accel_z); - accel_z->setPos(startX,startY); - accel_z->setTransform(QTransform::fromScale(1,0),true); + accel_z->setPos(startX, startY); + accel_z->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("gyro_x"); rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_x")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - gyro_x = new QGraphicsSvgItem(); + startX = rect.x(); + startY = rect.y() + rect.height(); + gyro_x = new QGraphicsSvgItem(); gyro_x->setSharedRenderer(renderer); gyro_x->setElementId("gyro_x"); m_ui->sensorsBargraph->scene()->addItem(gyro_x); - gyro_x->setPos(startX,startY); - gyro_x->setTransform(QTransform::fromScale(1,0),true); + gyro_x->setPos(startX, startY); + gyro_x->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("gyro_y"); rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_y")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - gyro_y = new QGraphicsSvgItem(); + startX = rect.x(); + startY = rect.y() + rect.height(); + gyro_y = new QGraphicsSvgItem(); gyro_y->setSharedRenderer(renderer); gyro_y->setElementId("gyro_y"); m_ui->sensorsBargraph->scene()->addItem(gyro_y); - gyro_y->setPos(startX,startY); - gyro_y->setTransform(QTransform::fromScale(1,0),true); + gyro_y->setPos(startX, startY); + gyro_y->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("gyro_z"); rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_z")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - gyro_z = new QGraphicsSvgItem(); + startX = rect.x(); + startY = rect.y() + rect.height(); + gyro_z = new QGraphicsSvgItem(); gyro_z->setSharedRenderer(renderer); gyro_z->setElementId("gyro_z"); m_ui->sensorsBargraph->scene()->addItem(gyro_z); - gyro_z->setPos(startX,startY); - gyro_z->setTransform(QTransform::fromScale(1,0),true); + gyro_z->setPos(startX, startY); + gyro_z->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("mag_x"); rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_x")); - startX = rect.x(); - startY = rect.y()+ rect.height(); + startX = rect.x(); + startY = rect.y() + rect.height(); mag_x = new QGraphicsSvgItem(); mag_x->setSharedRenderer(renderer); mag_x->setElementId("mag_x"); m_ui->sensorsBargraph->scene()->addItem(mag_x); - mag_x->setPos(startX,startY); - mag_x->setTransform(QTransform::fromScale(1,0),true); + mag_x->setPos(startX, startY); + mag_x->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("mag_y"); rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_y")); - startX = rect.x(); - startY = rect.y()+ rect.height(); + startX = rect.x(); + startY = rect.y() + rect.height(); mag_y = new QGraphicsSvgItem(); mag_y->setSharedRenderer(renderer); mag_y->setElementId("mag_y"); m_ui->sensorsBargraph->scene()->addItem(mag_y); - mag_y->setPos(startX,startY); - mag_y->setTransform(QTransform::fromScale(1,0),true); + mag_y->setPos(startX, startY); + mag_y->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("mag_z"); rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_z")); - startX = rect.x(); - startY = rect.y()+ rect.height(); + startX = rect.x(); + startY = rect.y() + rect.height(); mag_z = new QGraphicsSvgItem(); mag_z->setSharedRenderer(renderer); mag_z->setElementId("mag_z"); m_ui->sensorsBargraph->scene()->addItem(mag_z); - mag_z->setPos(startX,startY); - mag_z->setTransform(QTransform::fromScale(1,0),true); + mag_z->setPos(startX, startY); + mag_z->setTransform(QTransform::fromScale(1, 0), true); // Must set up the UI (above) before setting up the UAVO mappings or refreshWidgetValues // will be dealing with some null pointers addUAVObject("RevoCalibration"); addUAVObject("EKFConfiguration"); + addUAVObject("HomeLocation"); + addUAVObject("AttitudeSettings"); autoLoadWidgets(); // Connect the signals @@ -222,10 +224,17 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); connect(m_ui->noiseMeasurementStart, SIGNAL(clicked()), this, SLOT(doStartNoiseMeasurement())); + connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation())); + addUAVObjectToWidgetRelation("RevoSettings", "FusionAlgorithm", m_ui->FusionAlgorithm); + addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->rollRotation, AttitudeSettings::BOARDROTATION_ROLL); + addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->pitchRotation, AttitudeSettings::BOARDROTATION_PITCH); + addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->yawRotation, AttitudeSettings::BOARDROTATION_YAW); + populateWidgets(); refreshWidgetsValues(); + m_ui->tabWidget->setCurrentIndex(0); } ConfigRevoWidget::~ConfigRevoWidget() @@ -241,25 +250,29 @@ void ConfigRevoWidget::showEvent(QShowEvent *event) // widget is shown, otherwise it cannot compute its values and // the result is usually a sensorsBargraph that is way too small. m_ui->sensorsBargraph->fitInView(sensorsBargraph, Qt::KeepAspectRatio); - m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); + m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio); } void ConfigRevoWidget::resizeEvent(QResizeEvent *event) { Q_UNUSED(event) m_ui->sensorsBargraph->fitInView(sensorsBargraph, Qt::KeepAspectRatio); - m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); + m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio); } /** - * Starts an accelerometer bias calibration. - */ + * Starts an accelerometer bias calibration. + */ void ConfigRevoWidget::doStartAccelGyroBiasCalibration() { + // Store and reset board rotation before calibration starts + isBoardRotationStored = false; + storeAndClearBoardRotation(); + m_ui->accelBiasStart->setEnabled(false); m_ui->accelBiasProgress->setValue(0); - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_FALSE; @@ -267,7 +280,7 @@ void ConfigRevoWidget::doStartAccelGyroBiasCalibration() revoCalibration->updated(); // Disable gyro bias correction while calibrating - AttitudeSettings * attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); + AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); Q_ASSERT(attitudeSettings); AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData(); attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE; @@ -284,7 +297,7 @@ void ConfigRevoWidget::doStartAccelGyroBiasCalibration() UAVObject::Metadata mdata; /* Need to get as many accel updates as possible */ - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); initialAccelsMdata = accels->getMetadata(); mdata = initialAccelsMdata; @@ -292,7 +305,7 @@ void ConfigRevoWidget::doStartAccelGyroBiasCalibration() mdata.flightTelemetryUpdatePeriod = 100; accels->setMetadata(mdata); - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); Q_ASSERT(gyros); initialGyrosMdata = gyros->getMetadata(); mdata = initialGyrosMdata; @@ -302,22 +315,23 @@ void ConfigRevoWidget::doStartAccelGyroBiasCalibration() // Now connect to the accels and mag updates, gather for 100 samples collectingData = true; - connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetAccelGyroBiasData(UAVObject*))); - connect(gyros, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetAccelGyroBiasData(UAVObject*))); + connect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *))); + connect(gyros, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *))); } /** - Updates the accel bias raw values - */ + Updates the accel bias raw values + */ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) { QMutexLocker lock(&sensorsUpdateLock); + Q_UNUSED(lock); - switch(obj->getObjID()) { + switch (obj->getObjID()) { case Accels::OBJID: { - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); Accels::DataFields accelsData = accels->getData(); @@ -328,7 +342,7 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) } case Gyros::OBJID: { - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); Q_ASSERT(gyros); Gyros::DataFields gyrosData = gyros->getData(); @@ -342,25 +356,24 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) } // Work out the progress based on whichever has less - double p1 = (double) accel_accum_x.size() / (double) NOISE_SAMPLES; - double p2 = (double) accel_accum_y.size() / (double) NOISE_SAMPLES; + double p1 = (double)accel_accum_x.size() / (double)NOISE_SAMPLES; + double p2 = (double)accel_accum_y.size() / (double)NOISE_SAMPLES; m_ui->accelBiasProgress->setValue(((p1 < p2) ? p1 : p2) * 100); - if(accel_accum_x.size() >= NOISE_SAMPLES && - gyro_accum_y.size() >= NOISE_SAMPLES && - collectingData == true) { - + if (accel_accum_x.size() >= NOISE_SAMPLES && + gyro_accum_y.size() >= NOISE_SAMPLES && + collectingData == true) { collectingData = false; - Accels * accels = Accels::GetInstance(getObjectManager()); - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); - disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetAccelGyroBiasData(UAVObject*))); - disconnect(gyros,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetAccelGyroBiasData(UAVObject*))); + disconnect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *))); + disconnect(gyros, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *))); m_ui->accelBiasStart->setEnabled(true); - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_TRUE; @@ -368,15 +381,15 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) // Update the biases based on collected data revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] += listMean(accel_accum_x); revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] += listMean(accel_accum_y); - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] += ( listMean(accel_accum_z) + GRAVITY ); - revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_X] += listMean(gyro_accum_x); - revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_Y] += listMean(gyro_accum_y); - revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_Z] += listMean(gyro_accum_z); + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] += (listMean(accel_accum_z) + GRAVITY); + revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_X] += listMean(gyro_accum_x); + revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_Y] += listMean(gyro_accum_y); + revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_Z] += listMean(gyro_accum_z); revoCalibration->setData(revoCalibrationData); revoCalibration->updated(); - AttitudeSettings * attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); + AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); Q_ASSERT(attitudeSettings); AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData(); attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE; @@ -385,132 +398,132 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) accels->setMetadata(initialAccelsMdata); gyros->setMetadata(initialGyrosMdata); + + // Recall saved board rotation + recallBoardRotation(); } } - -int LinearEquationsSolving(int nDim, double* pfMatr, double* pfVect, double* pfSolution) +int LinearEquationsSolving(int nDim, double *pfMatr, double *pfVect, double *pfSolution) { - double fMaxElem; - double fAcc; + double fMaxElem; + double fAcc; - int i , j, k, m; + int i, j, k, m; - for(k=0; k<(nDim-1); k++) // base row of matrix - { - // search of line with max element - fMaxElem = fabs( pfMatr[k*nDim + k] ); - m = k; - for(i=k+1; i= 0; k--) { + pfSolution[k] = pfVect[k]; + for (i = (k + 1); i < nDim; i++) { + pfSolution[k] -= (pfMatr[k * nDim + i] * pfSolution[i]); + } + pfSolution[k] = pfSolution[k] / pfMatr[k * nDim + k]; + } - for(k=(nDim-1); k>=0; k--) - { - pfSolution[k] = pfVect[k]; - for(i=(k+1); igetData(); HomeLocation::DataFields homeLocationData = homeLocation->getData(); - //check if Homelocation is set - if(!homeLocationData.Set) - { + // check if Homelocation is set + if (!homeLocationData.Set) { QMessageBox msgBox; msgBox.setInformativeText(tr("

HomeLocation not SET.

Please set your HomeLocation and try again. Aborting calibration!

")); msgBox.setStandardButtons(QMessageBox::Ok); @@ -525,9 +538,9 @@ void ConfigRevoWidget::doStartSixPointCalibration() revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = 1; revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = 1; revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = 1; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = 0; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = 0; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = 0; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = 0; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = 0; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = 0; accel_accum_x.clear(); accel_accum_y.clear(); @@ -538,9 +551,9 @@ void ConfigRevoWidget::doStartSixPointCalibration() revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = 1; revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = 1; revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = 1; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = 0; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = 0; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = 0; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = 0; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = 0; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = 0; // Disable adaptive mag nulling initialMagCorrectionRate = revoCalibrationData.MagBiasNullingRate; @@ -561,7 +574,7 @@ void ConfigRevoWidget::doStartSixPointCalibration() #ifdef SIX_POINT_CAL_ACCEL /* Need to get as many accel updates as possible */ - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); initialAccelsMdata = accels->getMetadata(); @@ -572,7 +585,7 @@ void ConfigRevoWidget::doStartSixPointCalibration() #endif /* Need to get as many mag updates as possible */ - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Magnetometer *mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); initialMagMdata = mag->getMetadata(); mdata = initialMagMdata; @@ -590,13 +603,14 @@ void ConfigRevoWidget::doStartSixPointCalibration() } /** - * Saves the data from the aircraft in one of six positions. - * This is called when they click "save position" and starts - * averaging data for this position. - */ + * Saves the data from the aircraft in one of six positions. + * This is called when they click "save position" and starts + * averaging data for this position. + */ void ConfigRevoWidget::savePositionData() { QMutexLocker lock(&sensorsUpdateLock); + m_ui->sixPointsSave->setEnabled(false); accel_accum_x.clear(); @@ -608,39 +622,39 @@ void ConfigRevoWidget::savePositionData() collectingData = true; - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Magnetometer *mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); - connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); - connect(mag, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + connect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *))); + connect(mag, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *))); m_ui->sixPointCalibInstructions->append("Hold..."); } /** - * Grab a sample of mag (optionally accel) data while in this position and - * store it for averaging. When sufficient points are collected advance - * to the next position (give message to user) or compute the scale and bias - */ -void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) + * Grab a sample of mag (optionally accel) data while in this position and + * store it for averaging. When sufficient points are collected advance + * to the next position (give message to user) or compute the scale and bias + */ +void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject *obj) { QMutexLocker lock(&sensorsUpdateLock); // This is necessary to prevent a race condition on disconnect signal and another update if (collectingData == true) { - if( obj->getObjID() == Accels::OBJID ) { + if (obj->getObjID() == Accels::OBJID) { #ifdef SIX_POINT_CAL_ACCEL - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); Accels::DataFields accelsData = accels->getData(); accel_accum_x.append(accelsData.x); accel_accum_y.append(accelsData.y); accel_accum_z.append(accelsData.z); #endif - } else if( obj->getObjID() == Magnetometer::OBJID ) { - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + } else if (obj->getObjID() == Magnetometer::OBJID) { + Magnetometer *mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); Magnetometer::DataFields magData = mag->getData(); mag_accum_x.append(magData.x); @@ -652,9 +666,9 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) } #ifdef SIX_POINT_CAL_ACCEL - if(accel_accum_x.size() >= 20 && mag_accum_x.size() >= 20 && collectingData == true) { + if (accel_accum_x.size() >= 20 && mag_accum_x.size() >= 20 && collectingData == true) { #else - if(mag_accum_x.size() >= 20 && collectingData == true) { + if (mag_accum_x.size() >= 20 && collectingData == true) { #endif collectingData = false; @@ -662,44 +676,44 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) #ifdef SIX_POINT_CAL_ACCEL // Store the mean for this position for the accel - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); - disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + disconnect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *))); accel_data_x[position] = listMean(accel_accum_x); accel_data_y[position] = listMean(accel_accum_y); accel_data_z[position] = listMean(accel_accum_z); #endif // Store the mean for this position for the mag - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Magnetometer *mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); - disconnect(mag,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + disconnect(mag, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *))); mag_data_x[position] = listMean(mag_accum_x); mag_data_y[position] = listMean(mag_accum_y); mag_data_z[position] = listMean(mag_accum_z); position = (position + 1) % 6; - if(position == 1) { + if (position == 1) { m_ui->sixPointCalibInstructions->append("Place with left side down and click save position..."); displayPlane("plane-left"); } - if(position == 2) { + if (position == 2) { m_ui->sixPointCalibInstructions->append("Place upside down and click save position..."); displayPlane("plane-flip"); } - if(position == 3) { + if (position == 3) { m_ui->sixPointCalibInstructions->append("Place with right side down and click save position..."); displayPlane("plane-right"); } - if(position == 4) { + if (position == 4) { m_ui->sixPointCalibInstructions->append("Place with nose up and click save position..."); displayPlane("plane-up"); } - if(position == 5) { + if (position == 5) { m_ui->sixPointCalibInstructions->append("Place with nose down and click save position..."); displayPlane("plane-down"); } - if(position == 0) { + if (position == 0) { computeScaleBias(); m_ui->sixPointsStart->setEnabled(true); m_ui->sixPointsSave->setEnabled(false); @@ -709,144 +723,187 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) accels->setMetadata(initialAccelsMdata); #endif mag->setMetadata(initialMagMdata); + + // Recall saved board rotation + recallBoardRotation(); } } } /** - * Computes the scale and bias for the magnetomer and (compile option) - * for the accel once all the data has been collected in 6 positions. - */ + * Computes the scale and bias for the magnetomer and (compile option) + * for the accel once all the data has been collected in 6 positions. + */ void ConfigRevoWidget::computeScaleBias() { - double S[3], b[3]; - double Be_length; - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); - HomeLocation * homeLocation = HomeLocation::GetInstance(getObjectManager()); - Q_ASSERT(revoCalibration); - Q_ASSERT(homeLocation); - RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); - HomeLocation::DataFields homeLocationData = homeLocation->getData(); + double S[3], b[3]; + double Be_length; + RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); -#ifdef SIX_POINT_CAL_ACCEL - // Calibration accel - SixPointInConstFieldCal( homeLocationData.g_e, accel_data_x, accel_data_y, accel_data_z, S, b); - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = fabs(S[0]); - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = fabs(S[1]); - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = fabs(S[2]); - - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = -sign(S[0]) * b[0]; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = -sign(S[1]) * b[1]; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = -sign(S[2]) * b[2]; -#endif - - // Calibration mag - Be_length = sqrt(pow(homeLocationData.Be[0],2)+pow(homeLocationData.Be[1],2)+pow(homeLocationData.Be[2],2)); - SixPointInConstFieldCal( Be_length, mag_data_x, mag_data_y, mag_data_z, S, b); - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = fabs(S[0]); - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = fabs(S[1]); - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = fabs(S[2]); - - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = -sign(S[0]) * b[0]; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = -sign(S[1]) * b[1]; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = -sign(S[2]) * b[2]; - - // Restore the previous setting - revoCalibrationData.MagBiasNullingRate = initialMagCorrectionRate; - -#ifdef SIX_POINT_CAL_ACCEL - bool good_calibration = true; - - // Check the mag calibration is good - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y]; - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z]; - - // Check the accel calibration is good - good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] == - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X]; - good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] == - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y]; - good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] == - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z]; - good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] == - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X]; - good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] == - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y]; - good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] == - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z]; - if (good_calibration) { - revoCalibration->setData(revoCalibrationData); - m_ui->sixPointCalibInstructions->append("Computed accel and mag scale and bias..."); - } else { - revoCalibrationData = revoCalibration->getData(); - m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); - } -#else - bool good_calibration = true; - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y]; - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z]; - if (good_calibration) { - revoCalibration->setData(revoCalibrationData); - m_ui->sixPointCalibInstructions->append("Computed mag scale and bias..."); - } else { - revoCalibrationData = revoCalibration->getData(); - m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); - } -#endif - - position = -1; //set to run again -} - -/** - Rotate the paper plane - */ -void ConfigRevoWidget::displayPlane(QString elementID) -{ - paperplane->setElementId(elementID); - m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect()); - m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); - -} - -/*********** Noise measurement functions **************/ -/** - * Connect sensor updates and timeout for measuring the noise - */ -void ConfigRevoWidget::doStartNoiseMeasurement() -{ - QMutexLocker lock(&sensorsUpdateLock); - Q_UNUSED(lock); - - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); - HomeLocation * homeLocation = HomeLocation::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); Q_ASSERT(homeLocation); RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); HomeLocation::DataFields homeLocationData = homeLocation->getData(); - //check if Homelocation is set - if(!homeLocationData.Set) - { +#ifdef SIX_POINT_CAL_ACCEL + // Calibration accel + SixPointInConstFieldCal(homeLocationData.g_e, accel_data_x, accel_data_y, accel_data_z, S, b); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = fabs(S[0]); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = fabs(S[1]); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = fabs(S[2]); + + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = -sign(S[0]) * b[0]; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = -sign(S[1]) * b[1]; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = -sign(S[2]) * b[2]; +#endif + + // Calibration mag + Be_length = sqrt(pow(homeLocationData.Be[0], 2) + pow(homeLocationData.Be[1], 2) + pow(homeLocationData.Be[2], 2)); + SixPointInConstFieldCal(Be_length, mag_data_x, mag_data_y, mag_data_z, S, b); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = fabs(S[0]); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = fabs(S[1]); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = fabs(S[2]); + + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = -sign(S[0]) * b[0]; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = -sign(S[1]) * b[1]; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = -sign(S[2]) * b[2]; + + // Restore the previous setting + revoCalibrationData.MagBiasNullingRate = initialMagCorrectionRate; + +#ifdef SIX_POINT_CAL_ACCEL + bool good_calibration = true; + + // Check the mag calibration is good + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z]; + + // Check the accel calibration is good + good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] == + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X]; + good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] == + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y]; + good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] == + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z]; + good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] == + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X]; + good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] == + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y]; + good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] == + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z]; + if (good_calibration) { + revoCalibration->setData(revoCalibrationData); + m_ui->sixPointCalibInstructions->append("Computed accel and mag scale and bias..."); + } else { + revoCalibrationData = revoCalibration->getData(); + m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); + } +#else // ifdef SIX_POINT_CAL_ACCEL + bool good_calibration = true; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z]; + if (good_calibration) { + revoCalibration->setData(revoCalibrationData); + m_ui->sixPointCalibInstructions->append("Computed mag scale and bias..."); + } else { + revoCalibrationData = revoCalibration->getData(); + m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); + } +#endif // ifdef SIX_POINT_CAL_ACCEL + + position = -1; // set to run again +} + +void ConfigRevoWidget::storeAndClearBoardRotation() +{ + if(!isBoardRotationStored) { + // Store current board rotation + isBoardRotationStored = true; + AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); + Q_ASSERT(attitudeSettings); + AttitudeSettings::DataFields data = attitudeSettings->getData(); + storedBoardRotation[AttitudeSettings::BOARDROTATION_YAW] = data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW]; + storedBoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL]; + storedBoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH]; + + // Set board rotation to no rotation + data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = 0; + data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = 0; + data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = 0; + attitudeSettings->setData(data); + } +} + +void ConfigRevoWidget::recallBoardRotation() +{ + if(isBoardRotationStored) { + // Recall current board rotation + isBoardRotationStored = false; + + AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); + Q_ASSERT(attitudeSettings); + AttitudeSettings::DataFields data = attitudeSettings->getData(); + data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = storedBoardRotation[AttitudeSettings::BOARDROTATION_YAW]; + data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = storedBoardRotation[AttitudeSettings::BOARDROTATION_ROLL]; + data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = storedBoardRotation[AttitudeSettings::BOARDROTATION_PITCH]; + attitudeSettings->setData(data); + } +} + +/** + Rotate the paper plane + */ +void ConfigRevoWidget::displayPlane(QString elementID) +{ + paperplane->setElementId(elementID); + m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect()); + m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio); +} + +/*********** Noise measurement functions **************/ +/** + * Connect sensor updates and timeout for measuring the noise + */ +void ConfigRevoWidget::doStartNoiseMeasurement() +{ + QMutexLocker lock(&sensorsUpdateLock); + + // Store and reset board rotation before calibration starts + isBoardRotationStored = false; + storeAndClearBoardRotation(); + + Q_UNUSED(lock); + + RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + Q_ASSERT(homeLocation); + RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); + HomeLocation::DataFields homeLocationData = homeLocation->getData(); + + // check if Homelocation is set + if (!homeLocationData.Set) { QMessageBox msgBox; msgBox.setInformativeText(tr("

HomeLocation not SET.

Please set your HomeLocation and try again. Aborting calibration!

")); msgBox.setStandardButtons(QMessageBox::Ok); @@ -867,11 +924,11 @@ void ConfigRevoWidget::doStartNoiseMeasurement() mag_accum_z.clear(); /* Need to get as many accel, mag and gyro updates as possible */ - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); Q_ASSERT(gyros); - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Magnetometer *mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); UAVObject::Metadata mdata; @@ -895,26 +952,27 @@ void ConfigRevoWidget::doStartNoiseMeasurement() mag->setMetadata(mdata); /* Connect for updates */ - connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); - connect(gyros, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); - connect(mag, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); + connect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); + connect(gyros, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); + connect(mag, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); } /** - * Called when any of the sensors are updated. Stores the sample for measuring the - * variance at the end - */ -void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) + * Called when any of the sensors are updated. Stores the sample for measuring the + * variance at the end + */ +void ConfigRevoWidget::doGetNoiseSample(UAVObject *obj) { QMutexLocker lock(&sensorsUpdateLock); + Q_UNUSED(lock); Q_ASSERT(obj); - switch(obj->getObjID()) { + switch (obj->getObjID()) { case Gyros::OBJID: { - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); Q_ASSERT(gyros); Gyros::DataFields gyroData = gyros->getData(); gyro_accum_x.append(gyroData.x); @@ -924,7 +982,7 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) } case Accels::OBJID: { - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); Accels::DataFields accelsData = accels->getData(); accel_accum_x.append(accelsData.x); @@ -934,7 +992,7 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) } case Magnetometer::OBJID: { - Magnetometer * mags = Magnetometer::GetInstance(getObjectManager()); + Magnetometer *mags = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mags); Magnetometer::DataFields magData = mags->getData(); mag_accum_x.append(magData.x); @@ -946,95 +1004,109 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) Q_ASSERT(0); } - float p1 = (float) mag_accum_x.length() / (float) NOISE_SAMPLES; - float p2 = (float) gyro_accum_x.length() / (float) NOISE_SAMPLES; - float p3 = (float) accel_accum_x.length() / (float) NOISE_SAMPLES; + float p1 = (float)mag_accum_x.length() / (float)NOISE_SAMPLES; + float p2 = (float)gyro_accum_x.length() / (float)NOISE_SAMPLES; + float p3 = (float)accel_accum_x.length() / (float)NOISE_SAMPLES; float prog = (p1 < p2) ? p1 : p2; prog = (prog < p3) ? prog : p3; m_ui->noiseMeasurementProgress->setValue(prog * 100); - if(mag_accum_x.length() >= NOISE_SAMPLES && - gyro_accum_x.length() >= NOISE_SAMPLES && - accel_accum_x.length() >= NOISE_SAMPLES) { + if (mag_accum_x.length() >= NOISE_SAMPLES && + gyro_accum_x.length() >= NOISE_SAMPLES && + accel_accum_x.length() >= NOISE_SAMPLES) { // No need to for more updates - Magnetometer * mags = Magnetometer::GetInstance(getObjectManager()); - Accels * accels = Accels::GetInstance(getObjectManager()); - Gyros * gyros = Gyros::GetInstance(getObjectManager()); - disconnect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); - disconnect(gyros, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); - disconnect(mags, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); + Magnetometer *mags = Magnetometer::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); + disconnect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); + disconnect(gyros, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); + disconnect(mags, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); EKFConfiguration *ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager()); Q_ASSERT(ekfConfiguration); - if(ekfConfiguration) { + if (ekfConfiguration) { EKFConfiguration::DataFields revoCalData = ekfConfiguration->getData(); revoCalData.Q[EKFConfiguration::Q_ACCELX] = listVar(accel_accum_x); revoCalData.Q[EKFConfiguration::Q_ACCELY] = listVar(accel_accum_y); revoCalData.Q[EKFConfiguration::Q_ACCELZ] = listVar(accel_accum_z); - revoCalData.Q[EKFConfiguration::Q_GYROX] = listVar(gyro_accum_x); - revoCalData.Q[EKFConfiguration::Q_GYROY] = listVar(gyro_accum_y); - revoCalData.Q[EKFConfiguration::Q_GYROZ] = listVar(gyro_accum_z); - revoCalData.R[EKFConfiguration::R_MAGX] = listVar(mag_accum_x); - revoCalData.R[EKFConfiguration::R_MAGY] = listVar(mag_accum_y); - revoCalData.R[EKFConfiguration::R_MAGZ] = listVar(mag_accum_z); + revoCalData.Q[EKFConfiguration::Q_GYROX] = listVar(gyro_accum_x); + revoCalData.Q[EKFConfiguration::Q_GYROY] = listVar(gyro_accum_y); + revoCalData.Q[EKFConfiguration::Q_GYROZ] = listVar(gyro_accum_z); + revoCalData.R[EKFConfiguration::R_MAGX] = listVar(mag_accum_x); + revoCalData.R[EKFConfiguration::R_MAGY] = listVar(mag_accum_y); + revoCalData.R[EKFConfiguration::R_MAGZ] = listVar(mag_accum_z); ekfConfiguration->setData(revoCalData); } + + // Recall saved board rotation + recallBoardRotation(); } } /********** UI Functions *************/ /** - Draws the sensor variances bargraph - */ + Draws the sensor variances bargraph + */ void ConfigRevoWidget::drawVariancesGraph() { - EKFConfiguration * ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager()); + EKFConfiguration *ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager()); + Q_ASSERT(ekfConfiguration); - if(!ekfConfiguration) + if (!ekfConfiguration) { return; + } EKFConfiguration::DataFields ekfConfigurationData = ekfConfiguration->getData(); // The expected range is from 1E-6 to 1E-1 double steps = 6; // 6 bars on the graph - float accel_x_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELX])); - if(accel_x) - accel_x->setTransform(QTransform::fromScale(1,accel_x_var),false); - float accel_y_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELY])); - if(accel_y) - accel_y->setTransform(QTransform::fromScale(1,accel_y_var),false); - float accel_z_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELZ])); - if(accel_z) - accel_z->setTransform(QTransform::fromScale(1,accel_z_var),false); + float accel_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELX])); + if (accel_x) { + accel_x->setTransform(QTransform::fromScale(1, accel_x_var), false); + } + float accel_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELY])); + if (accel_y) { + accel_y->setTransform(QTransform::fromScale(1, accel_y_var), false); + } + float accel_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELZ])); + if (accel_z) { + accel_z->setTransform(QTransform::fromScale(1, accel_z_var), false); + } - float gyro_x_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROX])); - if(gyro_x) - gyro_x->setTransform(QTransform::fromScale(1,gyro_x_var),false); - float gyro_y_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROY])); - if(gyro_y) - gyro_y->setTransform(QTransform::fromScale(1,gyro_y_var),false); - float gyro_z_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROZ])); - if(gyro_z) - gyro_z->setTransform(QTransform::fromScale(1,gyro_z_var),false); + float gyro_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROX])); + if (gyro_x) { + gyro_x->setTransform(QTransform::fromScale(1, gyro_x_var), false); + } + float gyro_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROY])); + if (gyro_y) { + gyro_y->setTransform(QTransform::fromScale(1, gyro_y_var), false); + } + float gyro_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROZ])); + if (gyro_z) { + gyro_z->setTransform(QTransform::fromScale(1, gyro_z_var), false); + } // Scale by 1e-3 because mag vars are much higher. - float mag_x_var = -1/steps*(1+steps+log10(1e-3*ekfConfigurationData.R[EKFConfiguration::R_MAGX])); - if(mag_x) - mag_x->setTransform(QTransform::fromScale(1,mag_x_var),false); - float mag_y_var = -1/steps*(1+steps+log10(1e-3*ekfConfigurationData.R[EKFConfiguration::R_MAGY])); - if(mag_y) - mag_y->setTransform(QTransform::fromScale(1,mag_y_var),false); - float mag_z_var = -1/steps*(1+steps+log10(1e-3*ekfConfigurationData.R[EKFConfiguration::R_MAGZ])); - if(mag_z) - mag_z->setTransform(QTransform::fromScale(1,mag_z_var),false); + float mag_x_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGX])); + if (mag_x) { + mag_x->setTransform(QTransform::fromScale(1, mag_x_var), false); + } + float mag_y_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGY])); + if (mag_y) { + mag_y->setTransform(QTransform::fromScale(1, mag_y_var), false); + } + float mag_z_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGZ])); + if (mag_z) { + mag_z->setTransform(QTransform::fromScale(1, mag_z_var), false); + } } /** - * Called by the ConfigTaskWidget parent when RevoCalibration is updated - * to update the UI - */ + * Called by the ConfigTaskWidget parent when RevoCalibration is updated + * to update the UI + */ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object) { ConfigTaskWidget::refreshWidgetsValues(object); @@ -1044,12 +1116,31 @@ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object) m_ui->noiseMeasurementStart->setEnabled(true); m_ui->sixPointsStart->setEnabled(true); m_ui->accelBiasStart->setEnabled(true); - m_ui->startDriftCalib->setEnabled(true); - m_ui->calibInstructions->setText(QString("Press \"Start\" above to calibrate.")); + + m_ui->isSetCheckBox->setEnabled(false); + + HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); + Q_ASSERT(homeLocation); + HomeLocation::DataFields homeLocationData = homeLocation->getData(); + + QString beStr = QString("%1:%2:%3").arg(QString::number(homeLocationData.Be[0]), QString::number(homeLocationData.Be[1]), QString::number(homeLocationData.Be[2])); + m_ui->beBox->setText(beStr); } -/** - @} - @} - */ +void ConfigRevoWidget::clearHomeLocation() +{ + HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); + + Q_ASSERT(homeLocation); + HomeLocation::DataFields homeLocationData; + homeLocationData.Latitude = 0; + homeLocationData.Longitude = 0; + homeLocationData.Altitude = 0; + homeLocationData.Be[0] = 0; + homeLocationData.Be[1] = 0; + homeLocationData.Be[2] = 0; + homeLocationData.g_e = 9.81f; + homeLocationData.Set = HomeLocation::SET_FALSE; + homeLocation->setData(homeLocationData); +} diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index 9bc35004c..9eb349612 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -43,19 +43,18 @@ class Ui_Widget; -class ConfigRevoWidget: public ConfigTaskWidget -{ +class ConfigRevoWidget : public ConfigTaskWidget { Q_OBJECT public: ConfigRevoWidget(QWidget *parent = 0); ~ConfigRevoWidget(); - + private: void drawVariancesGraph(); void displayPlane(QString elementID); - //! Computes the scale and bias of the mag based on collected data + // ! Computes the scale and bias of the mag based on collected data void computeScaleBias(); Ui_RevoSensorsWidget *m_ui; @@ -101,27 +100,36 @@ private: static const int NOISE_SAMPLES = 100; + // Board rotation store/recall + qint16 storedBoardRotation[3]; + bool isBoardRotationStored; + void storeAndClearBoardRotation(); + void recallBoardRotation(); + + private slots: - //! Overriden method from the configTaskWidget to update UI - virtual void refreshWidgetsValues(UAVObject *object=NULL); + // ! Overriden method from the configTaskWidget to update UI + virtual void refreshWidgetsValues(UAVObject *object = NULL); // Slots for calibrating the mags void doStartSixPointCalibration(); - void doGetSixPointCalibrationMeasurement(UAVObject * obj); + void doGetSixPointCalibrationMeasurement(UAVObject *obj); void savePositionData(); // Slots for calibrating the accel and gyro void doStartAccelGyroBiasCalibration(); - void doGetAccelGyroBiasData(UAVObject*); + void doGetAccelGyroBiasData(UAVObject *); // Slots for measuring the sensor noise void doStartNoiseMeasurement(); void doGetNoiseSample(UAVObject *); + // Slot for clearing home location + void clearHomeLocation(); + protected: void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); - }; #endif // ConfigRevoWidget_H diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 5469403ae..896801f16 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -1,7 +1,7 @@ /** ****************************************************************************** * - * @file configstabilizationwidget.h + * @file configstabilizationwidget.cpp * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ @@ -36,132 +36,161 @@ #include #include - #include #include - ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) { - m_stabilization = new Ui_StabilizationWidget(); - m_stabilization->setupUi(this); + ui = new Ui_StabilizationWidget(); + ui->setupUi(this); - ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); - Core::Internal::GeneralSettings * settings=pm->getObject(); - if(!settings->useExpertMode()) - m_stabilization->saveStabilizationToRAM_6->setVisible(false); + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings *settings = pm->getObject(); - + if (!settings->useExpertMode()) { + ui->saveStabilizationToRAM_6->setVisible(false); + } autoLoadWidgets(); - realtimeUpdates=new QTimer(this); - connect(m_stabilization->realTimeUpdates_6,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int))); - connect(realtimeUpdates,SIGNAL(timeout()),this,SLOT(apply())); - connect(m_stabilization->checkBox_7,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); - connect(m_stabilization->checkBox_2,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); - connect(m_stabilization->checkBox_8,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); - connect(m_stabilization->checkBox_3,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); + realtimeUpdates = new QTimer(this); + connect(realtimeUpdates, SIGNAL(timeout()), this, SLOT(apply())); - connect(this,SIGNAL(widgetContentsChanged(QWidget*)),this,SLOT(processLinkedWidgets(QWidget*))); + connect(ui->realTimeUpdates_6, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool))); + addWidget(ui->realTimeUpdates_6); + connect(ui->realTimeUpdates_8, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool))); + addWidget(ui->realTimeUpdates_8); + connect(ui->realTimeUpdates_12, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool))); + addWidget(ui->realTimeUpdates_12); + + connect(ui->checkBox_7, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); + addWidget(ui->checkBox_7); + connect(ui->checkBox_2, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); + addWidget(ui->checkBox_2); + connect(ui->checkBox_8, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); + addWidget(ui->checkBox_8); + connect(ui->checkBox_3, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); + addWidget(ui->checkBox_3); + + addWidget(ui->pushButton_2); + addWidget(ui->pushButton_3); + addWidget(ui->pushButton_4); + addWidget(ui->pushButton_5); + addWidget(ui->pushButton_6); + addWidget(ui->pushButton_9); + addWidget(ui->pushButton_20); + addWidget(ui->pushButton_22); + addWidget(ui->pushButton_23); + + addWidget(ui->basicResponsivenessGroupBox); + connect(ui->basicResponsivenessGroupBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); + addWidget(ui->advancedResponsivenessGroupBox); + connect(ui->advancedResponsivenessGroupBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); + + connect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *))); + + // Link by default + ui->checkBox_7->setChecked(true); + ui->checkBox_8->setChecked(true); disableMouseWheelEvents(); - - + updateEnableControls(); } - ConfigStabilizationWidget::~ConfigStabilizationWidget() { // Do nothing } -void ConfigStabilizationWidget::realtimeUpdatesSlot(int value) + +void ConfigStabilizationWidget::refreshWidgetsValues(UAVObject *o) { - m_stabilization->realTimeUpdates_6->setCheckState((Qt::CheckState)value); - if(value==Qt::Checked && !realtimeUpdates->isActive()) - realtimeUpdates->start(300); - else if(value==Qt::Unchecked) + ConfigTaskWidget::refreshWidgetsValues(o); + + ui->basicResponsivenessGroupBox->setChecked(ui->rateRollKp_3->value() == ui->ratePitchKp_4->value() && + ui->rateRollKi_3->value() == ui->ratePitchKi_4->value()); +} + +void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value) +{ + ui->realTimeUpdates_6->setChecked(value); + ui->realTimeUpdates_8->setChecked(value); + ui->realTimeUpdates_12->setChecked(value); + + if (value && !realtimeUpdates->isActive()) { + realtimeUpdates->start(AUTOMATIC_UPDATE_RATE); + qDebug() << "Instant Update timer started."; + } else if (!value && realtimeUpdates->isActive()) { realtimeUpdates->stop(); -} - -void ConfigStabilizationWidget::linkCheckBoxes(int value) -{ - if(sender()== m_stabilization->checkBox_7) - m_stabilization->checkBox_3->setCheckState((Qt::CheckState)value); - else if(sender()== m_stabilization->checkBox_3) - m_stabilization->checkBox_7->setCheckState((Qt::CheckState)value); - else if(sender()== m_stabilization->checkBox_8) - m_stabilization->checkBox_2->setCheckState((Qt::CheckState)value); - else if(sender()== m_stabilization->checkBox_2) - m_stabilization->checkBox_8->setCheckState((Qt::CheckState)value); -} - -void ConfigStabilizationWidget::processLinkedWidgets(QWidget * widget) -{ - if(m_stabilization->checkBox_7->checkState()==Qt::Checked) - { - if(widget== m_stabilization->RateRollKp_2) - { - m_stabilization->RatePitchKp->setValue(m_stabilization->RateRollKp_2->value()); - } - else if(widget== m_stabilization->RateRollKi_2) - { - m_stabilization->RatePitchKi->setValue(m_stabilization->RateRollKi_2->value()); - } - else if(widget== m_stabilization->RateRollILimit_2) - { - m_stabilization->RatePitchILimit->setValue(m_stabilization->RateRollILimit_2->value()); - } - else if(widget== m_stabilization->RatePitchKp) - { - m_stabilization->RateRollKp_2->setValue(m_stabilization->RatePitchKp->value()); - } - else if(widget== m_stabilization->RatePitchKi) - { - m_stabilization->RateRollKi_2->setValue(m_stabilization->RatePitchKi->value()); - } - else if(widget== m_stabilization->RatePitchILimit) - { - m_stabilization->RateRollILimit_2->setValue(m_stabilization->RatePitchILimit->value()); - } - else if(widget== m_stabilization->RollRateKd) - { - m_stabilization->PitchRateKd->setValue(m_stabilization->RollRateKd->value()); - } - else if(widget== m_stabilization->PitchRateKd) - { - m_stabilization->RollRateKd->setValue(m_stabilization->PitchRateKd->value()); - } - } - if(m_stabilization->checkBox_8->checkState()==Qt::Checked) - { - if(widget== m_stabilization->AttitudeRollKp) - { - m_stabilization->AttitudePitchKp_2->setValue(m_stabilization->AttitudeRollKp->value()); - } - else if(widget== m_stabilization->AttitudeRollKi) - { - m_stabilization->AttitudePitchKi_2->setValue(m_stabilization->AttitudeRollKi->value()); - } - else if(widget== m_stabilization->AttitudeRollILimit) - { - m_stabilization->AttitudePitchILimit_2->setValue(m_stabilization->AttitudeRollILimit->value()); - } - else if(widget== m_stabilization->AttitudePitchKp_2) - { - m_stabilization->AttitudeRollKp->setValue(m_stabilization->AttitudePitchKp_2->value()); - } - else if(widget== m_stabilization->AttitudePitchKi_2) - { - m_stabilization->AttitudeRollKi->setValue(m_stabilization->AttitudePitchKi_2->value()); - } - else if(widget== m_stabilization->AttitudePitchILimit_2) - { - m_stabilization->AttitudeRollILimit->setValue(m_stabilization->AttitudePitchILimit_2->value()); - } + qDebug() << "Instant Update timer stopped."; } } +void ConfigStabilizationWidget::linkCheckBoxes(bool value) +{ + if (sender() == ui->checkBox_7) { + ui->checkBox_3->setChecked(value); + } else if (sender() == ui->checkBox_3) { + ui->checkBox_7->setChecked(value); + } else if (sender() == ui->checkBox_8) { + ui->checkBox_2->setChecked(value); + } else if (sender() == ui->checkBox_2) { + ui->checkBox_8->setChecked(value); + } else if (sender() == ui->basicResponsivenessGroupBox) { + ui->advancedResponsivenessGroupBox->setChecked(!value); + if (value) { + processLinkedWidgets(ui->AttitudeResponsivenessSlider); + processLinkedWidgets(ui->RateResponsivenessSlider); + } + } else if (sender() == ui->advancedResponsivenessGroupBox) { + ui->basicResponsivenessGroupBox->setChecked(!value); + } +} +void ConfigStabilizationWidget::processLinkedWidgets(QWidget *widget) +{ + if (ui->checkBox_7->isChecked()) { + if (widget == ui->RateRollKp_2) { + ui->RatePitchKp->setValue(ui->RateRollKp_2->value()); + } else if (widget == ui->RateRollKi_2) { + ui->RatePitchKi->setValue(ui->RateRollKi_2->value()); + } else if (widget == ui->RateRollILimit_2) { + ui->RatePitchILimit->setValue(ui->RateRollILimit_2->value()); + } else if (widget == ui->RatePitchKp) { + ui->RateRollKp_2->setValue(ui->RatePitchKp->value()); + } else if (widget == ui->RatePitchKi) { + ui->RateRollKi_2->setValue(ui->RatePitchKi->value()); + } else if (widget == ui->RatePitchILimit) { + ui->RateRollILimit_2->setValue(ui->RatePitchILimit->value()); + } else if (widget == ui->RollRateKd) { + ui->PitchRateKd->setValue(ui->RollRateKd->value()); + } else if (widget == ui->PitchRateKd) { + ui->RollRateKd->setValue(ui->PitchRateKd->value()); + } + } + + if (ui->checkBox_8->isChecked()) { + if (widget == ui->AttitudeRollKp) { + ui->AttitudePitchKp_2->setValue(ui->AttitudeRollKp->value()); + } else if (widget == ui->AttitudeRollKi) { + ui->AttitudePitchKi_2->setValue(ui->AttitudeRollKi->value()); + } else if (widget == ui->AttitudeRollILimit) { + ui->AttitudePitchILimit_2->setValue(ui->AttitudeRollILimit->value()); + } else if (widget == ui->AttitudePitchKp_2) { + ui->AttitudeRollKp->setValue(ui->AttitudePitchKp_2->value()); + } else if (widget == ui->AttitudePitchKi_2) { + ui->AttitudeRollKi->setValue(ui->AttitudePitchKi_2->value()); + } else if (widget == ui->AttitudePitchILimit_2) { + ui->AttitudeRollILimit->setValue(ui->AttitudePitchILimit_2->value()); + } + } + + if (ui->basicResponsivenessGroupBox->isChecked()) { + if (widget == ui->AttitudeResponsivenessSlider) { + ui->ratePitchKp_4->setValue(ui->AttitudeResponsivenessSlider->value()); + } else if (widget == ui->RateResponsivenessSlider) { + ui->ratePitchKi_4->setValue(ui->RateResponsivenessSlider->value()); + } + } +} diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h index 266b59ae9..d728a877b 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h @@ -46,11 +46,18 @@ public: ~ConfigStabilizationWidget(); private: - Ui_StabilizationWidget *m_stabilization; + Ui_StabilizationWidget *ui; QTimer * realtimeUpdates; + + // Milliseconds between automatic 'Instant Updates' + static const int AUTOMATIC_UPDATE_RATE = 500; + +protected slots: + void refreshWidgetsValues(UAVObject *o = NULL); + private slots: - void realtimeUpdatesSlot(int); - void linkCheckBoxes(int value); + void realtimeUpdatesSlot(bool value); + void linkCheckBoxes(bool value); void processLinkedWidgets(QWidget*); }; diff --git a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp index 91ecfdb2e..b279135bb 100644 --- a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp @@ -108,9 +108,3 @@ void ConfigTxPIDWidget::saveSettings() UAVObject *obj = HwSettings::GetInstance(getObjectManager()); saveObjectToSD(obj); } - - -/** - @} - @} - */ diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index f22d84214..af316585a 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -138,8 +138,6 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi // Connect the help pushbutton connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - enableControls(false); - refreshWidgetsValues(); // register widgets for dirty state management @@ -150,8 +148,12 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi addWidget(m_aircraft->accelTime); addWidget(m_aircraft->decelTime); addWidget(m_aircraft->maxAccelSlider); + addWidget(m_aircraft->ffTestBox1); + addWidget(m_aircraft->ffTestBox2); + addWidget(m_aircraft->ffTestBox3); disableMouseWheelEvents(); + updateEnableControls(); } /** diff --git a/ground/openpilotgcs/src/plugins/config/defaultattitude.ui b/ground/openpilotgcs/src/plugins/config/defaultattitude.ui index c191e996c..ebb726ae1 100644 --- a/ground/openpilotgcs/src/plugins/config/defaultattitude.ui +++ b/ground/openpilotgcs/src/plugins/config/defaultattitude.ui @@ -29,11 +29,11 @@ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Attitude / INS calibration</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-weight:600;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">This panel will be updated to provide the relevant controls to let you calibrate your OpenPilot INS or your CopterControl unit, depending on the board which is detected once telemetry is connected and running.</p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"></p></body></html> +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">Attitude Calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt; font-weight:600;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This panel will be updated to provide the relevant controls to let you calibrate your OpenPilot unit, depending on the board which is detected once telemetry is connected and running.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p></body></html>
diff --git a/ground/openpilotgcs/src/plugins/config/defaulthwsettings.ui b/ground/openpilotgcs/src/plugins/config/defaulthwsettings.ui index d1ef7d913..b4272ab22 100644 --- a/ground/openpilotgcs/src/plugins/config/defaulthwsettings.ui +++ b/ground/openpilotgcs/src/plugins/config/defaulthwsettings.ui @@ -25,15 +25,18 @@ + + true + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">Hardware Configuration</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt; font-weight:600;"></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt; font-weight:600;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This panel will be updated to provide the relevant controls to let you configure your hardware once telemetry is connected and running.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p></body></html> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p></body></html> diff --git a/ground/openpilotgcs/src/plugins/config/images/revolution_top.png b/ground/openpilotgcs/src/plugins/config/images/revolution_top.png index a98e7e377..3a6b8fbd6 100644 Binary files a/ground/openpilotgcs/src/plugins/config/images/revolution_top.png and b/ground/openpilotgcs/src/plugins/config/images/revolution_top.png differ diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp index d94281035..0a573adce 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp @@ -4,15 +4,14 @@ #include "manualcontrolsettings.h" #include "gcsreceiver.h" -inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) : +inputChannelForm::inputChannelForm(QWidget *parent, bool showlegend) : ConfigTaskWidget(parent), ui(new Ui::inputChannelForm) { ui->setupUi(this); - - //The first time through the loop, keep the legend. All other times, delete it. - if(!showlegend) - { + + // The first time through the loop, keep the legend. All other times, delete it. + if (!showlegend) { layout()->removeWidget(ui->legend0); layout()->removeWidget(ui->legend1); layout()->removeWidget(ui->legend2); @@ -27,19 +26,18 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) : delete ui->legend4; delete ui->legend5; delete ui->legend6; - } - connect(ui->channelMin,SIGNAL(valueChanged(int)),this,SLOT(minMaxUpdated())); - connect(ui->channelMax,SIGNAL(valueChanged(int)),this,SLOT(minMaxUpdated())); - connect(ui->channelGroup,SIGNAL(currentIndexChanged(int)),this,SLOT(groupUpdated())); - connect(ui->channelNeutral,SIGNAL(valueChanged(int)), this, SLOT(neutralUpdated(int))); + connect(ui->channelMin, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated())); + connect(ui->channelMax, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated())); + connect(ui->channelGroup, SIGNAL(currentIndexChanged(int)), this, SLOT(groupUpdated())); + connect(ui->channelNeutral, SIGNAL(valueChanged(int)), this, SLOT(neutralUpdated(int))); // This is awkward but since we want the UI to be a dropdown but the field is not an enum // it breaks the UAUVObject widget relation of the task gadget. Running the data through // a spin box fixes this - connect(ui->channelNumberDropdown,SIGNAL(currentIndexChanged(int)),this,SLOT(channelDropdownUpdated(int))); - connect(ui->channelNumber,SIGNAL(valueChanged(int)),this,SLOT(channelNumberUpdated(int))); + connect(ui->channelNumberDropdown, SIGNAL(currentIndexChanged(int)), this, SLOT(channelDropdownUpdated(int))); + connect(ui->channelNumber, SIGNAL(valueChanged(int)), this, SLOT(channelNumberUpdated(int))); disableMouseWheelEvents(); } @@ -54,26 +52,28 @@ void inputChannelForm::setName(QString &name) { ui->channelName->setText(name); QFontMetrics metrics(ui->channelName->font()); - int width=metrics.width(name)+5; - foreach(inputChannelForm * form,parent()->findChildren()) - { - if(form==this) + int width = metrics.width(name) + 5; + foreach(inputChannelForm * form, parent()->findChildren()) { + if (form == this) { continue; - if(form->ui->channelName->minimumSize().width()ui->channelName->setMinimumSize(width,0); - else - width=form->ui->channelName->minimumSize().width(); + } + if (form->ui->channelName->minimumSize().width() < width) { + form->ui->channelName->setMinimumSize(width, 0); + } else { + width = form->ui->channelName->minimumSize().width(); + } } - ui->channelName->setMinimumSize(width,0); + ui->channelName->setMinimumSize(width, 0); } /** - * Update the direction of the slider and boundaries - */ + * Update the direction of the slider and boundaries + */ void inputChannelForm::minMaxUpdated() { bool reverse = ui->channelMin->value() > ui->channelMax->value(); - if(reverse) { + + if (reverse) { ui->channelNeutral->setMinimum(ui->channelMax->value()); ui->channelNeutral->setMaximum(ui->channelMin->value()); } else { @@ -91,11 +91,11 @@ void inputChannelForm::neutralUpdated(int newval) } /** - * Update the channel options based on the selected receiver type - * - * I fully admit this is terrible practice to embed data within UI - * like this. Open to suggestions. JC 2011-09-07 - */ + * Update the channel options based on the selected receiver type + * + * I fully admit this is terrible practice to embed data within UI + * like this. Open to suggestions. JC 2011-09-07 + */ void inputChannelForm::groupUpdated() { ui->channelNumberDropdown->clear(); @@ -103,7 +103,7 @@ void inputChannelForm::groupUpdated() quint8 count = 0; - switch(ui->channelGroup->currentIndex()) { + switch (ui->channelGroup->currentIndex()) { case -1: // Nothing selected count = 0; break; @@ -129,24 +129,25 @@ void inputChannelForm::groupUpdated() Q_ASSERT(0); } - for (int i = 0; i < count; i++) - ui->channelNumberDropdown->addItem(QString(tr("Chan %1").arg(i+1))); + for (int i = 0; i < count; i++) { + ui->channelNumberDropdown->addItem(QString(tr("Chan %1").arg(i + 1))); + } ui->channelNumber->setMaximum(count); ui->channelNumber->setMinimum(0); } /** - * Update the dropdown from the hidden control - */ + * Update the dropdown from the hidden control + */ void inputChannelForm::channelDropdownUpdated(int newval) { ui->channelNumber->setValue(newval); } /** - * Update the hidden control from the dropdown - */ + * Update the hidden control from the dropdown + */ void inputChannelForm::channelNumberUpdated(int newval) { ui->channelNumberDropdown->setCurrentIndex(newval); diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index b55974c86..17e9c48cd 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -38,15 +38,11 @@ MixerCurve::MixerCurve(QWidget *parent) : m_mixerUI->setupUi(this); // setup some convienence pointers - m_curve = m_mixerUI->CurveWidget; + m_curve = m_mixerUI->CurveWidget; m_settings = m_mixerUI->CurveSettings; m_mixerUI->SettingsGroup->hide(); - m_curve->showCommands(false); - m_curve->showCommand("Reset", false); - m_curve->showCommand("Popup", false); - m_curve->showCommand("Commands", false); // create our spin delegate m_spinDelegate = new DoubleSpinDelegate(); @@ -54,27 +50,19 @@ MixerCurve::MixerCurve(QWidget *parent) : // set the default mixer type setMixerType(MixerCurve::MIXERCURVE_THROTTLE); - // setup and turn off advanced mode - CommandActivated(); - // paint the ui UpdateCurveUI(); // wire up our signals - connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(CurveTypeChanged())); connect(m_mixerUI->ResetCurve, SIGNAL(clicked()), this, SLOT(ResetCurve())); - connect(m_mixerUI->PopupCurve, SIGNAL(clicked()),this,SLOT(PopupCurve())); + connect(m_mixerUI->PopupCurve, SIGNAL(clicked()), this, SLOT(PopupCurve())); connect(m_mixerUI->GenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve())); connect(m_curve, SIGNAL(curveUpdated()), this, SLOT(UpdateSettingsTable())); - connect(m_curve, SIGNAL(commandActivated(MixerNode*)),this, SLOT(CommandActivated(MixerNode*))); - connect(m_settings, SIGNAL(cellChanged(int,int)), this, SLOT(SettingsTableChanged())); + connect(m_settings, SIGNAL(cellChanged(int, int)), this, SLOT(SettingsTableChanged())); connect(m_mixerUI->CurveMin, SIGNAL(valueChanged(double)), this, SLOT(CurveMinChanged(double))); connect(m_mixerUI->CurveMax, SIGNAL(valueChanged(double)), this, SLOT(CurveMaxChanged(double))); connect(m_mixerUI->CurveStep, SIGNAL(valueChanged(double)), this, SLOT(GenerateCurve())); - - - } MixerCurve::~MixerCurve() @@ -91,27 +79,26 @@ void MixerCurve::setMixerType(MixerCurveType curveType) m_mixerUI->CurveMax->setMaximum(1.0); switch (m_curveType) { - case MixerCurve::MIXERCURVE_THROTTLE: - { - m_mixerUI->SettingsGroup->setTitle("Throttle Curve"); - m_curve->setRange(0.0, 1.0); - m_mixerUI->CurveMin->setMinimum(0.0); - m_mixerUI->CurveMax->setMinimum(0.0); - break; - } - case MixerCurve::MIXERCURVE_PITCH: - { - m_mixerUI->SettingsGroup->setTitle("Pitch Curve"); - m_curve->setRange(-1.0, 1.0); - m_curve->setPositiveColor("#0000aa", "#0000aa"); - m_mixerUI->CurveMin->setMinimum(-1.0); - m_mixerUI->CurveMax->setMinimum(-1.0); - break; - } + case MixerCurve::MIXERCURVE_THROTTLE: + { + m_mixerUI->SettingsGroup->setTitle("Throttle Curve"); + m_curve->setRange(0.0, 1.0); + m_mixerUI->CurveMin->setMinimum(0.0); + m_mixerUI->CurveMax->setMinimum(0.0); + break; + } + case MixerCurve::MIXERCURVE_PITCH: + { + m_mixerUI->SettingsGroup->setTitle("Pitch Curve"); + m_curve->setRange(-1.0, 1.0); + m_mixerUI->CurveMin->setMinimum(-1.0); + m_mixerUI->CurveMax->setMinimum(-1.0); + break; + } } m_spinDelegate->setRange(m_mixerUI->CurveMin->minimum(), m_mixerUI->CurveMax->maximum()); - for (int i=0; isetItemDelegateForRow(i, m_spinDelegate); } @@ -126,43 +113,32 @@ void MixerCurve::ResetCurve() initLinearCurve(MixerCurveWidget::NODE_NUMELEM, getCurveMax(), getCurveMin()); - m_curve->activateCommand("Linear"); - UpdateSettingsTable(); } void MixerCurve::PopupCurve() { - if (!m_curve->isCommandActive("Popup")) { + m_mixerUI->SettingsGroup->show(); + m_mixerUI->PopupCurve->hide(); - m_mixerUI->SettingsGroup->show(); - m_mixerUI->PopupCurve->hide(); + PopupWidget *popup = new PopupWidget(); + popup->popUp(this); - PopupWidget* popup = new PopupWidget(); - popup->popUp(this); - - m_mixerUI->SettingsGroup->hide(); - m_mixerUI->PopupCurve->show(); - m_curve->showCommands(false); - } + m_mixerUI->SettingsGroup->hide(); + m_mixerUI->PopupCurve->show(); } + void MixerCurve::UpdateCurveUI() { - //get the user settings + // get the user settings QString curveType = m_mixerUI->CurveType->currentText(); - m_curve->activateCommand(curveType); - bool cmdsActive = m_curve->isCommandActive("Commands"); - - m_curve->showCommand("StepPlus", cmdsActive && curveType != "Linear"); - m_curve->showCommand("StepMinus", cmdsActive && curveType != "Linear"); - m_curve->showCommand("StepValue", cmdsActive && curveType != "Linear"); m_mixerUI->CurveStep->setMinimum(0.0); m_mixerUI->CurveStep->setMaximum(100.0); m_mixerUI->CurveStep->setSingleStep(1.00); - //set default visible + // set default visible m_mixerUI->minLabel->setVisible(true); m_mixerUI->CurveMin->setVisible(true); m_mixerUI->maxLabel->setVisible(false); @@ -170,8 +146,7 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->stepLabel->setVisible(false); m_mixerUI->CurveStep->setVisible(false); - if ( curveType.compare("Flat")==0) - { + if (curveType.compare("Flat") == 0) { m_mixerUI->minLabel->setVisible(false); m_mixerUI->CurveMin->setVisible(false); m_mixerUI->stepLabel->setVisible(true); @@ -181,13 +156,11 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveStep->setSingleStep(0.01); m_mixerUI->CurveStep->setValue(m_mixerUI->CurveMax->value() / 2); } - if ( curveType.compare("Linear")==0) - { + if (curveType.compare("Linear") == 0) { m_mixerUI->maxLabel->setVisible(true); m_mixerUI->CurveMax->setVisible(true); } - if ( curveType.compare("Step")==0) - { + if (curveType.compare("Step") == 0) { m_mixerUI->maxLabel->setVisible(true); m_mixerUI->CurveMax->setVisible(true); m_mixerUI->stepLabel->setText("Step at"); @@ -196,8 +169,7 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveStep->setMinimum(1.0); } - if ( curveType.compare("Exp")==0) - { + if (curveType.compare("Exp") == 0) { m_mixerUI->maxLabel->setVisible(true); m_mixerUI->CurveMax->setVisible(true); m_mixerUI->stepLabel->setText("Power"); @@ -206,13 +178,12 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveStep->setMinimum(1.0); } - if ( curveType.compare("Log")==0) - { + if (curveType.compare("Log") == 0) { m_mixerUI->maxLabel->setVisible(true); m_mixerUI->CurveMax->setVisible(true); m_mixerUI->stepLabel->setText("Power"); m_mixerUI->stepLabel->setVisible(true); - m_mixerUI->CurveStep->setVisible(true); + m_mixerUI->CurveStep->setVisible(true); m_mixerUI->CurveStep->setMinimum(1.0); } @@ -221,71 +192,62 @@ void MixerCurve::UpdateCurveUI() void MixerCurve::GenerateCurve() { - double scale; - double newValue; + double scale; + double newValue; - //get the user settings - double value1 = getCurveMin(); - double value2 = getCurveMax(); - double value3 = getCurveStep(); + // get the user settings + double value1 = getCurveMin(); + double value2 = getCurveMax(); + double value3 = getCurveStep(); - m_curve->setCommandText("StepValue", QString("%0").arg(value3)); + QString CurveType = m_mixerUI->CurveType->currentText(); - QString CurveType = m_mixerUI->CurveType->currentText(); + QList points; - QList points; + for (int i = 0; i < MixerCurveWidget::NODE_NUMELEM; i++) { + scale = ((double)i / (double)(MixerCurveWidget::NODE_NUMELEM - 1)); - for (int i=0; i* points) + Wrappers for mixercurvewidget. + */ +void MixerCurve::initCurve(const QList *points) { m_curve->setCurve(points); UpdateSettingsTable(); } + QList MixerCurve::getCurve() { return m_curve->getCurve(); } + void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue) { setMin(minValue); @@ -293,42 +255,49 @@ void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue m_curve->initLinearCurve(numPoints, maxValue, minValue); - if (m_spinDelegate) + if (m_spinDelegate) { m_spinDelegate->setRange(minValue, maxValue); + } } -void MixerCurve::setCurve(const QList* points) + +void MixerCurve::setCurve(const QList *points) { m_curve->setCurve(points); UpdateSettingsTable(); } + void MixerCurve::setMin(double value) { - //m_curve->setMin(value); + // m_curve->setMin(value); m_mixerUI->CurveMin->setMinimum(value); } + double MixerCurve::getMin() { return m_curve->getMin(); } + void MixerCurve::setMax(double value) { - //m_curve->setMax(value); + // m_curve->setMax(value); m_mixerUI->CurveMax->setMaximum(value); } + double MixerCurve::getMax() { return m_curve->getMax(); } + double MixerCurve::setRange(double min, double max) { return m_curve->setRange(min, max); } - double MixerCurve::getCurveMin() { return m_mixerUI->CurveMin->value(); } + double MixerCurve::getCurveMax() { return m_mixerUI->CurveMax->value(); @@ -344,11 +313,11 @@ void MixerCurve::UpdateSettingsTable() QList points = m_curve->getCurve(); int ptCnt = points.count(); - for (int i=0; iitem(i, 0); - if (item) - item->setText(QString().sprintf("%.2f",points.at( (ptCnt - 1) - i ))); + for (int i = 0; i < ptCnt; i++) { + QTableWidgetItem *item = m_settings->item(i, 0); + if (item) { + item->setText(QString().sprintf("%.2f", points.at((ptCnt - 1) - i))); + } } } @@ -356,12 +325,12 @@ void MixerCurve::SettingsTableChanged() { QList points; - for (int i=0; i < m_settings->rowCount(); i++) - { - QTableWidgetItem* item = m_settings->item(i, 0); + for (int i = 0; i < m_settings->rowCount(); i++) { + QTableWidgetItem *item = m_settings->item(i, 0); - if (item) + if (item) { points.push_front(item->text().toDouble()); + } } m_mixerUI->CurveMin->setValue(points.first()); @@ -370,59 +339,6 @@ void MixerCurve::SettingsTableChanged() m_curve->setCurve(&points); } -void MixerCurve::CommandActivated(MixerNode* node) -{ - QString name = (node) ? node->getName() : "Reset"; - - if (name == "Reset") { - ResetCurve(); - m_curve->showCommands(false); - } - else if (name == "Commands") { - - } - else if (name == "Popup" ) { - PopupCurve(); - } - else if (name == "Linear") { - m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear")); - } - else if (name == "Log") { - m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Log")); - } - else if (name == "Exp") { - m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Exp")); - } - else if (name == "Flat") { - m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Flat")); - } - else if (name == "Step") { - m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Step")); - } - else if (name == "MinPlus") { - m_mixerUI->CurveMin->stepUp(); - } - else if (name == "MinMinus") { - m_mixerUI->CurveMin->stepDown(); - } - else if (name == "MaxPlus") { - m_mixerUI->CurveMax->stepUp(); - } - else if (name == "MaxMinus"){ - m_mixerUI->CurveMax->stepDown(); - } - else if (name == "StepPlus") { - m_mixerUI->CurveStep->stepUp(); - m_curve->setCommandText("StepValue", QString("%0").arg(getCurveStep())); - } - else if (name == "StepMinus") { - m_mixerUI->CurveStep->stepDown(); - m_curve->setCommandText("StepValue", QString("%0").arg(getCurveStep())); - } - - GenerateCurve(); -} - void MixerCurve::CurveTypeChanged() { // setup the ui for this curvetype @@ -440,7 +356,7 @@ void MixerCurve::CurveMinChanged(double value) void MixerCurve::CurveMaxChanged(double value) { // the max changed so redraw the curve - // mixercurvewidget::setCurve will trim any points above max + // mixercurvewidget::setCurve will trim any points above max QList points = m_curve->getCurve(); points.removeLast(); points.append(value); @@ -452,23 +368,25 @@ void MixerCurve::showEvent(QShowEvent *event) Q_UNUSED(event); m_settings->resizeColumnsToContents(); - m_settings->setColumnWidth(0,(m_settings->width()- m_settings->verticalHeader()->width())); + m_settings->setColumnWidth(0, (m_settings->width() - m_settings->verticalHeader()->width())); - int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount(); - for (int i=0; irowCount(); i++) + int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount(); + for (int i = 0; i < m_settings->rowCount(); i++) { m_settings->setRowHeight(i, h); + } m_curve->showEvent(event); } -void MixerCurve::resizeEvent(QResizeEvent* event) +void MixerCurve::resizeEvent(QResizeEvent *event) { m_settings->resizeColumnsToContents(); - m_settings->setColumnWidth(0,(m_settings->width() - m_settings->verticalHeader()->width())); + m_settings->setColumnWidth(0, (m_settings->width() - m_settings->verticalHeader()->width())); - int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount(); - for (int i=0; irowCount(); i++) + int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount(); + for (int i = 0; i < m_settings->rowCount(); i++) { m_settings->setRowHeight(i, h); + } m_curve->resizeEvent(event); } diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.h b/ground/openpilotgcs/src/plugins/config/mixercurve.h index ef98414bc..58e0c2f8b 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.h @@ -84,7 +84,6 @@ public slots: void UpdateSettingsTable(); private slots: - void CommandActivated(MixerNode* node = 0); void SettingsTableChanged(); void CurveTypeChanged(); void CurveMinChanged(double value); diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.h b/ground/openpilotgcs/src/plugins/config/outputchannelform.h index 873a5ea50..434f9517a 100644 --- a/ground/openpilotgcs/src/plugins/config/outputchannelform.h +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.h @@ -38,7 +38,7 @@ class OutputChannelForm : public ConfigTaskWidget public: explicit OutputChannelForm(const int index, QWidget *parent = NULL, const bool showLegend = false); ~OutputChannelForm(); - friend class ConfigOnputWidget; + friend class ConfigOutputWidget; void setAssignment(const QString &assignment); int index() const; @@ -57,10 +57,10 @@ signals: void channelChanged(int index, int value); private: - Ui::outputChannelForm ui; /// Channel index int m_index; bool m_inChannelTest; + Ui::outputChannelForm ui; private slots: void linkToggled(bool state); diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index 2ecf1ee04..6741c20da 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -6,8 +6,8 @@ 0 0 - 720 - 567 + 643 + 531 @@ -16,10 +16,16 @@ + + true + 0 + + true + Calibration @@ -46,8 +52,8 @@ - 75 - true + 50 + false @@ -132,8 +138,8 @@ - 75 - true + 50 + false @@ -235,8 +241,8 @@ Hint: run this with engines at cruising speed. - 75 - true + 50 + false @@ -288,173 +294,6 @@ Hint: run this with engines at cruising speed.
- - - - QFrame::StyledPanel - - - QFrame::Raised - - - - 3 - - - - - - - - - - 75 - true - - - - #4 Gyro temperature drift calibration - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - Temp: - - - - - - - - 9 - - - - Min - - - - - - - Currently measured temperature on the system. This is actually the -MB temperature, be careful if somehow you know that your INS -temperature is very different from your MB temp... - - - Qt::Horizontal - - - QSlider::TicksBelow - - - - - - - - 9 - - - - Max - - - - - - - - - - - Current drift: - - - - - - - - - - - Saved drift: - - - - - - - - - - - false - - - Start gathering data for temperature drift calibration. -Avoid sudden moves once you have started gathering! - - - Start - - - - - - - false - - - Launch drift measurement based on gathered data. - -TODO: is this necessary? Measurement could be auto updated every second or so, or done when we stop measuring... - - - Measure - - - - - - - false - - - Updates the XYZ drift values into the AHRS (saves to SD) - - - Save - - - - - - - - - - @@ -473,130 +312,420 @@ p, li { white-space: pre-wrap; } <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">Help</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">Step #1 and #2 are really necessary. Steps #3 and #4 will help you achieve the best possible results.</span></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt; font-weight:600;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#1: Multi-Point calibration:</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">Help</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Step #1 and #2 are really necessary. Step #3 will help you achieve the best possible results.</span></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">#1: Multi-Point calibration:</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This calibration will compute the scale for all sensors on the INS. Press &quot;Start&quot; to begin calibration, and follow the instructions which will be displayed here. Note that your HomeLocation must be set first, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#2: Sensor noise calibration:</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">#2: Sensor noise calibration:</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This calibration will compute sensor variance under standard conditions. You can leave your engines running at low to mid throttle to take their vibration into account before pressing &quot;Start&quot;.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#3: Accelerometer bias calibration:</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step will ensure that accelerometer bias is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#4 Gyro temp drift calibration:</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt; font-weight:600;"><br /></p></td></tr></table></body></html> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">#3: Accelerometer bias calibration:</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step will ensure that accelerometer bias is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.</span></p></td></tr></table></body></html> + + true + Settings + + 6 + - - - - 75 - true - + + + + 0 + 0 + - - Attitude Algorithm: + + Attitude Estimation Algorithm + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + + + + + 0 + 0 + + + + Selects the sensor integration algorithm to be used by the Revolution board. + + + + + + + Qt::Vertical + + + QSizePolicy::MinimumExpanding + + + + 20 + 0 + + + + + - - - Selects the sensor integration algorithm to be used by the Revolution board. + + + + 0 + 0 + - - - - - - Qt::Horizontal + + Home Location - - - 40 - 20 - + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - - - - - 75 - true - - - - Home Location: - - - - - - - false - - - Saves the Home Location. This is only enabled -if the Home Location is set, i.e. if the GPS fix is -successful. - -Disabled if there is no GPS fix. - - - Set - - - true - - - buttonGroup - - - - - - - true - - - Clears the HomeLocation: only makes sense if you save -to SD. This will force the INS to use the next GPS fix as the -new home location unless it is in indoor mode. - - - Clear - - - buttonGroup - + + + QLayout::SetDefaultConstraint + + + + + Gravity acceleration: + + + + + + + Latitude: + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + objname:HomeLocation + fieldname:g_e + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + objname:HomeLocation + fieldname:Latitude + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + + + + Altitude: + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + objname:HomeLocation + fieldname:Altitude + + + + + + + + Magnetic field vector: + + + + + + + <html><head/><body><p>This information must be set to enable calibration the Revolution controllers sensors. <br/>Set home location using context menu in the map widget.</p></body></html> + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + objname:HomeLocation + fieldname:Longitude + + + + + + + + false + + + Is Set + + + true + + + + objname:HomeLocation + fieldname:Set + + + + + + + + Longitude: + + + + + + + + 0 + 0 + + + + Clear + + + + + + + Qt::Vertical + + + + 20 + 0 + + + + + + + + + Rotate virtual attitude relative to board + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Roll + + + Qt::AlignCenter + + + + + + + -180 + + + 180 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + -180 + + + 180 + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Yaw + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Pitch + + + Qt::AlignCenter + + + + + + + -90 + + + 90 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + Qt::Vertical + + QSizePolicy::Expanding + 20 - 40 + 100 @@ -716,7 +845,4 @@ specific calibration button on top of the screen. - - - diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index a133279db..7bce2f777 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,8 +6,8 @@ 0 0 - 965 - 687 + 1075 + 834 @@ -589,6 +589,9 @@ QFrame::NoFrame + + QFrame::Sunken + 0 @@ -600,17 +603,2030 @@ 0 0 - 937 - 595 + 1045 + 751 - + + + 0 + 0 + + + - 12 + 9 - - 12 + + 9 + + + + + + + Responsiveness + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + true + + + + 12 + + + + + + 0 + 0 + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:6 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + QGroupBox{border: 0px;} + + + + + + true + + + + 0 + + + 0 + + + 0 + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 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(14, 200, 14, 255), stop:0.78607 rgba(6, 150, 6 , 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Snappy + + + Qt::AlignCenter + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + 10 + + + 255 + + + 115 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + 100 + + + 800 + + + 400 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + 100 + + + 800 + + + 400 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 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(34, 34, 200, 255), stop:0.78607 rgba(6, 6, 150, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Moderate + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 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(200, 14, 14, 255), stop:0.78607 rgba(160 , 6, 6 , 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Insane + + + Qt::AlignCenter + + + + + + + + 78 + 16 + + + + Attitude mode + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 78 + 16 + + + + Rate mode + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 10 + + + 255 + + + 1 + + + 115 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + 100 + + + 800 + + + 400 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 78 + 16 + + + + Rate mode yaw + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + 100 + + + 800 + + + 400 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + + @@ -1163,7 +3179,7 @@ false - + QGroupBox{border: 0px;} @@ -1172,569 +3188,15 @@ true - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 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; - - - Roll - - - Qt::AlignCenter - - - + + 0 + + + 0 + + + 0 + @@ -1748,555 +3210,18 @@ border-radius: 5; - - - - - 0 - 0 - + + + + Qt::Horizontal - + - 0 - 16 + 40 + 20 - - - - - - - 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; - - - Pitch - - - Qt::AlignCenter - - + @@ -2861,45 +3786,557 @@ border-radius: 5; - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - + + - + 0 0 - 78 + 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; - Proportional + Pitch - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + Qt::AlignCenter - + @@ -2953,7 +4390,7 @@ Then lower the value by 5 or so. - + @@ -2992,97 +4429,32 @@ Then lower the value by 5 or so. - - + + - + 0 0 - 0 - 25 + 78 + 16 - - Qt::StrongFocus - - - Slowly raise Proportional until you start seeing clear oscillations when you fly. -Then lower the value by 5 or so. - - - 100 + + Proportional - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kp - haslimits:yes - scale:0.0001 - buttongroup:1,10 - + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - Slowly raise Proportional until you start seeing clear oscillations when you fly. -Then lower the value by 5 or so. - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kp - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - + @@ -3133,7 +4505,97 @@ Then lower the value by 5 or so. - + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kp + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kp + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + @@ -3172,26 +4634,7 @@ Then lower the value by 5 or so. - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - + @@ -3242,7 +4685,26 @@ value as the Kp. - + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + @@ -3281,59 +4743,8 @@ value as the Kp. - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Integral at roughly the same -value as the Kp. - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Ki - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - + + 50 @@ -3362,7 +4773,7 @@ value as the Kp. objname:StabilizationSettings - fieldname:PitchRatePID + fieldname:YawRatePID element:Ki haslimits:yes scale:0.0001 @@ -3371,7 +4782,7 @@ value as the Kp. - + @@ -3422,8 +4833,59 @@ value as the Kp. - - + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Ki + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + 50 @@ -3452,7 +4914,7 @@ value as the Kp. objname:StabilizationSettings - fieldname:YawRatePID + fieldname:PitchRatePID element:Ki haslimits:yes scale:0.0001 @@ -3461,6 +4923,569 @@ value as the Kp. + + + + + 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; + + + Roll + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + @@ -4516,7 +6541,7 @@ value as the Kp. false - + QGroupBox{border: 0px;} @@ -4525,6 +6550,15 @@ value as the Kp. true + + 0 + + + 0 + + + 0 + @@ -6770,71 +8804,118 @@ border-radius: 5; - - - - 0 - 0 - - - - - 0 - 62 - - - - - - - Integral - - - - 12 - - - - - - 0 - 0 - + + + + + + 0 + 0 + + + + + 0 + 62 + + + + + + + Integral + + + + 12 - - - 300 - 20 - - - - When the throttle is low, zero the intergral term to prevent intergral wind-up - - - - - - Zero the integral when throttle is low - - - - objname:StabilizationSettings - fieldname:LowThrottleZeroIntegral - - - - - - + + + + + 0 + 0 + + + + + 300 + 20 + + + + When the throttle is low, zero the intergral term to prevent intergral wind-up + + + + + + Zero the integral when throttle is low + + + + objname:StabilizationSettings + fieldname:LowThrottleZeroIntegral + + + + + + + + + + + + 0 + 0 + + + + + 0 + 60 + + + + Instant Update + + + + + + + 0 + 0 + + + + + 136 + 20 + + + + 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. + + + + + + Update flight controller in real time + + + + + + + Qt::Vertical - - QSizePolicy::Expanding - 20 @@ -6937,17 +9018,3357 @@ border-radius: 5; 0 0 - 540 - 663 + 1045 + 751 true - - - 12 - + + + + + + 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 + + + + + + + + Responsiveness + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + true + + + false + + + + 12 + + + 6 + + + + + Qt::Horizontal + + + QSizePolicy::Expanding + + + + 632 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup: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 + + + 0 + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 255.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:PitchMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 128 + 16 + + + + + 16777215 + 16777215 + + + + + + + Max rate attitude (deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 255.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:YawMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 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; + + + Yaw + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + 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; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Attitude mode response (deg) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 140 + 16 + + + + + + + + + 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; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 255.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + Rate mode response (deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + + 20 + 20 + + + + + + + + + + @@ -7483,7 +12904,7 @@ border-radius: 5; - Rate Stabization Coefficients (Inner Loop) + Rate Stabilization (Inner Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -7498,16 +12919,6 @@ border-radius: 5; 6 - - - - - - - Link Roll and Pitch - - - @@ -7521,6 +12932,16 @@ border-radius: 5; + + + + + + + Link Roll and Pitch + + + @@ -7992,7 +13413,7 @@ border-radius: 5; false - + QGroupBox{border: 0px;} @@ -8004,8 +13425,11 @@ border-radius: 5; 0 + + 0 + - 9 + 0 @@ -10808,7 +16232,7 @@ Then lower the value by 20% or so. false - Attitude Stabization Coefficients (Outer Loop) + Attitude Stabilization (Outer Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -11317,7 +16741,7 @@ Then lower the value by 20% or so. false - + QGroupBox{border: 0px;} @@ -11329,6 +16753,12 @@ Then lower the value by 20% or so. 0 + + 0 + + + 0 + @@ -13401,9 +18831,9 @@ border-radius: 5; - + - + 0 0 @@ -13411,598 +18841,15 @@ border-radius: 5; 0 - 0 + 60 - - - 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 - - - - - - - Stick Range and Limits + Instant Update - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - 12 - - - 6 - - - - - Qt::Horizontal - - - QSizePolicy::Expanding - - - - 632 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:6 - - - - - - + + + 0 @@ -14011,2721 +18858,19 @@ border-radius: 5; - 0 - 140 + 136 + 20 - - - - - - - 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 + + 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. - - + + Update flight controller in real time - - true - - - - 0 - - - 0 - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:PitchMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 128 - 16 - - - - - 16777215 - 16777215 - - - - - - - Max rate attitude (deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Roll - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:YawMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Pitch - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 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; - - - Yaw - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - 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; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Full stick angle (deg) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Pitch - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 140 - 16 - - - - - - - - - 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; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Roll - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - QAbstractSpinBox::UpDownArrows - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:RollMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - Full stick rate (deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - - 20 - 20 - - - - - @@ -16860,13 +19005,16 @@ border-radius: 5; 0 0 - 802 - 607 + 1045 + 751 + + 9 + - 12 + 9 @@ -16945,12 +19093,24 @@ border-radius: 5; + + QGroupBox{border: 0px;} + true - - 12 + + 0 + + + 9 + + + 0 + + + 0 @@ -19782,6 +21942,9 @@ border-radius: 5; + + QGroupBox{border: 0px;} + @@ -19789,8 +21952,17 @@ border-radius: 5; true - - 12 + + 0 + + + 9 + + + 0 + + + 0 @@ -22921,7 +25093,7 @@ border-radius: 5; false - + QGroupBox{border: 0px;} @@ -22930,8 +25102,17 @@ border-radius: 5; true - - 12 + + 0 + + + 9 + + + 0 + + + 0 @@ -24815,7 +26996,7 @@ border-radius: 5; - Real Time Updates + Instant Update @@ -24833,14 +27014,13 @@ border-radius: 5; - If you check this, the GCS will udpate the stabilization factors -automatically every 300ms, which will help for fast tuning. + 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. - Update in real time + Update flight controller in real time @@ -25101,7 +27281,6 @@ Useful if you have accidentally changed some settings. RollRateKd PitchRateKd YawRateKd - scrollArea pushButton_2 AttitudeRollKp AttitudePitchKp_2 diff --git a/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml b/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml index 98ccf4ef3..1fe8934cf 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml +++ b/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml @@ -38,9 +38,7 @@ ** ****************************************************************************/ - import QtQuick 1.1 - import QtWebKit 1.0 - + import QtQuick 1.1 // This is a tabbed pane element. Add a nested Rectangle to add a tab. TabWidget { diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp index d9b33b185..ec7c01113 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp @@ -33,52 +33,47 @@ #include ScopeGadget::ScopeGadget(QString classId, ScopeGadgetWidget *widget, QWidget *parent) : - IUAVGadget(classId, parent), - m_widget(widget), - configLoaded(false) + IUAVGadget(classId, parent), + m_widget(widget), + configLoaded(false) +{} + +void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration *config) { - -} - -void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config) -{ - - ScopeGadgetConfiguration *sgConfig = qobject_cast(config); - ScopeGadgetWidget* widget = qobject_cast(m_widget); + ScopeGadgetConfiguration *sgConfig = qobject_cast(config); + ScopeGadgetWidget *widget = qobject_cast(m_widget); widget->setXWindowSize(sgConfig->dataSize()); widget->setRefreshInterval(sgConfig->refreshInterval()); - if(sgConfig->plotType() == SequentialPlot ) + if (sgConfig->plotType() == SequentialPlot) { widget->setupSequentialPlot(); - else if(sgConfig->plotType() == ChronoPlot) + } else if (sgConfig->plotType() == ChronoPlot) { widget->setupChronoPlot(); - // else if(sgConfig->plotType() == UAVObjectPlot) - // widget->setupUAVObjectPlot(); + } - foreach (PlotCurveConfiguration* plotCurveConfig, sgConfig->plotCurveConfigs()) { - - QString uavObject = plotCurveConfig->uavObject; - QString uavField = plotCurveConfig->uavField; + foreach(PlotCurveConfiguration * plotCurveConfig, sgConfig->plotCurveConfigs()) { + QString uavObject = plotCurveConfig->uavObject; + QString uavField = plotCurveConfig->uavField; int scale = plotCurveConfig->yScalePower; int mean = plotCurveConfig->yMeanSamples; QString mathFunction = plotCurveConfig->mathFunction; QRgb color = plotCurveConfig->color; - + bool antialiased = plotCurveConfig->drawAntialiased; widget->addCurvePlot( - uavObject, - uavField, - scale, - mean, - mathFunction, - QPen( QBrush(QColor(color),Qt::SolidPattern), -// (qreal)2, - (qreal)1, - Qt::SolidLine, - Qt::SquareCap, - Qt::BevelJoin) - ); - } + uavObject, + uavField, + scale, + mean, + mathFunction, + QPen(QBrush(QColor(color), Qt::SolidPattern), + (qreal)1, + Qt::SolidLine, + Qt::SquareCap, + Qt::BevelJoin), + antialiased + ); + } widget->setLoggingEnabled(sgConfig->getLoggingEnabled()); widget->setLoggingNewFileOnConnect(sgConfig->getLoggingNewFileOnConnect()); @@ -87,14 +82,13 @@ void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config) widget->csvLoggingStop(); widget->csvLoggingSetName(sgConfig->name()); widget->csvLoggingStart(); - } /** - Scope gadget destructor: should delete the associated - scope gadget widget too! - */ + Scope gadget destructor: should delete the associated + scope gadget widget too! + */ ScopeGadget::~ScopeGadget() { - delete m_widget; + delete m_widget; } diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp index 57b1c134f..cc1095cfc 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp @@ -27,75 +27,63 @@ #include "scopegadgetconfiguration.h" -ScopeGadgetConfiguration::ScopeGadgetConfiguration(QString classId, QSettings* qSettings, QObject *parent) : - IUAVGadgetConfiguration(classId, parent), - m_plotType((int)ChronoPlot), - m_dataSize(60), - m_refreshInterval(1000), - m_mathFunctionType(0) +ScopeGadgetConfiguration::ScopeGadgetConfiguration(QString classId, QSettings *qSettings, QObject *parent) : + IUAVGadgetConfiguration(classId, parent), + m_plotType((int)ChronoPlot), + m_dataSize(60), + m_refreshInterval(1000), + m_mathFunctionType(0) { uint currentStreamVersion = 0; int plotCurveCount = 0; - //if a saved configuration exists load it - if(qSettings != 0) { + // If a saved configuration exists load it + if (qSettings != 0) { currentStreamVersion = qSettings->value("configurationStreamVersion").toUInt(); - if(currentStreamVersion != m_configurationStreamVersion) + if (currentStreamVersion != m_configurationStreamVersion) { return; + } - m_plotType = qSettings->value("plotType").toInt(); - m_dataSize = qSettings->value("dataSize").toInt(); + m_plotType = qSettings->value("plotType").toInt(); + m_dataSize = qSettings->value("dataSize").toInt(); m_refreshInterval = qSettings->value("refreshInterval").toInt(); - plotCurveCount = qSettings->value("plotCurveCount").toInt(); - - for(int plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) - { - QString uavObject; - QString uavField; - QRgb color; + plotCurveCount = qSettings->value("plotCurveCount").toInt(); + for (int plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) { qSettings->beginGroup(QString("plotCurve") + QString().number(plotDatasLoadIndex)); - PlotCurveConfiguration* plotCurveConf = new PlotCurveConfiguration(); - uavObject = qSettings->value("uavObject").toString(); - plotCurveConf->uavObject = uavObject; - uavField = qSettings->value("uavField").toString(); - plotCurveConf->uavField = uavField; - color = qSettings->value("color").value(); - plotCurveConf->color = color; - plotCurveConf->yScalePower = qSettings->value("yScalePower").toInt(); + PlotCurveConfiguration *plotCurveConf = new PlotCurveConfiguration(); + plotCurveConf->uavObject = qSettings->value("uavObject").toString(); + plotCurveConf->uavField = qSettings->value("uavField").toString(); + plotCurveConf->color = qSettings->value("color").value(); + plotCurveConf->yScalePower = qSettings->value("yScalePower").toInt(); plotCurveConf->mathFunction = qSettings->value("mathFunction").toString(); - plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples").toInt(); - - if (!plotCurveConf->yMeanSamples) plotCurveConf->yMeanSamples = 1; // fallback for backward compatibility with earlier versions //IS THIS STILL NECESSARY? - + plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples", 1).toInt(); + plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples", 1).toInt(); + plotCurveConf->drawAntialiased = qSettings->value("drawAntialiased", true).toBool(); plotCurveConf->yMinimum = qSettings->value("yMinimum").toDouble(); plotCurveConf->yMaximum = qSettings->value("yMaximum").toDouble(); - - m_PlotCurveConfigs.append(plotCurveConf); + m_plotCurveConfigs.append(plotCurveConf); qSettings->endGroup(); } - m_LoggingEnabled = qSettings->value("LoggingEnabled").toBool(); - m_LoggingNewFileOnConnect = qSettings->value("LoggingNewFileOnConnect").toBool(); - m_LoggingPath = qSettings->value("LoggingPath").toString(); - + m_loggingEnabled = qSettings->value("LoggingEnabled").toBool(); + m_loggingNewFileOnConnect = qSettings->value("LoggingNewFileOnConnect").toBool(); + m_loggingPath = qSettings->value("LoggingPath").toString(); } } void ScopeGadgetConfiguration::clearPlotData() { - PlotCurveConfiguration* poltCurveConfig; + PlotCurveConfiguration *plotCurveConfig; - while(m_PlotCurveConfigs.size() > 0) - { - poltCurveConfig = m_PlotCurveConfigs.first(); - m_PlotCurveConfigs.pop_front(); - - delete poltCurveConfig; + while (m_plotCurveConfigs.size() > 0) { + plotCurveConfig = m_plotCurveConfigs.first(); + m_plotCurveConfigs.pop_front(); + delete plotCurveConfig; } } @@ -105,40 +93,38 @@ void ScopeGadgetConfiguration::clearPlotData() */ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone() { - int plotCurveCount = 0; + int plotCurveCount = 0; int plotDatasLoadIndex = 0; ScopeGadgetConfiguration *m = new ScopeGadgetConfiguration(this->classId()); - m->setPlotType( m_plotType); - m->setDataSize( m_dataSize); - m->setMathFunctionType( m_mathFunctionType); - m->setRefreashInterval( m_refreshInterval); - plotCurveCount = m_PlotCurveConfigs.size(); + m->setPlotType(m_plotType); + m->setDataSize(m_dataSize); + m->setMathFunctionType(m_mathFunctionType); + m->setRefreashInterval(m_refreshInterval); - for(plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) - { - PlotCurveConfiguration* currentPlotCurveConf = m_PlotCurveConfigs.at(plotDatasLoadIndex); + plotCurveCount = m_plotCurveConfigs.size(); - PlotCurveConfiguration* newPlotCurveConf = new PlotCurveConfiguration(); - newPlotCurveConf->uavObject = currentPlotCurveConf->uavObject; - newPlotCurveConf->uavField = currentPlotCurveConf->uavField; - newPlotCurveConf->color = currentPlotCurveConf->color; - newPlotCurveConf->yScalePower = currentPlotCurveConf->yScalePower; + for (plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) { + PlotCurveConfiguration *currentPlotCurveConf = m_plotCurveConfigs.at(plotDatasLoadIndex); + + PlotCurveConfiguration *newPlotCurveConf = new PlotCurveConfiguration(); + newPlotCurveConf->uavObject = currentPlotCurveConf->uavObject; + newPlotCurveConf->uavField = currentPlotCurveConf->uavField; + newPlotCurveConf->color = currentPlotCurveConf->color; + newPlotCurveConf->yScalePower = currentPlotCurveConf->yScalePower; newPlotCurveConf->yMeanSamples = currentPlotCurveConf->yMeanSamples; newPlotCurveConf->mathFunction = currentPlotCurveConf->mathFunction; - - newPlotCurveConf->yMinimum = currentPlotCurveConf->yMinimum; - newPlotCurveConf->yMaximum = currentPlotCurveConf->yMaximum; + newPlotCurveConf->drawAntialiased = currentPlotCurveConf->drawAntialiased; + newPlotCurveConf->yMinimum = currentPlotCurveConf->yMinimum; + newPlotCurveConf->yMaximum = currentPlotCurveConf->yMaximum; m->addPlotCurveConfig(newPlotCurveConf); } - m->setLoggingEnabled(m_LoggingEnabled); - m->setLoggingNewFileOnConnect(m_LoggingNewFileOnConnect); - m->setLoggingPath(m_LoggingPath); - - + m->setLoggingEnabled(m_loggingEnabled); + m->setLoggingNewFileOnConnect(m_loggingNewFileOnConnect); + m->setLoggingPath(m_loggingPath); return m; } @@ -148,9 +134,9 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone() * Saves a configuration. //REDEFINES saveConfig CHILD BEHAVIOR? * */ -void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const { - - int plotCurveCount = m_PlotCurveConfigs.size(); +void ScopeGadgetConfiguration::saveConfig(QSettings *qSettings) const +{ + int plotCurveCount = m_plotCurveConfigs.size(); int plotDatasLoadIndex = 0; qSettings->setValue("configurationStreamVersion", m_configurationStreamVersion); @@ -159,35 +145,33 @@ void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const { qSettings->setValue("refreshInterval", m_refreshInterval); qSettings->setValue("plotCurveCount", plotCurveCount); - for(plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) - { + for (plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) { qSettings->beginGroup(QString("plotCurve") + QString().number(plotDatasLoadIndex)); - PlotCurveConfiguration* plotCurveConf = m_PlotCurveConfigs.at(plotDatasLoadIndex); - qSettings->setValue("uavObject", plotCurveConf->uavObject); - qSettings->setValue("uavField", plotCurveConf->uavField); - qSettings->setValue("color", plotCurveConf->color); - qSettings->setValue("mathFunction", plotCurveConf->mathFunction); - qSettings->setValue("yScalePower", plotCurveConf->yScalePower); - qSettings->setValue("yMeanSamples", plotCurveConf->yMeanSamples); - qSettings->setValue("yMinimum", plotCurveConf->yMinimum); - qSettings->setValue("yMaximum", plotCurveConf->yMaximum); + PlotCurveConfiguration *plotCurveConf = m_plotCurveConfigs.at(plotDatasLoadIndex); + qSettings->setValue("uavObject", plotCurveConf->uavObject); + qSettings->setValue("uavField", plotCurveConf->uavField); + qSettings->setValue("color", plotCurveConf->color); + qSettings->setValue("mathFunction", plotCurveConf->mathFunction); + qSettings->setValue("yScalePower", plotCurveConf->yScalePower); + qSettings->setValue("yMeanSamples", plotCurveConf->yMeanSamples); + qSettings->setValue("yMinimum", plotCurveConf->yMinimum); + qSettings->setValue("yMaximum", plotCurveConf->yMaximum); + qSettings->setValue("drawAntialiased", plotCurveConf->drawAntialiased); qSettings->endGroup(); } - qSettings->setValue("LoggingEnabled", m_LoggingEnabled); - qSettings->setValue("LoggingNewFileOnConnect", m_LoggingNewFileOnConnect); - qSettings->setValue("LoggingPath", m_LoggingPath); - - + qSettings->setValue("LoggingEnabled", m_loggingEnabled); + qSettings->setValue("LoggingNewFileOnConnect", m_loggingNewFileOnConnect); + qSettings->setValue("LoggingPath", m_loggingPath); } -void ScopeGadgetConfiguration::replacePlotCurveConfig(QList newPlotCurveConfigs) +void ScopeGadgetConfiguration::replacePlotCurveConfig(QList newPlotCurveConfigs) { clearPlotData(); - m_PlotCurveConfigs.append(newPlotCurveConfigs); + m_plotCurveConfigs.append(newPlotCurveConfigs); } ScopeGadgetConfiguration::~ScopeGadgetConfiguration() diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h index 5fcb488e2..924a6786c 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h @@ -35,66 +35,117 @@ using namespace Core; -struct PlotCurveConfiguration -{ +struct PlotCurveConfiguration { QString uavObject; QString uavField; - int yScalePower; //This is the power to which each value must be raised - QRgb color; - int yMeanSamples; + int yScalePower; // This is the power to which each value must be raised + QRgb color; + int yMeanSamples; QString mathFunction; - double yMinimum; - double yMaximum; + double yMinimum; + double yMaximum; + bool drawAntialiased; }; -class ScopeGadgetConfiguration : public IUAVGadgetConfiguration -{ +class ScopeGadgetConfiguration : public IUAVGadgetConfiguration { Q_OBJECT public: - explicit ScopeGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); + explicit ScopeGadgetConfiguration(QString classId, QSettings *qSettings = 0, QObject *parent = 0); ~ScopeGadgetConfiguration(); - //configuration setter functions - void setPlotType(int value){m_plotType = value;} - void setMathFunctionType(int value){m_mathFunctionType = value;} - void setDataSize(int value){m_dataSize = value;} - void setRefreashInterval(int value){m_refreshInterval = value;} - void addPlotCurveConfig(PlotCurveConfiguration* value){m_PlotCurveConfigs.append(value);} - void replacePlotCurveConfig(QList m_PlotCurveConfigs); + // configuration setter functions + void setPlotType(int value) + { + m_plotType = value; + } + void setMathFunctionType(int value) + { + m_mathFunctionType = value; + } + void setDataSize(int value) + { + m_dataSize = value; + } + void setRefreashInterval(int value) + { + m_refreshInterval = value; + } + void addPlotCurveConfig(PlotCurveConfiguration *value) + { + m_plotCurveConfigs.append(value); + } + void replacePlotCurveConfig(QList m_plotCurveConfigs); - //configurations getter functions - int plotType(){return m_plotType;} - int mathFunctionType(){return m_mathFunctionType;} - int dataSize(){return m_dataSize;} - int refreshInterval(){return m_refreshInterval;} - QList plotCurveConfigs(){return m_PlotCurveConfigs;} + // Configurations getter functions + int plotType() + { + return m_plotType; + } + int mathFunctionType() + { + return m_mathFunctionType; + } + int dataSize() + { + return m_dataSize; + } + int refreshInterval() + { + return m_refreshInterval; + } + QList plotCurveConfigs() + { + return m_plotCurveConfigs; + } - void saveConfig(QSettings* settings) const; //THIS SEEMS TO BE UNUSED + void saveConfig(QSettings *settings) const; // THIS SEEMS TO BE UNUSED IUAVGadgetConfiguration *clone(); - bool getLoggingEnabled(){return m_LoggingEnabled;}; - bool getLoggingNewFileOnConnect(){return m_LoggingNewFileOnConnect;}; - QString getLoggingPath(){return m_LoggingPath;}; - void setLoggingEnabled(bool value){m_LoggingEnabled=value;}; - void setLoggingNewFileOnConnect(bool value){m_LoggingNewFileOnConnect=value;}; - void setLoggingPath(QString value){m_LoggingPath=value;}; + bool getLoggingEnabled() + { + return m_loggingEnabled; + } + bool getLoggingNewFileOnConnect() + { + return m_loggingNewFileOnConnect; + } + QString getLoggingPath() + { + return m_loggingPath; + } + void setLoggingEnabled(bool value) + { + m_loggingEnabled = value; + } + void setLoggingNewFileOnConnect(bool value) + { + m_loggingNewFileOnConnect = value; + } + void setLoggingPath(QString value) + { + m_loggingPath = value; + } private: - static const uint m_configurationStreamVersion = 1000;//Increment this if the stream format is not compatible with previous versions. This would cause existing configs to be discarded. - int m_plotType; //The type of the plot - int m_dataSize; //The size of the data buffer to render in the curve plot - int m_refreshInterval; //The interval to replot the curve widget. The data buffer is refresh as the data comes in. - int m_mathFunctionType; //The type of math function to be used in the scope analysis - QList m_PlotCurveConfigs; + // Increment this if the stream format is not compatible with previous versions. This would cause existing configs to be discarded. + static const uint m_configurationStreamVersion = 1000; + // The type of the plot + int m_plotType; + // The size of the data buffer to render in the curve plot + int m_dataSize; + // The interval to replot the curve widget. The data buffer is refresh as the data comes in. + int m_refreshInterval; + // The type of math function to be used in the scope analysis + int m_mathFunctionType; + QList m_plotCurveConfigs; void clearPlotData(); - bool m_LoggingEnabled; - bool m_LoggingNewFileOnConnect; - QString m_LoggingPath; - + bool m_loggingEnabled; + bool m_loggingNewFileOnConnect; + QString m_loggingPath; }; #endif // SCOPEGADGETCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp index 06111931f..e0c0a0143 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp @@ -36,96 +36,98 @@ ScopeGadgetOptionsPage::ScopeGadgetOptionsPage(ScopeGadgetConfiguration *config, QObject *parent) : - IOptionsPage(parent), - m_config(config) + IOptionsPage(parent), + m_config(config) { - //nothing to do here... + // nothing to do here... } -//creates options page widget (uses the UI file) -QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent) +// creates options page widget (uses the UI file) +QWidget *ScopeGadgetOptionsPage::createPage(QWidget *parent) { Q_UNUSED(parent); options_page = new Ui::ScopeGadgetOptionsPage(); - //main widget + // main widget QWidget *optionsPageWidget = new QWidget; - //main layout + // main layout options_page->setupUi(optionsPageWidget); - options_page->cmbPlotType->addItem("Sequential Plot",""); - options_page->cmbPlotType->addItem("Chronological Plot",""); + options_page->cmbPlotType->addItem("Sequential Plot", ""); + options_page->cmbPlotType->addItem("Chronological Plot", ""); // Fills the combo boxes for the UAVObjects ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); - QList< QList > objList = objManager->getDataObjects(); - foreach (QList list, objList) { - foreach (UAVDataObject* obj, list) { + QList< QList > objList = objManager->getDataObjects(); + foreach(QList list, objList) { + foreach(UAVDataObject * obj, list) { options_page->cmbUAVObjects->addItem(obj->getName()); } } - //Connect signals to slots cmbUAVObjects.currentIndexChanged + // Connect signals to slots cmbUAVObjects.currentIndexChanged connect(options_page->cmbUAVObjects, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_cmbUAVObjects_currentIndexChanged(QString))); options_page->mathFunctionComboBox->addItem("None"); options_page->mathFunctionComboBox->addItem("Boxcar average"); options_page->mathFunctionComboBox->addItem("Standard deviation"); - if(options_page->cmbUAVObjects->currentIndex() >= 0) + if (options_page->cmbUAVObjects->currentIndex() >= 0) { on_cmbUAVObjects_currentIndexChanged(options_page->cmbUAVObjects->currentText()); + } options_page->cmbScale->addItem("10^-9", -9); options_page->cmbScale->addItem("10^-6", -6); - options_page->cmbScale->addItem("10^-5",-5); - options_page->cmbScale->addItem("10^-4",-4); - options_page->cmbScale->addItem("10^-3",-3); - options_page->cmbScale->addItem("10^-2",-2); - options_page->cmbScale->addItem("10^-1",-1); - options_page->cmbScale->addItem("1",0); - options_page->cmbScale->addItem("10^1",1); - options_page->cmbScale->addItem("10^2",2); - options_page->cmbScale->addItem("10^3",3); - options_page->cmbScale->addItem("10^4",4); - options_page->cmbScale->addItem("10^5",5); - options_page->cmbScale->addItem("10^6",6); - options_page->cmbScale->addItem("10^9",9); - options_page->cmbScale->addItem("10^12",12); + options_page->cmbScale->addItem("10^-5", -5); + options_page->cmbScale->addItem("10^-4", -4); + options_page->cmbScale->addItem("10^-3", -3); + options_page->cmbScale->addItem("10^-2", -2); + options_page->cmbScale->addItem("10^-1", -1); + options_page->cmbScale->addItem("1", 0); + options_page->cmbScale->addItem("10^1", 1); + options_page->cmbScale->addItem("10^2", 2); + options_page->cmbScale->addItem("10^3", 3); + options_page->cmbScale->addItem("10^4", 4); + options_page->cmbScale->addItem("10^5", 5); + options_page->cmbScale->addItem("10^6", 6); + options_page->cmbScale->addItem("10^9", 9); + options_page->cmbScale->addItem("10^12", 12); options_page->cmbScale->setCurrentIndex(7); - //Set widget values from settings + // Set widget values from settings options_page->cmbPlotType->setCurrentIndex(m_config->plotType()); options_page->mathFunctionComboBox->setCurrentIndex(m_config->mathFunctionType()); options_page->spnDataSize->setValue(m_config->dataSize()); options_page->spnRefreshInterval->setValue(m_config->refreshInterval()); - //add the configured curves - foreach (PlotCurveConfiguration* plotData, m_config->plotCurveConfigs()) { - + // add the configured curves + foreach(PlotCurveConfiguration * plotData, m_config->plotCurveConfigs()) { QString uavObject = plotData->uavObject; QString uavField = plotData->uavField; int scale = plotData->yScalePower; int mean = plotData->yMeanSamples; QString mathFunction = plotData->mathFunction; QVariant varColor = plotData->color; + bool antialiased = plotData->drawAntialiased; - addPlotCurveConfig(uavObject,uavField,scale,mean,mathFunction,varColor); + addPlotCurveConfig(uavObject, uavField, scale, mean, mathFunction, varColor, antialiased); } - if(m_config->plotCurveConfigs().count() > 0) + if (m_config->plotCurveConfigs().count() > 0) { options_page->lstCurves->setCurrentRow(0, QItemSelectionModel::ClearAndSelect); + } connect(options_page->btnAddCurve, SIGNAL(clicked()), this, SLOT(on_btnAddCurve_clicked())); connect(options_page->btnRemoveCurve, SIGNAL(clicked()), this, SLOT(on_btnRemoveCurve_clicked())); connect(options_page->lstCurves, SIGNAL(currentRowChanged(int)), this, SLOT(on_lstCurves_currentRowChanged(int))); connect(options_page->btnColor, SIGNAL(clicked()), this, SLOT(on_btnColor_clicked())); connect(options_page->mathFunctionComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(on_mathFunctionComboBox_currentIndexChanged(int))); - connect(options_page->spnRefreshInterval, SIGNAL(valueChanged(int )), this, SLOT(on_spnRefreshInterval_valueChanged(int))); + connect(options_page->spnRefreshInterval, SIGNAL(valueChanged(int)), this, SLOT(on_spnRefreshInterval_valueChanged(int))); setYAxisWidgetFromPlotCurve(); - //logging path setup + // logging path setup options_page->LoggingPath->setExpectedKind(Utils::PathChooser::Directory); options_page->LoggingPath->setPromptDialogTitle(tr("Choose Logging Directory")); options_page->LoggingPath->setPath(m_config->getLoggingPath()); @@ -134,89 +136,91 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent) connect(options_page->LoggingEnable, SIGNAL(clicked()), this, SLOT(on_loggingEnable_clicked())); on_loggingEnable_clicked(); - //Disable mouse wheel events - foreach( QSpinBox * sp, findChildren() ) { - sp->installEventFilter( this ); + // Disable mouse wheel events + foreach(QSpinBox * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QDoubleSpinBox * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QDoubleSpinBox * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QSlider * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QSlider * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QComboBox * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QComboBox * sp, findChildren()) { + sp->installEventFilter(this); } - return optionsPageWidget; } -bool ScopeGadgetOptionsPage::eventFilter( QObject * obj, QEvent * evt ) { - //Filter all wheel events, and ignore them - if ( evt->type() == QEvent::Wheel && - (qobject_cast( obj ) || - qobject_cast( obj ) || - qobject_cast( obj ) )) - { +bool ScopeGadgetOptionsPage::eventFilter(QObject *obj, QEvent *evt) +{ + // Filter all wheel events, and ignore them + if (evt->type() == QEvent::Wheel && + (qobject_cast(obj) || + qobject_cast(obj) || + qobject_cast(obj))) { evt->ignore(); return true; } - return ScopeGadgetOptionsPage::eventFilter( obj, evt ); + return ScopeGadgetOptionsPage::eventFilter(obj, evt); } -void ScopeGadgetOptionsPage::on_mathFunctionComboBox_currentIndexChanged(int currentIndex){ - if (currentIndex > 0){ +void ScopeGadgetOptionsPage::on_mathFunctionComboBox_currentIndexChanged(int currentIndex) +{ + if (currentIndex > 0) { options_page->spnMeanSamples->setEnabled(true); - } - else{ + } else { options_page->spnMeanSamples->setEnabled(false); } - } void ScopeGadgetOptionsPage::on_btnColor_clicked() - { - QColor color = QColorDialog::getColor( QColor(options_page->btnColor->text())); - if (color.isValid()) { - setButtonColor(color); - } - } +{ + QColor color = QColorDialog::getColor(QColor(options_page->btnColor->text())); + + if (color.isValid()) { + setButtonColor(color); + } +} /*! - \brief Populate the widgets that containts the configs for the Y-Axis from - the selected plot curve - */ + \brief Populate the widgets that containts the configs for the Y-Axis from + the selected plot curve + */ void ScopeGadgetOptionsPage::setYAxisWidgetFromPlotCurve() { bool parseOK = false; - QListWidgetItem* listItem = options_page->lstCurves->currentItem(); + QListWidgetItem *listItem = options_page->lstCurves->currentItem(); - if(listItem == 0) + if (listItem == 0) { return; + } - //WHAT IS UserRole DOING? - int currentIndex = options_page->cmbUAVObjects->findText( listItem->data(Qt::UserRole + 0).toString()); + // WHAT IS UserRole DOING? + int currentIndex = options_page->cmbUAVObjects->findText(listItem->data(Qt::UserRole + 0).toString()); options_page->cmbUAVObjects->setCurrentIndex(currentIndex); - currentIndex = options_page->cmbUAVField->findText( listItem->data(Qt::UserRole + 1).toString()); + currentIndex = options_page->cmbUAVField->findText(listItem->data(Qt::UserRole + 1).toString()); options_page->cmbUAVField->setCurrentIndex(currentIndex); - currentIndex = options_page->cmbScale->findData( listItem->data(Qt::UserRole + 2), Qt::UserRole, Qt::MatchExactly); + currentIndex = options_page->cmbScale->findData(listItem->data(Qt::UserRole + 2), Qt::UserRole, Qt::MatchExactly); options_page->cmbScale->setCurrentIndex(currentIndex); - QVariant varColor = listItem->data(Qt::UserRole + 3); + QVariant varColor = listItem->data(Qt::UserRole + 3); int rgb = varColor.toInt(&parseOK); setButtonColor(QColor((QRgb)rgb)); int mean = listItem->data(Qt::UserRole + 4).toInt(&parseOK); - if(!parseOK) mean = 1; + if (!parseOK) { + mean = 1; + } options_page->spnMeanSamples->setValue(mean); - currentIndex = options_page->mathFunctionComboBox->findText( listItem->data(Qt::UserRole + 5).toString()); + currentIndex = options_page->mathFunctionComboBox->findText(listItem->data(Qt::UserRole + 5).toString()); options_page->mathFunctionComboBox->setCurrentIndex(currentIndex); - + options_page->drawAntialiasedCheckBox->setChecked(listItem->data(Qt::UserRole + 6).toBool()); } void ScopeGadgetOptionsPage::setButtonColor(const QColor &color) @@ -227,33 +231,32 @@ void ScopeGadgetOptionsPage::setButtonColor(const QColor &color) } /*! - \brief When a new UAVObject is selected, populate the UAVObject field combo box with the correct values. - */ + \brief When a new UAVObject is selected, populate the UAVObject field combo box with the correct values. + */ void ScopeGadgetOptionsPage::on_cmbUAVObjects_currentIndexChanged(QString val) { options_page->cmbUAVField->clear(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); - UAVDataObject* obj = dynamic_cast( objManager->getObject(val) ); + UAVDataObject *obj = dynamic_cast(objManager->getObject(val)); - if (obj == NULL) + if (obj == NULL) { return; // Rare case: the config contained a UAVObject name which does not exist anymore. - - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - if(field->getType() == UAVObjectField::STRING || field->getType() == UAVObjectField::ENUM ) + } + QList fieldList = obj->getFields(); + foreach(UAVObjectField * field, fieldList) { + if (field->getType() == UAVObjectField::STRING || field->getType() == UAVObjectField::ENUM) { continue; + } - if(field->getElementNames().count() > 1) - { - foreach(QString elemName , field->getElementNames()) - { + if (field->getElementNames().count() > 1) { + foreach(QString elemName, field->getElementNames()) { options_page->cmbUAVField->addItem(field->getName() + "-" + elemName); } - } - else + } else { options_page->cmbUAVField->addItem(field->getName()); + } } } @@ -267,130 +270,131 @@ void ScopeGadgetOptionsPage::apply() { bool parseOK = false; - //Apply configuration changes + // Apply configuration changes m_config->setPlotType(options_page->cmbPlotType->currentIndex()); m_config->setMathFunctionType(options_page->mathFunctionComboBox->currentIndex()); m_config->setDataSize(options_page->spnDataSize->value()); m_config->setRefreashInterval(options_page->spnRefreshInterval->value()); - QList plotCurveConfigs; - for(int iIndex = 0; iIndex < options_page->lstCurves->count();iIndex++) { - QListWidgetItem* listItem = options_page->lstCurves->item(iIndex); + QList plotCurveConfigs; + for (int iIndex = 0; iIndex < options_page->lstCurves->count(); iIndex++) { + QListWidgetItem *listItem = options_page->lstCurves->item(iIndex); - PlotCurveConfiguration* newPlotCurveConfigs = new PlotCurveConfiguration(); - newPlotCurveConfigs->uavObject = listItem->data(Qt::UserRole + 0).toString(); - newPlotCurveConfigs->uavField = listItem->data(Qt::UserRole + 1).toString(); - newPlotCurveConfigs->yScalePower = listItem->data(Qt::UserRole + 2).toInt(&parseOK); - if(!parseOK) + PlotCurveConfiguration *newPlotCurveConfigs = new PlotCurveConfiguration(); + newPlotCurveConfigs->uavObject = listItem->data(Qt::UserRole + 0).toString(); + newPlotCurveConfigs->uavField = listItem->data(Qt::UserRole + 1).toString(); + newPlotCurveConfigs->yScalePower = listItem->data(Qt::UserRole + 2).toInt(&parseOK); + if (!parseOK) { newPlotCurveConfigs->yScalePower = 0; + } - QVariant varColor = listItem->data(Qt::UserRole + 3); + QVariant varColor = listItem->data(Qt::UserRole + 3); int rgb = varColor.toInt(&parseOK); - if(!parseOK) + if (!parseOK) { newPlotCurveConfigs->color = QColor(Qt::black).rgb(); - else + } else { newPlotCurveConfigs->color = (QRgb)rgb; + } newPlotCurveConfigs->yMeanSamples = listItem->data(Qt::UserRole + 4).toInt(&parseOK); - if(!parseOK) + if (!parseOK) { newPlotCurveConfigs->yMeanSamples = 1; + } - newPlotCurveConfigs->mathFunction = listItem->data(Qt::UserRole + 5).toString(); - + newPlotCurveConfigs->mathFunction = listItem->data(Qt::UserRole + 5).toString(); + newPlotCurveConfigs->drawAntialiased = listItem->data(Qt::UserRole + 6).toBool(); plotCurveConfigs.append(newPlotCurveConfigs); } m_config->replacePlotCurveConfig(plotCurveConfigs); - //save the logging config + // save the logging config m_config->setLoggingPath(options_page->LoggingPath->path()); m_config->setLoggingNewFileOnConnect(options_page->LoggingConnect->isChecked()); m_config->setLoggingEnabled(options_page->LoggingEnable->isChecked()); - } /*! - \brief Add a new curve to the plot. -*/ + \brief Add a new curve to the plot. + */ void ScopeGadgetOptionsPage::on_btnAddCurve_clicked() { - bool parseOK = false; + bool parseOK = false; QString uavObject = options_page->cmbUAVObjects->currentText(); - QString uavField = options_page->cmbUAVField->currentText(); + QString uavField = options_page->cmbUAVField->currentText(); int scale = options_page->cmbScale->itemData(options_page->cmbScale->currentIndex()).toInt(&parseOK); - if(!parseOK) - scale = 0; + if (!parseOK) { + scale = 0; + } int mean = options_page->spnMeanSamples->value(); QString mathFunction = options_page->mathFunctionComboBox->currentText(); - QVariant varColor = (int)QColor(options_page->btnColor->text()).rgb(); + QVariant varColor = (int)QColor(options_page->btnColor->text()).rgb(); - //Find an existing plot curve config based on the uavobject and uav field. If it - //exists, update it, else add a new one. - if(options_page->lstCurves->count() && - options_page->lstCurves->currentItem()->text() == uavObject + "." + uavField) - { + bool antialiased = options_page->drawAntialiasedCheckBox->isChecked(); + // Find an existing plot curve config based on the uavobject and uav field. If it + // exists, update it, else add a new one. + if (options_page->lstCurves->count() && + options_page->lstCurves->currentItem()->text() == uavObject + "." + uavField) { QListWidgetItem *listWidgetItem = options_page->lstCurves->currentItem(); - setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,mean,mathFunction,varColor); - }else - { - addPlotCurveConfig(uavObject,uavField,scale,mean,mathFunction,varColor); + setCurvePlotProperties(listWidgetItem, uavObject, uavField, scale, mean, mathFunction, varColor, antialiased); + } else { + addPlotCurveConfig(uavObject, uavField, scale, mean, mathFunction, varColor, antialiased); options_page->lstCurves->setCurrentRow(options_page->lstCurves->count() - 1); } } -void ScopeGadgetOptionsPage::addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor) +void ScopeGadgetOptionsPage::addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor, bool antialias) { - //Add a new curve config to the list - QString listItemDisplayText = uavObject + "." + uavField; + // Add a new curve config to the list + QString listItemDisplayText = uavObject + "." + uavField; + options_page->lstCurves->addItem(listItemDisplayText); QListWidgetItem *listWidgetItem = options_page->lstCurves->item(options_page->lstCurves->count() - 1); - setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,mean,mathFunction,varColor); - + setCurvePlotProperties(listWidgetItem, uavObject, uavField, scale, mean, mathFunction, varColor, antialias); } -void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetItem,QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor) +void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, + int mean, QString mathFunction, QVariant varColor, bool antialias) { bool parseOK = false; - //Set the properties of the newly added list item - QString listItemDisplayText = uavObject + "." + uavField; + // Set the properties of the newly added list item QRgb rgbColor = (QRgb)varColor.toInt(&parseOK); - QColor color = QColor( rgbColor ); - //listWidgetItem->setText(listItemDisplayText); - listWidgetItem->setTextColor( color ); + QColor color = QColor(rgbColor); - //Store some additional data for the plot curve on the list item - listWidgetItem->setData(Qt::UserRole + 0,QVariant(uavObject)); - listWidgetItem->setData(Qt::UserRole + 1,QVariant(uavField)); - listWidgetItem->setData(Qt::UserRole + 2,QVariant(scale)); - listWidgetItem->setData(Qt::UserRole + 3,varColor); - listWidgetItem->setData(Qt::UserRole + 4,QVariant(mean)); - listWidgetItem->setData(Qt::UserRole + 5,QVariant(mathFunction)); + listWidgetItem->setTextColor(color); + + // Store some additional data for the plot curve on the list item + listWidgetItem->setData(Qt::UserRole + 0, QVariant(uavObject)); + listWidgetItem->setData(Qt::UserRole + 1, QVariant(uavField)); + listWidgetItem->setData(Qt::UserRole + 2, QVariant(scale)); + listWidgetItem->setData(Qt::UserRole + 3, varColor); + listWidgetItem->setData(Qt::UserRole + 4, QVariant(mean)); + listWidgetItem->setData(Qt::UserRole + 5, QVariant(mathFunction)); + listWidgetItem->setData(Qt::UserRole + 6, QVariant(antialias)); } /*! - Remove a curve config from the plot. - */ + Remove a curve config from the plot. + */ void ScopeGadgetOptionsPage::on_btnRemoveCurve_clicked() { options_page->lstCurves->takeItem(options_page->lstCurves->currentIndex().row()); } void ScopeGadgetOptionsPage::finish() -{ - -} +{} /*! - When a different plot curve config is selected, populate its values into the widgets. - */ + When a different plot curve config is selected, populate its values into the widgets. + */ void ScopeGadgetOptionsPage::on_lstCurves_currentRowChanged(int currentRow) { Q_UNUSED(currentRow); @@ -398,15 +402,15 @@ void ScopeGadgetOptionsPage::on_lstCurves_currentRowChanged(int currentRow) } void ScopeGadgetOptionsPage::on_loggingEnable_clicked() - { +{ bool en = options_page->LoggingEnable->isChecked(); + options_page->LoggingPath->setEnabled(en); options_page->LoggingConnect->setEnabled(en); options_page->LoggingLabel->setEnabled(en); +} - } - -void ScopeGadgetOptionsPage::on_spnRefreshInterval_valueChanged(int ) +void ScopeGadgetOptionsPage::on_spnRefreshInterval_valueChanged(int) { validateRefreshInterval(); } @@ -415,19 +419,19 @@ void ScopeGadgetOptionsPage::validateRefreshInterval() { ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); - for(int iIndex = 0; iIndex < options_page->lstCurves->count();iIndex++) { - QListWidgetItem* listItem = options_page->lstCurves->item(iIndex); - QString uavObject = listItem->data(Qt::UserRole + 0).toString(); + for (int iIndex = 0; iIndex < options_page->lstCurves->count(); iIndex++) { + QListWidgetItem *listItem = options_page->lstCurves->item(iIndex); - UAVDataObject* obj = dynamic_cast(objManager->getObject((uavObject))); - if(!obj) { + QString uavObject = listItem->data(Qt::UserRole + 0).toString(); + + UAVDataObject *obj = dynamic_cast(objManager->getObject((uavObject))); + if (!obj) { qDebug() << "Object " << uavObject << " is missing"; continue; } - if(options_page->spnRefreshInterval->value() < obj->getMetadata().flightTelemetryUpdatePeriod) - { + if (options_page->spnRefreshInterval->value() < obj->getMetadata().flightTelemetryUpdatePeriod) { options_page->lblWarnings->setText("The refresh interval is faster than some or all telemetry objects."); return; } @@ -435,4 +439,3 @@ void ScopeGadgetOptionsPage::validateRefreshInterval() options_page->lblWarnings->setText(""); } - diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h index 009f02337..e02c897bd 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h @@ -38,22 +38,19 @@ #include #include -namespace Core -{ +namespace Core { class IUAVGadgetConfiguration; } class ScopeGadgetConfiguration; -namespace Ui -{ +namespace Ui { class ScopeGadgetOptionsPage; } using namespace Core; -class ScopeGadgetOptionsPage : public IOptionsPage -{ +class ScopeGadgetOptionsPage : public IOptionsPage { Q_OBJECT public: explicit ScopeGadgetOptionsPage(ScopeGadgetConfiguration *config, QObject *parent = 0); @@ -66,23 +63,23 @@ private: Ui::ScopeGadgetOptionsPage *options_page; ScopeGadgetConfiguration *m_config; - void addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor); - void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor); + void addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor, bool antialias); + void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, int mean, + QString mathFunction, QVariant varColor, bool antialias); void setYAxisWidgetFromPlotCurve(); void setButtonColor(const QColor &color); void validateRefreshInterval(); - bool eventFilter( QObject * obj, QEvent * evt ); + bool eventFilter(QObject *obj, QEvent *evt); private slots: - void on_spnRefreshInterval_valueChanged(int ); + void on_spnRefreshInterval_valueChanged(int); void on_lstCurves_currentRowChanged(int currentRow); void on_btnRemoveCurve_clicked(); void on_btnAddCurve_clicked(); - void on_cmbUAVObjects_currentIndexChanged(QString val); + void on_cmbUAVObjects_currentIndexChanged(QString val); void on_btnColor_clicked(); void on_mathFunctionComboBox_currentIndexChanged(int currentIndex); void on_loggingEnable_clicked(); - }; #endif // SCOPEGADGETOPTIONSPAGE_H diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui index e5da31784..7ae473fa1 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui @@ -176,38 +176,18 @@ - - + + - Color: + Math function: - - + + Qt::StrongFocus - - Choose - - - - - - - Y-axis scale factor: - - - - - - - Qt::StrongFocus - - - false - @@ -248,18 +228,51 @@ - - + + - Math function: + Color: - - + + Qt::StrongFocus + + Choose + + + + + + + Y-axis scale factor: + + + + + + + Qt::StrongFocus + + + false + + + + + + + Check this to have the curve drawn antialiased. + + + Draw Antialiased + + + true + @@ -277,7 +290,7 @@ 20 - 100 + 40 @@ -288,8 +301,7 @@ Add a new curve to the scope, or update it if the UAVObject and UAVField is the same. - Add -Update + Add / Update @@ -299,8 +311,7 @@ Update Remove the curve from the scope. - Remove - + Remove @@ -310,12 +321,12 @@ Update Qt::Vertical - QSizePolicy::Fixed + QSizePolicy::Expanding 20 - 15 + 40 @@ -331,8 +342,8 @@ Update - 0 - 200 + 20 + 40 @@ -347,6 +358,19 @@ Update + + + + Qt::Vertical + + + + 20 + 40 + + + + diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp index e1775ace0..661ac3035 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp @@ -53,16 +53,16 @@ #include #include -//using namespace Core; +// using namespace Core; // ****************************************************************** ScopeGadgetWidget::ScopeGadgetWidget(QWidget *parent) : QwtPlot(parent) { - setMouseTracking(true); -// canvas()->setMouseTracking(true); + setMouseTracking(true); +// canvas()->setMouseTracking(true); - //Setup the timer that replots data + // Setup the timer that replots data replotTimer = new QTimer(this); connect(replotTimer, SIGNAL(timeout()), this, SLOT(replotNewData())); @@ -71,179 +71,191 @@ ScopeGadgetWidget::ScopeGadgetWidget(QWidget *parent) : QwtPlot(parent) // Also listen to disconnect actions from the user Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); connect(cm, SIGNAL(deviceAboutToDisconnect()), this, SLOT(stopPlotting())); - connect(cm, SIGNAL(deviceConnected(QIODevice*)), this, SLOT(startPlotting())); + connect(cm, SIGNAL(deviceConnected(QIODevice *)), this, SLOT(startPlotting())); - m_csvLoggingStarted=0; - m_csvLoggingEnabled=0; - m_csvLoggingHeaderSaved=0; - m_csvLoggingDataSaved=0; - m_csvLoggingDataUpdated=0; - m_csvLoggingNameSet=0; - m_csvLoggingConnected=0; - m_csvLoggingNewFileOnConnect=0; + m_csvLoggingStarted = 0; + m_csvLoggingEnabled = 0; + m_csvLoggingHeaderSaved = 0; + m_csvLoggingDataSaved = 0; + m_csvLoggingDataUpdated = 0; + m_csvLoggingNameSet = 0; + m_csvLoggingConnected = 0; + m_csvLoggingNewFileOnConnect = 0; m_csvLoggingPath = QString("./csvlogging/"); - m_csvLoggingStartTime = QDateTime::currentDateTime(); + m_csvLoggingStartTime = QDateTime::currentDateTime(); - //Listen to autopilot connection events + // Listen to autopilot connection events connect(cm, SIGNAL(deviceAboutToDisconnect()), this, SLOT(csvLoggingDisconnect())); - connect(cm, SIGNAL(deviceConnected(QIODevice*)), this, SLOT(csvLoggingConnect())); + connect(cm, SIGNAL(deviceConnected(QIODevice *)), this, SLOT(csvLoggingConnect())); } ScopeGadgetWidget::~ScopeGadgetWidget() { - if (replotTimer) - { - replotTimer->stop(); + if (replotTimer) { + replotTimer->stop(); - delete replotTimer; - replotTimer = NULL; - } + delete replotTimer; + replotTimer = NULL; + } - // Get the object to de-monitor - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - foreach (QString uavObjName, m_connectedUAVObjects) - { - UAVDataObject *obj = dynamic_cast(objManager->getObject(uavObjName)); - disconnect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(uavObjectReceived(UAVObject*))); - } + // Get the object to de-monitor + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + foreach(QString uavObjName, m_connectedUAVObjects) { + UAVDataObject *obj = dynamic_cast(objManager->getObject(uavObjName)); - clearCurvePlots(); + disconnect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(uavObjectReceived(UAVObject *))); + } + + clearCurvePlots(); } // ****************************************************************** void ScopeGadgetWidget::mousePressEvent(QMouseEvent *e) { - QwtPlot::mousePressEvent(e); + QwtPlot::mousePressEvent(e); } void ScopeGadgetWidget::mouseReleaseEvent(QMouseEvent *e) { - QwtPlot::mouseReleaseEvent(e); + QwtPlot::mouseReleaseEvent(e); } void ScopeGadgetWidget::mouseDoubleClickEvent(QMouseEvent *e) { - //On double-click, toggle legend + // On double-click, toggle legend mutex.lock(); - if (legend()) + if (legend()) { deleteLegend(); - else + } else { addLegend(); + } mutex.unlock(); - //On double-click, reset plot zoom + // On double-click, reset plot zoom setAxisAutoScale(QwtPlot::yLeft, true); update(); - QwtPlot::mouseDoubleClickEvent(e); + QwtPlot::mouseDoubleClickEvent(e); } void ScopeGadgetWidget::mouseMoveEvent(QMouseEvent *e) { - QwtPlot::mouseMoveEvent(e); + QwtPlot::mouseMoveEvent(e); } void ScopeGadgetWidget::wheelEvent(QWheelEvent *e) { - //Change zoom on scroll wheel event - QwtInterval yInterval=axisInterval(QwtPlot::yLeft); - if (yInterval.minValue() != yInterval.maxValue()) //Make sure that the two values are never the same. Sometimes axisInterval returns (0,0) - { - //Determine what y value to zoom about. NOTE, this approach has a bug that the in that - //the value returned by Qt includes the legend, whereas the value transformed by Qwt - //does *not*. Thus, when zooming with a legend, there will always be a small bias error. - //In practice, this seems not to be a UI problem. - QPoint mouse_pos=e->pos(); //Get the mouse coordinate in the frame - double zoomLine=invTransform(QwtPlot::yLeft, mouse_pos.y()); //Transform the y mouse coordinate into a frame value. + // Change zoom on scroll wheel event + QwtInterval yInterval = axisInterval(QwtPlot::yLeft); - double zoomScale=1.1; //THIS IS AN ARBITRARY CONSTANT, AND PERHAPS SHOULD BE IN A DEFINE INSTEAD OF BURIED HERE + if (yInterval.minValue() != yInterval.maxValue()) { // Make sure that the two values are never the same. Sometimes axisInterval returns (0,0) + // Determine what y value to zoom about. NOTE, this approach has a bug that the in that + // the value returned by Qt includes the legend, whereas the value transformed by Qwt + // does *not*. Thus, when zooming with a legend, there will always be a small bias error. + // In practice, this seems not to be a UI problem. + QPoint mouse_pos = e->pos(); // Get the mouse coordinate in the frame + double zoomLine = invTransform(QwtPlot::yLeft, mouse_pos.y()); // Transform the y mouse coordinate into a frame value. - mutex.lock(); //DOES THIS mutex.lock NEED TO BE HERE? I DON'T KNOW, I JUST COPIED IT FROM THE ABOVE CODE + double zoomScale = 1.1; // THIS IS AN ARBITRARY CONSTANT, AND PERHAPS SHOULD BE IN A DEFINE INSTEAD OF BURIED HERE + + mutex.lock(); // DOES THIS mutex.lock NEED TO BE HERE? I DON'T KNOW, I JUST COPIED IT FROM THE ABOVE CODE // Set the scale - if (e->delta()<0){ + if (e->delta() < 0) { setAxisScale(QwtPlot::yLeft, - (yInterval.minValue()-zoomLine)*zoomScale+zoomLine, - (yInterval.maxValue()-zoomLine)*zoomScale+zoomLine ); - } - else{ + (yInterval.minValue() - zoomLine) * zoomScale + zoomLine, + (yInterval.maxValue() - zoomLine) * zoomScale + zoomLine); + } else { setAxisScale(QwtPlot::yLeft, - (yInterval.minValue()-zoomLine)/zoomScale+zoomLine, - (yInterval.maxValue()-zoomLine)/zoomScale+zoomLine ); + (yInterval.minValue() - zoomLine) / zoomScale + zoomLine, + (yInterval.maxValue() - zoomLine) / zoomScale + zoomLine); } mutex.unlock(); } QwtPlot::wheelEvent(e); } +void ScopeGadgetWidget::showEvent(QShowEvent *e) +{ + replotNewData(); + QwtPlot::showEvent(e); +} + /** * Starts/stops telemetry */ void ScopeGadgetWidget::startPlotting() { - if (!replotTimer) - return; + if (!replotTimer) { + return; + } - if (!replotTimer->isActive()) + if (!replotTimer->isActive()) { replotTimer->start(m_refreshInterval); + } } void ScopeGadgetWidget::stopPlotting() { - if (!replotTimer) - return; + if (!replotTimer) { + return; + } - replotTimer->stop(); + replotTimer->stop(); } void ScopeGadgetWidget::deleteLegend() { - if (!legend()) - return; + if (!legend()) { + return; + } - disconnect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, 0); + disconnect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, 0); - insertLegend(NULL, QwtPlot::TopLegend); -// insertLegend(NULL, QwtPlot::ExternalLegend); + insertLegend(NULL, QwtPlot::TopLegend); +// insertLegend(NULL, QwtPlot::ExternalLegend); } void ScopeGadgetWidget::addLegend() { - if (legend()) - return; + if (legend()) { + return; + } - // Show a legend at the top - QwtLegend *legend = new QwtLegend(); - legend->setItemMode(QwtLegend::CheckableItem); - legend->setFrameStyle(QFrame::Box | QFrame::Sunken); - legend->setToolTip(tr("Click legend to show/hide scope trace")); + // Show a legend at the top + QwtLegend *legend = new QwtLegend(); + legend->setItemMode(QwtLegend::CheckableItem); + legend->setFrameStyle(QFrame::Box | QFrame::Sunken); + legend->setToolTip(tr("Click legend to show/hide scope trace")); - QPalette pal = legend->palette(); - pal.setColor(legend->backgroundRole(), QColor(100, 100, 100)); // background colour -// pal.setColor(legend->backgroundRole(), Qt::transparent); // background colour -// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour - pal.setColor(QPalette::Text, QColor(0, 0, 0)); // text colour - legend->setPalette(pal); + QPalette pal = legend->palette(); + pal.setColor(legend->backgroundRole(), QColor(100, 100, 100)); // background colour +// pal.setColor(legend->backgroundRole(), Qt::transparent); // background colour +// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour + pal.setColor(QPalette::Text, QColor(0, 0, 0)); // text colour + legend->setPalette(pal); - insertLegend(legend, QwtPlot::TopLegend); -// insertLegend(legend, QwtPlot::ExternalLegend); + insertLegend(legend, QwtPlot::TopLegend); +// insertLegend(legend, QwtPlot::ExternalLegend); -// // Show a legend at the bottom -// QwtLegend *legend = new QwtLegend(); -// legend->setItemMode(QwtLegend::CheckableItem); -// legend->setFrameStyle(QFrame::Box | QFrame::Sunken); -// insertLegend(legend, QwtPlot::BottomLegend); +//// Show a legend at the bottom +// QwtLegend *legend = new QwtLegend(); +// legend->setItemMode(QwtLegend::CheckableItem); +// legend->setFrameStyle(QFrame::Box | QFrame::Sunken); +// insertLegend(legend, QwtPlot::BottomLegend); // Update the checked/unchecked state of the legend items // -> this is necessary when hiding a legend where some plots are - // not visible, and the un-hiding it. - foreach (QwtPlotItem *item, this->itemList()) { - bool on = item->isVisible(); + // not visible, and the un-hiding it. + foreach(QwtPlotItem * item, this->itemList()) { + bool on = item->isVisible(); QWidget *w = legend->find(item); - if ( w && w->inherits("QwtLegendItem") ) + + if (w && w->inherits("QwtLegendItem")) { ((QwtLegendItem *)w)->setChecked(!on); + } } connect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, SLOT(showCurve(QwtPlotItem *, bool))); @@ -258,18 +270,18 @@ void ScopeGadgetWidget::preparePlot(PlotType plotType) setMinimumSize(64, 64); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); -// setMargin(1); +// setMargin(1); -// QPalette pal = palette(); -// QPalette::ColorRole cr = backgroundRole(); -// pal.setColor(cr, QColor(128, 128, 128)); // background colour -// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour -// setPalette(pal); +// QPalette pal = palette(); +// QPalette::ColorRole cr = backgroundRole(); +// pal.setColor(cr, QColor(128, 128, 128)); // background colour +// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour +// setPalette(pal); -// setCanvasBackground(Utils::StyleHelper::baseColor()); +// setCanvasBackground(Utils::StyleHelper::baseColor()); setCanvasBackground(QColor(64, 64, 64)); - //Add grid lines + // Add grid lines QwtPlotGrid *grid = new QwtPlotGrid; grid->setMajPen(QPen(Qt::gray, 0, Qt::DashLine)); grid->setMinPen(QPen(Qt::lightGray, 0, Qt::DotLine)); @@ -281,12 +293,12 @@ void ScopeGadgetWidget::preparePlot(PlotType plotType) // Only start the timer if we are already connected Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); - if (cm->getCurrentConnection() && replotTimer) - { - if (!replotTimer->isActive()) + if (cm->getCurrentConnection() && replotTimer) { + if (!replotTimer->isActive()) { replotTimer->start(m_refreshInterval); - else + } else { replotTimer->setInterval(m_refreshInterval); + } } } @@ -294,22 +306,23 @@ void ScopeGadgetWidget::showCurve(QwtPlotItem *item, bool on) { item->setVisible(!on); QWidget *w = legend()->find(item); - if ( w && w->inherits("QwtLegendItem") ) + if (w && w->inherits("QwtLegendItem")) { ((QwtLegendItem *)w)->setChecked(on); + } - mutex.lock(); - replot(); - mutex.unlock(); + mutex.lock(); + replot(); + mutex.unlock(); } void ScopeGadgetWidget::setupSequentialPlot() { preparePlot(SequentialPlot); -// QwtText title("Index"); +// QwtText title("Index"); //// title.setFont(QFont("Helvetica", 20)); -// title.font().setPointSize(title.font().pointSize() / 2); -// setAxisTitle(QwtPlot::xBottom, title); +// title.font().setPointSize(title.font().pointSize() / 2); +// setAxisTitle(QwtPlot::xBottom, title); //// setAxisTitle(QwtPlot::xBottom, "Index"); setAxisScaleDraw(QwtPlot::xBottom, new QwtScaleDraw()); @@ -317,175 +330,187 @@ void ScopeGadgetWidget::setupSequentialPlot() setAxisLabelRotation(QwtPlot::xBottom, 0.0); setAxisLabelAlignment(QwtPlot::xBottom, Qt::AlignLeft | Qt::AlignBottom); - QwtScaleWidget *scaleWidget = axisWidget(QwtPlot::xBottom); + QwtScaleWidget *scaleWidget = axisWidget(QwtPlot::xBottom); - // reduce the gap between the scope canvas and the axis scale - scaleWidget->setMargin(0); + // reduce the gap between the scope canvas and the axis scale + scaleWidget->setMargin(0); - // reduce the axis font size - QFont fnt(axisFont(QwtPlot::xBottom)); - fnt.setPointSize(7); - setAxisFont(QwtPlot::xBottom, fnt); // x-axis - setAxisFont(QwtPlot::yLeft, fnt); // y-axis + // reduce the axis font size + QFont fnt(axisFont(QwtPlot::xBottom)); + fnt.setPointSize(7); + setAxisFont(QwtPlot::xBottom, fnt); // x-axis + setAxisFont(QwtPlot::yLeft, fnt); // y-axis } void ScopeGadgetWidget::setupChronoPlot() { preparePlot(ChronoPlot); -// QwtText title("Time [h:m:s]"); +// QwtText title("Time [h:m:s]"); //// title.setFont(QFont("Helvetica", 20)); -// title.font().setPointSize(title.font().pointSize() / 2); -// setAxisTitle(QwtPlot::xBottom, title); +// title.font().setPointSize(title.font().pointSize() / 2); +// setAxisTitle(QwtPlot::xBottom, title); //// setAxisTitle(QwtPlot::xBottom, "Time [h:m:s]"); setAxisScaleDraw(QwtPlot::xBottom, new TimeScaleDraw()); uint NOW = QDateTime::currentDateTime().toTime_t(); setAxisScale(QwtPlot::xBottom, NOW - m_xWindowSize / 1000, NOW); -// setAxisLabelRotation(QwtPlot::xBottom, -15.0); - setAxisLabelRotation(QwtPlot::xBottom, 0.0); - setAxisLabelAlignment(QwtPlot::xBottom, Qt::AlignLeft | Qt::AlignBottom); -// setAxisLabelAlignment(QwtPlot::xBottom, Qt::AlignCenter | Qt::AlignBottom); +// setAxisLabelRotation(QwtPlot::xBottom, -15.0); + setAxisLabelRotation(QwtPlot::xBottom, 0.0); + setAxisLabelAlignment(QwtPlot::xBottom, Qt::AlignLeft | Qt::AlignBottom); +// setAxisLabelAlignment(QwtPlot::xBottom, Qt::AlignCenter | Qt::AlignBottom); - QwtScaleWidget *scaleWidget = axisWidget(QwtPlot::xBottom); -// QwtScaleDraw *scaleDraw = axisScaleDraw(); + QwtScaleWidget *scaleWidget = axisWidget(QwtPlot::xBottom); +// QwtScaleDraw *scaleDraw = axisScaleDraw(); - // reduce the gap between the scope canvas and the axis scale - scaleWidget->setMargin(0); + // reduce the gap between the scope canvas and the axis scale + scaleWidget->setMargin(0); - // reduce the axis font size - QFont fnt(axisFont(QwtPlot::xBottom)); - fnt.setPointSize(7); - setAxisFont(QwtPlot::xBottom, fnt); // x-axis - setAxisFont(QwtPlot::yLeft, fnt); // y-axis + // reduce the axis font size + QFont fnt(axisFont(QwtPlot::xBottom)); + fnt.setPointSize(7); + setAxisFont(QwtPlot::xBottom, fnt); // x-axis + setAxisFont(QwtPlot::yLeft, fnt); // y-axis - // set the axis colours .. can't seem to change the background colour :( -// QPalette pal = scaleWidget->palette(); -// QPalette::ColorRole cr = scaleWidget->backgroundRole(); -// pal.setColor(cr, QColor(128, 128, 128)); // background colour -// cr = scaleWidget->foregroundRole(); -// pal.setColor(cr, QColor(255, 255, 255)); // tick colour -// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour -// scaleWidget->setPalette(pal); + // set the axis colours .. can't seem to change the background colour :( +// QPalette pal = scaleWidget->palette(); +// QPalette::ColorRole cr = scaleWidget->backgroundRole(); +// pal.setColor(cr, QColor(128, 128, 128)); // background colour +// cr = scaleWidget->foregroundRole(); +// pal.setColor(cr, QColor(255, 255, 255)); // tick colour +// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour +// scaleWidget->setPalette(pal); /* - In situations, when there is a label at the most right position of the - scale, additional space is needed to display the overlapping part - of the label would be taken by reducing the width of scale and canvas. - To avoid this "jumping canvas" effect, we add a permanent margin. - We don't need to do the same for the left border, because there - is enough space for the overlapping label below the left scale. + In situations, when there is a label at the most right position of the + scale, additional space is needed to display the overlapping part + of the label would be taken by reducing the width of scale and canvas. + To avoid this "jumping canvas" effect, we add a permanent margin. + We don't need to do the same for the left border, because there + is enough space for the overlapping label below the left scale. */ -// const int fmh = QFontMetrics(scaleWidget->font()).height(); -// scaleWidget->setMinBorderDist(0, fmh / 2); +// const int fmh = QFontMetrics(scaleWidget->font()).height(); +// scaleWidget->setMinBorderDist(0, fmh / 2); -// const int fmw = QFontMetrics(scaleWidget->font()).width(" 00:00:00 "); -// const int fmw = QFontMetrics(scaleWidget->font()).width(" "); -// scaleWidget->setMinBorderDist(0, fmw); +// const int fmw = QFontMetrics(scaleWidget->font()).width(" 00:00:00 "); +// const int fmw = QFontMetrics(scaleWidget->font()).width(" "); +// scaleWidget->setMinBorderDist(0, fmw); } -void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor, int meanSamples, QString mathFunction, QPen pen) +void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor, int meanSamples, QString mathFunction, QPen pen, bool antialiased) { - PlotData* plotData; + PlotData *plotData; - if (m_plotType == SequentialPlot) + if (m_plotType == SequentialPlot) { plotData = new SequentialPlotData(uavObject, uavFieldSubField); - else if (m_plotType == ChronoPlot) + } else if (m_plotType == ChronoPlot) { plotData = new ChronoPlotData(uavObject, uavFieldSubField); - //else if (m_plotType == UAVObjectPlot) - // plotData = new UAVObjectPlotData(uavObject, uavField); + } + // else if (m_plotType == UAVObjectPlot) + // plotData = new UAVObjectPlotData(uavObject, uavField); plotData->m_xWindowSize = m_xWindowSize; - plotData->scalePower = scaleOrderFactor; - plotData->meanSamples = meanSamples; - plotData->mathFunction = mathFunction; + plotData->scalePower = scaleOrderFactor; + plotData->meanSamples = meanSamples; + plotData->mathFunction = mathFunction; - //If the y-bounds are supplied, set them - if (plotData->yMinimum != plotData->yMaximum) - { - setAxisScale(QwtPlot::yLeft, plotData->yMinimum, plotData->yMaximum); - } + // If the y-bounds are supplied, set them + if (plotData->yMinimum != plotData->yMaximum) { + setAxisScale(QwtPlot::yLeft, plotData->yMinimum, plotData->yMaximum); + } - //Create the curve + // Create the curve QString curveName = (plotData->uavObject) + "." + (plotData->uavField); - if(plotData->haveSubField) + if (plotData->haveSubField) { curveName = curveName.append("." + plotData->uavSubField); + } - //Get the uav object + // Get the uav object ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); - UAVDataObject* obj = dynamic_cast(objManager->getObject((plotData->uavObject))); - if(!obj) { + UAVDataObject *obj = dynamic_cast(objManager->getObject((plotData->uavObject))); + if (!obj) { qDebug() << "Object " << plotData->uavObject << " is missing"; return; } - UAVObjectField* field = obj->getField(plotData->uavField); - if(!field) { + UAVObjectField *field = obj->getField(plotData->uavField); + if (!field) { qDebug() << "In scope gadget, in fields loaded from GCS config file, field" << plotData->uavField << " of object " << plotData->uavObject << " is missing"; return; } QString units = field->getUnits(); - if(units == 0) + if (units == 0) { units = QString(); + } QString curveNameScaled; - if(scaleOrderFactor == 0) + if (scaleOrderFactor == 0) { curveNameScaled = curveName + " (" + units + ")"; - else + } else { curveNameScaled = curveName + " (x10^" + QString::number(scaleOrderFactor) + " " + units + ")"; + } + + QwtPlotCurve *plotCurve = new QwtPlotCurve(curveNameScaled); + + if (antialiased) { + plotCurve->setRenderHint(QwtPlotCurve::RenderAntialiased); + } - QwtPlotCurve* plotCurve = new QwtPlotCurve(curveNameScaled); plotCurve->setPen(pen); plotCurve->setSamples(*plotData->xData, *plotData->yData); plotCurve->attach(this); plotData->curve = plotCurve; - //Keep the curve details for later + // Keep the curve details for later m_curvesData.insert(curveNameScaled, plotData); - //Link to the new signal data only if this UAVObject has not been connected yet + // Link to the new signal data only if this UAVObject has not been connected yet if (!m_connectedUAVObjects.contains(obj->getName())) { m_connectedUAVObjects.append(obj->getName()); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(uavObjectReceived(UAVObject*))); + connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(uavObjectReceived(UAVObject *))); } - mutex.lock(); - replot(); - mutex.unlock(); + mutex.lock(); + replot(); + mutex.unlock(); } -//void ScopeGadgetWidget::removeCurvePlot(QString uavObject, QString uavField) -//{ -// QString curveName = uavObject + "." + uavField; +// void ScopeGadgetWidget::removeCurvePlot(QString uavObject, QString uavField) +// { +// QString curveName = uavObject + "." + uavField; // -// PlotData* plotData = m_curvesData.take(curveName); -// m_curvesData.remove(curveName); -// plotData->curve->detach(); +// PlotData* plotData = m_curvesData.take(curveName); +// m_curvesData.remove(curveName); +// plotData->curve->detach(); // -// delete plotData->curve; -// delete plotData; +// delete plotData->curve; +// delete plotData; // -// mutex.lock(); -// replot(); -// mutex.unlock(); -//} +// mutex.lock(); +// replot(); +// mutex.unlock(); +// } -void ScopeGadgetWidget::uavObjectReceived(UAVObject* obj) +void ScopeGadgetWidget::uavObjectReceived(UAVObject *obj) { - foreach(PlotData* plotData, m_curvesData.values()) { - if (plotData->append(obj)) m_csvLoggingDataUpdated=1; + foreach(PlotData * plotData, m_curvesData.values()) { + if (plotData->append(obj)) { + m_csvLoggingDataUpdated = 1; + } } csvLoggingAddData(); } void ScopeGadgetWidget::replotNewData() { - QMutexLocker locker(&mutex); + if (!isVisible()) { + return; + } - foreach(PlotData* plotData, m_curvesData.values()) - { + QMutexLocker locker(&mutex); + foreach(PlotData * plotData, m_curvesData.values()) { plotData->removeStaleData(); plotData->curve->setSamples(*plotData->xData, *plotData->yData); } @@ -493,66 +518,20 @@ void ScopeGadgetWidget::replotNewData() QDateTime NOW = QDateTime::currentDateTime(); double toTime = NOW.toTime_t(); toTime += NOW.time().msec() / 1000.0; - if (m_plotType == ChronoPlot) + if (m_plotType == ChronoPlot) { setAxisScale(QwtPlot::xBottom, toTime - m_xWindowSize, toTime); + } -// qDebug() << "replotNewData from " << NOW.addSecs(- m_xWindowSize) << " to " << NOW; +// qDebug() << "replotNewData from " << NOW.addSecs(- m_xWindowSize) << " to " << NOW; csvLoggingInsertData(); - replot(); + replot(); } -/* -void ScopeGadgetWidget::setupExamplePlot() -{ - preparePlot(SequentialPlot); - - // Show the axes - - setAxisTitle(xBottom, "x"); - setAxisTitle(yLeft, "y"); - - // Calculate the data, 500 points each - const int points = 500; - double x[ points ]; - double sn[ points ]; - double cs[ points ]; - double sg[ points ]; - - for (int i = 0; i < points; i++) { - x[i] = (3.0 * 3.14 / double(points)) * double(i); - sn[i] = 2.0 * sin(x[i]); - cs[i] = 3.0 * cos(x[i]); - sg[i] = (sn[i] > 0) ? 1 : ((sn[i] < 0) ? -1 : 0); - } - - // add curves - QwtPlotCurve *curve1 = new QwtPlotCurve("Curve 1"); - curve1->setPen(QPen(Qt::blue)); - QwtPlotCurve *curve2 = new QwtPlotCurve("Curve 2"); - curve2->setPen(QPen(Qt::red)); - QwtPlotCurve *curve3 = new QwtPlotCurve("Curve 3"); - curve3->setPen(QPen(Qt::green)); - - // copy the data into the curves - curve1->setSamples(x, sn, points); - curve2->setSamples(x, cs, points); - curve3->setSamples(x, sg, points); - curve1->attach(this); - curve2->attach(this); - curve3->attach(this); - - // finally, refresh the plot - mutex.lock(); - replot(); - mutex.unlock(); -} -*/ - void ScopeGadgetWidget::clearCurvePlots() { - foreach(PlotData* plotData, m_curvesData.values()) { + foreach(PlotData * plotData, m_curvesData.values()) { plotData->curve->detach(); delete plotData->curve; @@ -564,49 +543,42 @@ void ScopeGadgetWidget::clearCurvePlots() /* -int csvLoggingEnable; -int csvLoggingHeaderSaved; -int csvLoggingDataSaved; -QString csvLoggingPath; -QFile csvLoggingFile; -*/ + int csvLoggingEnable; + int csvLoggingHeaderSaved; + int csvLoggingDataSaved; + QString csvLoggingPath; + QFile csvLoggingFile; + */ int ScopeGadgetWidget::csvLoggingStart() { - if (!m_csvLoggingStarted) - if (m_csvLoggingEnabled) - if ((!m_csvLoggingNewFileOnConnect)||(m_csvLoggingNewFileOnConnect && m_csvLoggingConnected)) - { - QDateTime NOW = QDateTime::currentDateTime(); - m_csvLoggingStartTime = NOW; - m_csvLoggingHeaderSaved=0; - m_csvLoggingDataSaved=0; - m_csvLoggingBuffer.clear(); - QDir PathCheck(m_csvLoggingPath); - if (!PathCheck.exists()) - { - PathCheck.mkpath("./"); - } + if (!m_csvLoggingStarted) { + if (m_csvLoggingEnabled) { + if ((!m_csvLoggingNewFileOnConnect) || (m_csvLoggingNewFileOnConnect && m_csvLoggingConnected)) { + QDateTime NOW = QDateTime::currentDateTime(); + m_csvLoggingStartTime = NOW; + m_csvLoggingHeaderSaved = 0; + m_csvLoggingDataSaved = 0; + m_csvLoggingBuffer.clear(); + QDir PathCheck(m_csvLoggingPath); + if (!PathCheck.exists()) { + PathCheck.mkpath("./"); + } - if (m_csvLoggingNameSet) - { - m_csvLoggingFile.setFileName(QString("%1/%2_%3_%4.csv").arg(m_csvLoggingPath).arg(m_csvLoggingName).arg(NOW.toString("yyyy-MM-dd")).arg(NOW.toString("hh-mm-ss"))); + if (m_csvLoggingNameSet) { + m_csvLoggingFile.setFileName(QString("%1/%2_%3_%4.csv").arg(m_csvLoggingPath).arg(m_csvLoggingName).arg(NOW.toString("yyyy-MM-dd")).arg(NOW.toString("hh-mm-ss"))); + } else { + m_csvLoggingFile.setFileName(QString("%1/Log_%2_%3.csv").arg(m_csvLoggingPath).arg(NOW.toString("yyyy-MM-dd")).arg(NOW.toString("hh-mm-ss"))); + } + QDir FileCheck(m_csvLoggingFile.fileName()); + if (FileCheck.exists()) { + m_csvLoggingFile.setFileName(""); + } else { + m_csvLoggingStarted = 1; + csvLoggingInsertHeader(); + } + } } - else - { - m_csvLoggingFile.setFileName(QString("%1/Log_%2_%3.csv").arg(m_csvLoggingPath).arg(NOW.toString("yyyy-MM-dd")).arg(NOW.toString("hh-mm-ss"))); - } - QDir FileCheck(m_csvLoggingFile.fileName()); - if (FileCheck.exists()) - { - m_csvLoggingFile.setFileName(""); - } - else - { - m_csvLoggingStarted=1; - csvLoggingInsertHeader(); - } - } return 0; @@ -614,33 +586,37 @@ int ScopeGadgetWidget::csvLoggingStart() int ScopeGadgetWidget::csvLoggingStop() { - m_csvLoggingStarted=0; + m_csvLoggingStarted = 0; return 0; } int ScopeGadgetWidget::csvLoggingInsertHeader() { - if (!m_csvLoggingStarted) return -1; - if (m_csvLoggingHeaderSaved) return -2; - if (m_csvLoggingDataSaved) return -3; - - m_csvLoggingHeaderSaved=1; - if(m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append)== FALSE) - { - qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Header"; + if (!m_csvLoggingStarted) { + return -1; + } + if (m_csvLoggingHeaderSaved) { + return -2; + } + if (m_csvLoggingDataSaved) { + return -3; } - else - { - QTextStream ts( &m_csvLoggingFile ); - ts << "date" << ", " << "Time"<< ", " << "Sec since start"<< ", " << "Connected" << ", " << "Data changed"; - foreach(PlotData* plotData2, m_curvesData.values()) - { - ts << ", "; - ts << plotData2->uavObject; - ts << "." << plotData2->uavField; - if (plotData2->haveSubField) ts << "." << plotData2->uavSubField; + m_csvLoggingHeaderSaved = 1; + if (m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append) == FALSE) { + qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Header"; + } else { + QTextStream ts(&m_csvLoggingFile); + ts << "date" << ", " << "Time" << ", " << "Sec since start" << ", " << "Connected" << ", " << "Data changed"; + + foreach(PlotData * plotData2, m_curvesData.values()) { + ts << ", "; + ts << plotData2->uavObject; + ts << "." << plotData2->uavField; + if (plotData2->haveSubField) { + ts << "." << plotData2->uavSubField; + } } ts << endl; m_csvLoggingFile.close(); @@ -650,47 +626,40 @@ int ScopeGadgetWidget::csvLoggingInsertHeader() int ScopeGadgetWidget::csvLoggingAddData() { - if (!m_csvLoggingStarted) return -1; - m_csvLoggingDataValid=0; + if (!m_csvLoggingStarted) { + return -1; + } + m_csvLoggingDataValid = 0; QDateTime NOW = QDateTime::currentDateTime(); QString tempString; - QTextStream ss( &tempString ); - ss << NOW.toString("yyyy-MM-dd") << ", " << NOW.toString("hh:mm:ss.z") << ", " ; + QTextStream ss(&tempString); + ss << NOW.toString("yyyy-MM-dd") << ", " << NOW.toString("hh:mm:ss.z") << ", "; #if QT_VERSION >= 0x040700 - ss <<(NOW.toMSecsSinceEpoch() - m_csvLoggingStartTime.toMSecsSinceEpoch())/1000.00; + ss << (NOW.toMSecsSinceEpoch() - m_csvLoggingStartTime.toMSecsSinceEpoch()) / 1000.00; #else - ss <<(NOW.toTime_t() - m_csvLoggingStartTime.toTime_t()); + ss << (NOW.toTime_t() - m_csvLoggingStartTime.toTime_t()); #endif ss << ", " << m_csvLoggingConnected << ", " << m_csvLoggingDataUpdated; - m_csvLoggingDataUpdated=0; + m_csvLoggingDataUpdated = 0; - foreach(PlotData* plotData2, m_curvesData.values()) - { - ss << ", "; - if (plotData2->xData->isEmpty ()) - { - ss << ", "; - if (plotData2->xData->isEmpty ()) - { + foreach(PlotData * plotData2, m_curvesData.values()) { + ss << ", "; + if (plotData2->xData->isEmpty()) { + ss << ", "; + if (plotData2->xData->isEmpty()) {} else { + ss << QString().sprintf("%3.10g", plotData2->yData->last()); + m_csvLoggingDataValid = 1; } - else - { - ss << QString().sprintf("%3.10g",plotData2->yData->last()); - m_csvLoggingDataValid=1; - } - } - else - { - ss << QString().sprintf("%3.10g",plotData2->yData->last()); - m_csvLoggingDataValid=1; + } else { + ss << QString().sprintf("%3.10g", plotData2->yData->last()); + m_csvLoggingDataValid = 1; } } ss << endl; - if (m_csvLoggingDataValid) - { - QTextStream ts( &m_csvLoggingBuffer ); + if (m_csvLoggingDataValid) { + QTextStream ts(&m_csvLoggingBuffer); ts << tempString; } @@ -699,16 +668,15 @@ int ScopeGadgetWidget::csvLoggingAddData() int ScopeGadgetWidget::csvLoggingInsertData() { - if (!m_csvLoggingStarted) return -1; - m_csvLoggingDataSaved=1; - - if(m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append)== FALSE) - { - qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Data"; + if (!m_csvLoggingStarted) { + return -1; } - else - { - QTextStream ts( &m_csvLoggingFile ); + m_csvLoggingDataSaved = 1; + + if (m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append) == FALSE) { + qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Data"; + } else { + QTextStream ts(&m_csvLoggingFile); ts << m_csvLoggingBuffer; m_csvLoggingFile.close(); } @@ -719,20 +687,22 @@ int ScopeGadgetWidget::csvLoggingInsertData() void ScopeGadgetWidget::csvLoggingSetName(QString newName) { - m_csvLoggingName = newName; - m_csvLoggingNameSet=1; + m_csvLoggingName = newName; + m_csvLoggingNameSet = 1; } void ScopeGadgetWidget::csvLoggingConnect() { - m_csvLoggingConnected=1; - if (m_csvLoggingNewFileOnConnect)csvLoggingStart(); - return; + m_csvLoggingConnected = 1; + if (m_csvLoggingNewFileOnConnect) { + csvLoggingStart(); + } } void ScopeGadgetWidget::csvLoggingDisconnect() { - m_csvLoggingHeaderSaved=0; - m_csvLoggingConnected=0; - if (m_csvLoggingNewFileOnConnect)csvLoggingStop(); - return; + m_csvLoggingHeaderSaved = 0; + m_csvLoggingConnected = 0; + if (m_csvLoggingNewFileOnConnect) { + csvLoggingStop(); + } } diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h index f812e6fa6..da081c5c5 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h @@ -49,7 +49,6 @@ class TimeScaleDraw : public QwtScaleDraw { public: TimeScaleDraw() { - //baseTime = QDateTime::currentDateTime().toTime_t(); } virtual QwtText label(double v) const { uint seconds = (uint)(v); @@ -58,8 +57,6 @@ public: upTime.setTime(timePart); return upTime.toLocalTime().toString("hh:mm:ss"); } -private: -// double baseTime; }; class ScopeGadgetWidget : public QwtPlot @@ -81,15 +78,15 @@ public: int refreshInterval(){return m_refreshInterval;} - void addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, int meanSamples = 1, QString mathFunction= "None", QPen pen = QPen(Qt::black)); - //void removeCurvePlot(QString uavObject, QString uavField); + void addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, int meanSamples = 1, + QString mathFunction= "None", QPen pen = QPen(Qt::black), bool antialiased = true); void clearCurvePlots(); int csvLoggingStart(); int csvLoggingStop(); void csvLoggingSetName(QString); - void setLoggingEnabled(bool value){m_csvLoggingEnabled=value;}; - void setLoggingNewFileOnConnect(bool value){m_csvLoggingNewFileOnConnect=value;}; - void setLoggingPath(QString value){m_csvLoggingPath=value;}; + void setLoggingEnabled(bool value){m_csvLoggingEnabled=value;} + void setLoggingNewFileOnConnect(bool value){m_csvLoggingNewFileOnConnect=value;} + void setLoggingPath(QString value){m_csvLoggingPath=value;} protected: void mousePressEvent(QMouseEvent *e); @@ -97,6 +94,7 @@ protected: void mouseDoubleClickEvent(QMouseEvent *e); void mouseMoveEvent(QMouseEvent *e); void wheelEvent(QWheelEvent *e); + void showEvent(QShowEvent *e); private slots: void uavObjectReceived(UAVObject*); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index bf7a7dcc3..0c4036091 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -32,44 +32,45 @@ /** * Constructor */ -ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),allowWidgetUpdates(true),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL) +ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), isConnected(false), allowWidgetUpdates(true), smartsave(NULL), dirty(false), outOfLimitsStyle("background-color: rgb(255, 0, 0);"), timeOut(NULL) { pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); - TelemetryManager* telMngr = pm->getObject(); - utilMngr = pm->getObject(); - connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()),Qt::UniqueConnection); - connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()),Qt::UniqueConnection); - connect(telMngr, SIGNAL(connected()), this, SIGNAL(autoPilotConnected()),Qt::UniqueConnection); - connect(telMngr, SIGNAL(disconnected()), this, SIGNAL(autoPilotDisconnected()),Qt::UniqueConnection); - UAVSettingsImportExportFactory * importexportplugin = pm->getObject(); - connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(invalidateObjects())); + TelemetryManager *telMngr = pm->getObject(); + utilMngr = pm->getObject(); + connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()), Qt::UniqueConnection); + connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()), Qt::UniqueConnection); + connect(telMngr, SIGNAL(connected()), this, SIGNAL(autoPilotConnected()), Qt::UniqueConnection); + connect(telMngr, SIGNAL(disconnected()), this, SIGNAL(autoPilotDisconnected()), Qt::UniqueConnection); + UAVSettingsImportExportFactory *importexportplugin = pm->getObject(); + connect(importexportplugin, SIGNAL(importAboutToBegin()), this, SLOT(invalidateObjects())); } /** * Add a widget to the dirty detection pool * @param widget to add to the detection pool */ -void ConfigTaskWidget::addWidget(QWidget * widget) +void ConfigTaskWidget::addWidget(QWidget *widget) { - addUAVObjectToWidgetRelation("","",widget); + addUAVObjectToWidgetRelation("", "", widget); } /** * Add an object to the management system * @param objectName name of the object to add to the management system */ -void ConfigTaskWidget::addUAVObject(QString objectName,QList * reloadGroups) +void ConfigTaskWidget::addUAVObject(QString objectName, QList *reloadGroups) { - addUAVObjectToWidgetRelation(objectName,"",NULL,0,1,false,reloadGroups); + addUAVObjectToWidgetRelation(objectName, "", NULL, 0, 1, false, reloadGroups); } void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList *reloadGroups) { QString objstr; - if(objectName) - objstr=objectName->getName(); - addUAVObject(objstr, reloadGroups); + if (objectName) { + objstr = objectName->getName(); + } + addUAVObject(objstr, reloadGroups); } /** * Add an UAVObject field to widget relation to the management system @@ -78,25 +79,29 @@ void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList *reloadGro * @param widget pointer to the widget whitch will display/define the field value * @param index index of the field element to add to this relation */ -void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, QString index) +void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index) { - UAVObject *obj=NULL; - UAVObjectField *_field=NULL; - obj = objManager->getObject(QString(object)); + UAVObject *obj = NULL; + UAVObjectField *_field = NULL; + + obj = objManager->getObject(QString(object)); Q_ASSERT(obj); _field = obj->getField(QString(field)); Q_ASSERT(_field); - addUAVObjectToWidgetRelation(object,field,widget,_field->getElementNames().indexOf(index)); + addUAVObjectToWidgetRelation(object, field, widget, _field->getElementNames().indexOf(index)); } -void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field, QWidget *widget, QString index) +void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString index) { QString objstr; QString fieldstr; - if(obj) - objstr=obj->getName(); - if(field) - fieldstr=field->getName(); + + if (obj) { + objstr = obj->getName(); + } + if (field) { + fieldstr = field->getName(); + } addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index); } /** @@ -112,38 +117,45 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie */ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited, QList *defaultReloadGroups, quint32 instID) { - UAVObject *obj=objManager->getObject(QString(object),instID); + UAVObject *obj = objManager->getObject(QString(object), instID); + Q_ASSERT(obj); UAVObjectField *_field; - int index=0; - if(!field.isEmpty() && obj) - { + int index = 0; + if (!field.isEmpty() && obj) { _field = obj->getField(QString(field)); - if(!element.isEmpty()) - index=_field->getElementNames().indexOf(QString(element)); + if (!element.isEmpty()) { + index = _field->getElementNames().indexOf(QString(element)); + } } - addUAVObjectToWidgetRelation(object, field, widget,index,scale,isLimited,defaultReloadGroups,instID); + addUAVObjectToWidgetRelation(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID); } void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited, QList *defaultReloadGroups, quint32 instID) { QString objstr; QString fieldstr; - if(obj) - objstr=obj->getName(); - if(field) - fieldstr=field->getName(); + + if (obj) { + objstr = obj->getName(); + } + if (field) { + fieldstr = field->getName(); + } addUAVObjectToWidgetRelation(objstr, fieldstr, widget, element, scale, isLimited, defaultReloadGroups, instID); } -void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject * obj,UAVObjectField * field, QWidget * widget, int index,double scale,bool isLimited,QList* defaultReloadGroups, quint32 instID) +void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index, double scale, bool isLimited, QList *defaultReloadGroups, quint32 instID) { QString objstr; QString fieldstr; - if(obj) - objstr=obj->getName(); - if(field) - fieldstr=field->getName(); - addUAVObjectToWidgetRelation(objstr,fieldstr,widget,index,scale,isLimited,defaultReloadGroups,instID); + + if (obj) { + objstr = obj->getName(); + } + if (field) { + fieldstr = field->getName(); + } + addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index, scale, isLimited, defaultReloadGroups, instID); } /** @@ -157,63 +169,55 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject * obj,UAVObjectFie * @param defaultReloadGroups default and reload groups this relation belongs to * @param instID instance ID of the object used on this relation */ -void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, int index,double scale,bool isLimited,QList* defaultReloadGroups, quint32 instID) +void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, QList *defaultReloadGroups, quint32 instID) { - if(addShadowWidget(object,field,widget,index,scale,isLimited,defaultReloadGroups,instID)) + if (addShadowWidget(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID)) { return; - - UAVObject *obj=NULL; - UAVObjectField *_field=NULL; - if(!object.isEmpty()) - { - obj = objManager->getObject(QString(object),instID); - Q_ASSERT(obj); - objectUpdates.insert(obj,true); - connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*))); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*)), Qt::UniqueConnection); } - if(!field.isEmpty() && obj) + + UAVObject *obj = NULL; + UAVObjectField *_field = NULL; + if (!object.isEmpty()) { + obj = objManager->getObject(QString(object), instID); + Q_ASSERT(obj); + objectUpdates.insert(obj, true); + connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(objectUpdated(UAVObject *))); + connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection); + } + if (!field.isEmpty() && obj) { _field = obj->getField(QString(field)); - objectToWidget * ow=new objectToWidget(); - ow->field=_field; - ow->object=obj; - ow->widget=widget; - ow->index=index; - ow->scale=scale; - ow->isLimited=isLimited; + } + objectToWidget *ow = new objectToWidget(); + ow->field = _field; + ow->object = obj; + ow->widget = widget; + ow->index = index; + ow->scale = scale; + ow->isLimited = isLimited; objOfInterest.append(ow); - if(obj) - { - if(smartsave) - { - smartsave->addObject((UAVDataObject*)obj); + if (obj) { + if (smartsave) { + smartsave->addObject((UAVDataObject *)obj); } } - if(widget==NULL) - { - if(defaultReloadGroups && obj) - { - foreach(int i,*defaultReloadGroups) - { - if(this->defaultReloadGroups.contains(i)) - { + if (widget == NULL) { + if (defaultReloadGroups && obj) { + foreach(int i, *defaultReloadGroups) { + if (this->defaultReloadGroups.contains(i)) { this->defaultReloadGroups.value(i)->append(ow); - } - else - { - this->defaultReloadGroups.insert(i,new QList()); + } else { + this->defaultReloadGroups.insert(i, new QList()); this->defaultReloadGroups.value(i)->append(ow); } } } - } - else - { - connectWidgetUpdatesToSlot(widget,SLOT(widgetsContentsChanged())); - if(defaultReloadGroups) - addWidgetToDefaultReloadGroups(widget,defaultReloadGroups); - shadowsList.insert(widget,ow); - loadWidgetLimits(widget,_field,index,isLimited,scale); + } else { + connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged())); + if (defaultReloadGroups) { + addWidgetToDefaultReloadGroups(widget, defaultReloadGroups); + } + shadowsList.insert(widget, ow); + loadWidgetLimits(widget, _field, index, isLimited, scale); } } /** @@ -221,20 +225,20 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel */ ConfigTaskWidget::~ConfigTaskWidget() { - if(smartsave) + if (smartsave) { delete smartsave; - foreach(QList* pointer,defaultReloadGroups.values()) - { - if(pointer) + } + foreach(QList *pointer, defaultReloadGroups.values()) { + if (pointer) { delete pointer; + } } - foreach (objectToWidget* oTw, objOfInterest) - { - if(oTw) + foreach(objectToWidget * oTw, objOfInterest) { + if (oTw) { delete oTw; + } } - if(timeOut) - { + if (timeOut) { delete timeOut; timeOut = NULL; } @@ -245,7 +249,8 @@ void ConfigTaskWidget::saveObjectToSD(UAVObject *obj) // saveObjectToSD is now handled by the UAVUtils plugin in one // central place (and one central queue) ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectUtilManager* utilMngr = pm->getObject(); + UAVObjectUtilManager *utilMngr = pm->getObject(); + utilMngr->saveObjectToSD(obj); } @@ -253,9 +258,11 @@ void ConfigTaskWidget::saveObjectToSD(UAVObject *obj) * Util function to get a pointer to the object manager * @return pointer to the UAVObjectManager */ -UAVObjectManager* ConfigTaskWidget::getObjectManager() { +UAVObjectManager *ConfigTaskWidget::getObjectManager() +{ ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager * objMngr = pm->getObject(); + UAVObjectManager *objMngr = pm->getObject(); + Q_ASSERT(objMngr); return objMngr; } @@ -267,8 +274,10 @@ UAVObjectManager* ConfigTaskWidget::getObjectManager() { double ConfigTaskWidget::listMean(QList list) { double accum = 0; - for(int i = 0; i < list.size(); i++) + + for (int i = 0; i < list.size(); i++) { accum += list[i]; + } return accum / list.size(); } @@ -280,15 +289,17 @@ double ConfigTaskWidget::listMean(QList list) double ConfigTaskWidget::listVar(QList list) { double mean_accum = 0; - double var_accum = 0; + double var_accum = 0; double mean; - for(int i = 0; i < list.size(); i++) + for (int i = 0; i < list.size(); i++) { mean_accum += list[i]; + } mean = mean_accum / list.size(); - for(int i = 0; i < list.size(); i++) + for (int i = 0; i < list.size(); i++) { var_accum += (list[i] - mean) * (list[i] - mean); + } // Use unbiased estimator return var_accum / (list.size() - 1); @@ -299,26 +310,26 @@ double ConfigTaskWidget::listVar(QList list) void ConfigTaskWidget::onAutopilotDisconnect() { - isConnected=false; + isConnected = false; enableControls(false); invalidateObjects(); } -void ConfigTaskWidget::forceConnectedState()//dynamic widgets don't recieve the connected signal. This should be called instead. +void ConfigTaskWidget::forceConnectedState() // dynamic widgets don't recieve the connected signal. This should be called instead. { - isConnected=true; + isConnected = true; setDirty(false); } void ConfigTaskWidget::onAutopilotConnect() { - if (utilMngr) - currentBoard = utilMngr->getBoardModel();//TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE + if (utilMngr) { + currentBoard = utilMngr->getBoardModel(); // TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE + } invalidateObjects(); - isConnected=true; - foreach(objectToWidget * ow,objOfInterest) - { - loadWidgetLimits(ow->widget,ow->field,ow->index,ow->isLimited,ow->scale); + isConnected = true; + foreach(objectToWidget * ow, objOfInterest) { + loadWidgetLimits(ow->widget, ow->field, ow->index, ow->isLimited, ow->scale); } setDirty(false); enableControls(true); @@ -330,16 +341,15 @@ void ConfigTaskWidget::onAutopilotConnect() */ void ConfigTaskWidget::populateWidgets() { - bool dirtyBack=dirty; + bool dirtyBack = dirty; emit populateWidgetsRequested(); - foreach(objectToWidget * ow,objOfInterest) - { - if(ow->object==NULL || ow->field==NULL || ow->widget==NULL) - { + + foreach(objectToWidget * ow, objOfInterest) { + if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) { // do nothing + } else { + setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited); } - else - setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale,ow->isLimited); } setDirty(dirtyBack); } @@ -348,28 +358,24 @@ void ConfigTaskWidget::populateWidgets() * object field added to the framework pool * Overwrite this if you need to change the default behavior */ -void ConfigTaskWidget::refreshWidgetsValues(UAVObject * obj) +void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj) { - if (!allowWidgetUpdates) + if (!allowWidgetUpdates) { return; + } - bool dirtyBack=dirty; + bool dirtyBack = dirty; emit refreshWidgetsValuesRequested(); - foreach(objectToWidget * ow,objOfInterest) - { - if(ow->object==NULL || ow->field==NULL || ow->widget==NULL) - { - //do nothing + foreach(objectToWidget * ow, objOfInterest) { + if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) { + // do nothing + } else { + if (ow->object == obj || obj == NULL) { + setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited); + } } - else - { - if(ow->object==obj || obj==NULL) - setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale,ow->isLimited); - } - } setDirty(dirtyBack); - } /** * SLOT function used to update the uavobject fields from widgets with relation to @@ -379,15 +385,11 @@ void ConfigTaskWidget::refreshWidgetsValues(UAVObject * obj) void ConfigTaskWidget::updateObjectsFromWidgets() { emit updateObjectsFromWidgetsRequested(); - foreach(objectToWidget * ow,objOfInterest) - { - if(ow->object==NULL || ow->field==NULL) - { + foreach(objectToWidget * ow, objOfInterest) { + if (ow->object == NULL || ow->field == NULL) {} else { + setFieldFromWidget(ow->widget, ow->field, ow->index, ow->scale); } - else - setFieldFromWidget(ow->widget,ow->field,ow->index,ow->scale); - } } /** @@ -396,9 +398,11 @@ void ConfigTaskWidget::updateObjectsFromWidgets() */ void ConfigTaskWidget::helpButtonPressed() { - QString url=helpButtonList.value((QPushButton*)sender(),QString()); - if(!url.isEmpty()) - QDesktopServices::openUrl( QUrl(url, QUrl::StrictMode) ); + QString url = helpButtonList.value((QPushButton *)sender(), QString()); + + if (!url.isEmpty()) { + QDesktopServices::openUrl(QUrl(url, QUrl::StrictMode)); + } } /** * Add update and save buttons to the form @@ -408,33 +412,28 @@ void ConfigTaskWidget::helpButtonPressed() */ void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save) { - if(!smartsave) - { - smartsave=new smartSaveButton(); - connect(smartsave,SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); - connect(smartsave,SIGNAL(saveSuccessfull()),this,SLOT(clearDirty())); - connect(smartsave,SIGNAL(beginOp()),this,SLOT(disableObjUpdates())); - connect(smartsave,SIGNAL(endOp()),this,SLOT(enableObjUpdates())); + if (!smartsave) { + smartsave = new smartSaveButton(); + connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); + connect(smartsave, SIGNAL(saveSuccessfull()), this, SLOT(clearDirty())); + connect(smartsave, SIGNAL(beginOp()), this, SLOT(disableObjUpdates())); + connect(smartsave, SIGNAL(endOp()), this, SLOT(enableObjUpdates())); } - if(update && save) - smartsave->addButtons(save,update); - else if (update) + if (update && save) { + smartsave->addButtons(save, update); + } else if (update) { smartsave->addApplyButton(update); - else if (save) + } else if (save) { smartsave->addSaveButton(save); - if(objOfInterest.count()>0) - { - foreach(objectToWidget * oTw,objOfInterest) - { - smartsave->addObject((UAVDataObject*)oTw->object); + } + if (objOfInterest.count() > 0) { + foreach(objectToWidget * oTw, objOfInterest) { + smartsave->addObject((UAVDataObject *)oTw->object); } } - TelemetryManager* telMngr = pm->getObject(); - if(telMngr->isConnected()) - enableControls(true); - else - enableControls(false); + updateEnableControls(); } + /** * SLOT function used the enable or disable the SAVE, UPLOAD and RELOAD buttons * @param enable set to true to enable the buttons or false to disable them @@ -442,27 +441,36 @@ void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *sav */ void ConfigTaskWidget::enableControls(bool enable) { - if(smartsave) + if (smartsave) { smartsave->enableControls(enable); - foreach (QPushButton * button, reloadButtonList) { + } + + foreach(QPushButton * button, reloadButtonList) { button->setEnabled(enable); } + + foreach(objectToWidget * ow, objOfInterest) { + if (ow->widget) { + ow->widget->setEnabled(enable); + foreach(shadow * sh, ow->shadowsList) { + sh->widget->setEnabled(enable); + } + } + } } + /** * SLOT function called when on of the widgets contents added to the framework changes */ void ConfigTaskWidget::forceShadowUpdates() { - foreach(objectToWidget * oTw,objOfInterest) - { - foreach (shadow * sh, oTw->shadowsList) - { - disconnectWidgetUpdatesToSlot((QWidget*)sh->widget, SLOT(widgetsContentsChanged())); + foreach(objectToWidget * oTw, objOfInterest) { + foreach(shadow * sh, oTw->shadowsList) { + disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale); setWidgetFromVariant(sh->widget, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale); - emit widgetContentsChanged((QWidget*)sh->widget); - connectWidgetUpdatesToSlot((QWidget*)sh->widget, SLOT(widgetsContentsChanged())); - + emit widgetContentsChanged((QWidget *)sh->widget); + connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); } } setDirty(true); @@ -472,49 +480,44 @@ void ConfigTaskWidget::forceShadowUpdates() */ void ConfigTaskWidget::widgetsContentsChanged() { - emit widgetContentsChanged((QWidget*)sender()); + emit widgetContentsChanged((QWidget *)sender()); double scale; - objectToWidget * oTw= shadowsList.value((QWidget*)sender(),NULL); - if(oTw) - { - if(oTw->widget==(QWidget*)sender()) - { - scale=oTw->scale; - checkWidgetsLimits((QWidget*)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget*)sender(), oTw->scale, oTw->getUnits()), oTw->scale); - } - else - { - foreach (shadow * sh, oTw->shadowsList) - { - if(sh->widget==(QWidget*)sender()) - { - scale=sh->scale; - checkWidgetsLimits((QWidget*)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), scale); + objectToWidget *oTw = shadowsList.value((QWidget *)sender(), NULL); + + if (oTw) { + if (oTw->widget == (QWidget *)sender()) { + scale = oTw->scale; + checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(), + oTw->scale, oTw->getUnits()), oTw->scale); + } else { + foreach(shadow * sh, oTw->shadowsList) { + if (sh->widget == (QWidget *)sender()) { + scale = sh->scale; + checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(), + scale, oTw->getUnits()), scale); } } } - if(oTw->widget!=(QWidget *)sender()) - { - disconnectWidgetUpdatesToSlot((QWidget*)oTw->widget, SLOT(widgetsContentsChanged())); - checkWidgetsLimits(oTw->widget, oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), oTw->scale); - setWidgetFromVariant(oTw->widget, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), oTw->scale); - emit widgetContentsChanged((QWidget*)oTw->widget); - connectWidgetUpdatesToSlot((QWidget*)oTw->widget, SLOT(widgetsContentsChanged())); + if (oTw->widget != (QWidget *)sender()) { + disconnectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged())); + checkWidgetsLimits(oTw->widget, oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale); + setWidgetFromVariant(oTw->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale); + emit widgetContentsChanged((QWidget *)oTw->widget); + connectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged())); } - foreach (shadow * sh, oTw->shadowsList) - { - if(sh->widget!=(QWidget*)sender()) - { - disconnectWidgetUpdatesToSlot((QWidget*)sh->widget,SLOT(widgetsContentsChanged())); - checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), sh->scale); - setWidgetFromVariant(sh->widget, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), sh->scale); - emit widgetContentsChanged((QWidget*)sh->widget); - connectWidgetUpdatesToSlot((QWidget*)sh->widget,SLOT(widgetsContentsChanged())); + foreach(shadow * sh, oTw->shadowsList) { + if (sh->widget != (QWidget *)sender()) { + disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); + checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale); + setWidgetFromVariant(sh->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale); + emit widgetContentsChanged((QWidget *)sh->widget); + connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); } } } - if(smartsave) + if (smartsave) { smartsave->resetIcons(); + } setDirty(true); } /** @@ -530,7 +533,7 @@ void ConfigTaskWidget::clearDirty() */ void ConfigTaskWidget::setDirty(bool value) { - dirty=value; + dirty = value; } /** * Checks if the form is dirty (unsaved changes) @@ -538,10 +541,11 @@ void ConfigTaskWidget::setDirty(bool value) */ bool ConfigTaskWidget::isDirty() { - if(isConnected) + if (isConnected) { return dirty; - else + } else { return false; + } } /** * SLOT function used to disable widget contents changes when related object field changes @@ -549,9 +553,10 @@ bool ConfigTaskWidget::isDirty() void ConfigTaskWidget::disableObjUpdates() { allowWidgetUpdates = false; - foreach(objectToWidget * obj,objOfInterest) - { - if(obj->object)disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*))); + foreach(objectToWidget * obj, objOfInterest) { + if (obj->object) { + disconnect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *))); + } } } /** @@ -560,10 +565,10 @@ void ConfigTaskWidget::disableObjUpdates() void ConfigTaskWidget::enableObjUpdates() { allowWidgetUpdates = true; - foreach(objectToWidget * obj,objOfInterest) - { - if(obj->object) - connect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*)), Qt::UniqueConnection); + foreach(objectToWidget * obj, objOfInterest) { + if (obj->object) { + connect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection); + } } } /** @@ -572,7 +577,7 @@ void ConfigTaskWidget::enableObjUpdates() */ void ConfigTaskWidget::objectUpdated(UAVObject *obj) { - objectUpdates[obj]=true; + objectUpdates[obj] = true; } /** * Checks if all objects added to the pool have already been updated @@ -580,13 +585,12 @@ void ConfigTaskWidget::objectUpdated(UAVObject *obj) */ bool ConfigTaskWidget::allObjectsUpdated() { - qDebug()<<"ConfigTaskWidge:allObjectsUpdated called"; - bool ret=true; - foreach(UAVObject *obj, objectUpdates.keys()) - { - ret=ret & objectUpdates[obj]; + qDebug() << "ConfigTaskWidge:allObjectsUpdated called"; + bool ret = true; + foreach(UAVObject * obj, objectUpdates.keys()) { + ret = ret & objectUpdates[obj]; } - qDebug()<<"Returned:"<apply(); + } } /** * SLOT call this to save changes to uav objects */ void ConfigTaskWidget::save() { - if(smartsave) + if (smartsave) { smartsave->save(); + } } /** * Adds a new shadow widget @@ -632,50 +636,47 @@ void ConfigTaskWidget::save() * This function doesn't have to be used directly, addUAVObjectToWidgetRelation will call it if a previous relation exhists. * @return returns false if the shadow widget relation failed to be added (no previous relation exhisted) */ -bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited,QList* defaultReloadGroups,quint32 instID) +bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, + QList *defaultReloadGroups, quint32 instID) { - foreach(objectToWidget * oTw,objOfInterest) - { - if(!oTw->object || !oTw->widget || !oTw->field) + foreach(objectToWidget * oTw, objOfInterest) { + if (!oTw->object || !oTw->widget || !oTw->field) { continue; - if(oTw->object->getName()==object && oTw->field->getName()==field && oTw->index==index && oTw->object->getInstID()==instID) - { - shadow * sh=NULL; - //prefer anything else to QLabel - if(qobject_cast(oTw->widget) && !qobject_cast(widget)) - { - sh=new shadow; - sh->isLimited=oTw->isLimited; - sh->scale=oTw->scale; - sh->widget=oTw->widget; - oTw->isLimited=isLimited; - oTw->scale=scale; - oTw->widget=widget; + } + if (oTw->object->getName() == object && oTw->field->getName() == field && oTw->index == index && oTw->object->getInstID() == instID) { + shadow *sh = NULL; + // prefer anything else to QLabel + if (qobject_cast(oTw->widget) && !qobject_cast(widget)) { + sh = new shadow; + sh->isLimited = oTw->isLimited; + sh->scale = oTw->scale; + sh->widget = oTw->widget; + oTw->isLimited = isLimited; + oTw->scale = scale; + oTw->widget = widget; } - //prefer QDoubleSpinBox to anything else - else if(!qobject_cast(oTw->widget) && qobject_cast(widget)) - { - sh=new shadow; - sh->isLimited=oTw->isLimited; - sh->scale=oTw->scale; - sh->widget=oTw->widget; - oTw->isLimited=isLimited; - oTw->scale=scale; - oTw->widget=widget; + // prefer QDoubleSpinBox to anything else + else if (!qobject_cast(oTw->widget) && qobject_cast(widget)) { + sh = new shadow; + sh->isLimited = oTw->isLimited; + sh->scale = oTw->scale; + sh->widget = oTw->widget; + oTw->isLimited = isLimited; + oTw->scale = scale; + oTw->widget = widget; + } else { + sh = new shadow; + sh->isLimited = isLimited; + sh->scale = scale; + sh->widget = widget; } - else - { - sh=new shadow; - sh->isLimited=isLimited; - sh->scale=scale; - sh->widget=widget; - } - shadowsList.insert(widget,oTw); + shadowsList.insert(widget, oTw); oTw->shadowsList.append(sh); - connectWidgetUpdatesToSlot(widget,SLOT(widgetsContentsChanged())); - if(defaultReloadGroups) - addWidgetToDefaultReloadGroups(widget,defaultReloadGroups); - loadWidgetLimits(widget,oTw->field,oTw->index,isLimited,scale); + connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged())); + if (defaultReloadGroups) { + addWidgetToDefaultReloadGroups(widget, defaultReloadGroups); + } + loadWidgetLimits(widget, oTw->field, oTw->index, isLimited, scale); return true; } } @@ -687,118 +688,115 @@ bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *w */ void ConfigTaskWidget::autoLoadWidgets() { - QPushButton * saveButtonWidget=NULL; - QPushButton * applyButtonWidget=NULL; - foreach(QWidget * widget,this->findChildren()) - { - QVariant info=widget->property("objrelation"); - if(info.isValid()) - { + QPushButton *saveButtonWidget = NULL; + QPushButton *applyButtonWidget = NULL; + + foreach(QWidget * widget, this->findChildren()) { + QVariant info = widget->property("objrelation"); + + if (info.isValid()) { uiRelationAutomation uiRelation; - uiRelation.buttonType=none; - uiRelation.scale=1; - uiRelation.element=QString(); - uiRelation.haslimits=false; - foreach(QString str, info.toStringList()) - { - QString prop=str.split(":").at(0); - QString value=str.split(":").at(1); - if(prop== "objname") - uiRelation.objname=value; - else if(prop== "fieldname") - uiRelation.fieldname=value; - else if(prop=="element") - uiRelation.element=value; - else if(prop== "scale") - { - if(value=="null") - uiRelation.scale=1; - else - uiRelation.scale=value.toDouble(); - } - else if(prop== "haslimits") - { - if(value=="yes") - uiRelation.haslimits=true; - else - uiRelation.haslimits=false; - } - else if(prop== "button") - { - if(value=="save") - uiRelation.buttonType=save_button; - else if(value=="apply") - uiRelation.buttonType=apply_button; - else if(value=="reload") - uiRelation.buttonType=reload_button; - else if(value=="default") - uiRelation.buttonType=default_button; - else if(value=="help") - uiRelation.buttonType=help_button; - } - else if(prop== "buttongroup") - { - foreach(QString s,value.split(",")) - { + uiRelation.buttonType = none; + uiRelation.scale = 1; + uiRelation.element = QString(); + uiRelation.haslimits = false; + foreach(QString str, info.toStringList()) { + QString prop = str.split(":").at(0); + QString value = str.split(":").at(1); + + if (prop == "objname") { + uiRelation.objname = value; + } else if (prop == "fieldname") { + uiRelation.fieldname = value; + } else if (prop == "element") { + uiRelation.element = value; + } else if (prop == "scale") { + if (value == "null") { + uiRelation.scale = 1; + } else { + uiRelation.scale = value.toDouble(); + } + } else if (prop == "haslimits") { + if (value == "yes") { + uiRelation.haslimits = true; + } else { + uiRelation.haslimits = false; + } + } else if (prop == "button") { + if (value == "save") { + uiRelation.buttonType = save_button; + } else if (value == "apply") { + uiRelation.buttonType = apply_button; + } else if (value == "reload") { + uiRelation.buttonType = reload_button; + } else if (value == "default") { + uiRelation.buttonType = default_button; + } else if (value == "help") { + uiRelation.buttonType = help_button; + } + } else if (prop == "buttongroup") { + foreach(QString s, value.split(",")) { uiRelation.buttonGroup.append(s.toInt()); } + } else if (prop == "url") { + uiRelation.url = str.mid(str.indexOf(":") + 1); } - else if(prop=="url") - uiRelation.url=str.mid(str.indexOf(":")+1); } - if(!uiRelation.buttonType==none) - { - QPushButton * button=NULL; - switch(uiRelation.buttonType) - { + if (!uiRelation.buttonType == none) { + QPushButton *button = NULL; + switch (uiRelation.buttonType) { case save_button: - saveButtonWidget=qobject_cast(widget); - if(saveButtonWidget) - addApplySaveButtons(NULL,saveButtonWidget); + saveButtonWidget = qobject_cast(widget); + if (saveButtonWidget) { + addApplySaveButtons(NULL, saveButtonWidget); + } break; case apply_button: - applyButtonWidget=qobject_cast(widget); - if(applyButtonWidget) - addApplySaveButtons(applyButtonWidget,NULL); + applyButtonWidget = qobject_cast(widget); + if (applyButtonWidget) { + addApplySaveButtons(applyButtonWidget, NULL); + } break; case default_button: - button=qobject_cast(widget); - if(button) - addDefaultButton(button,uiRelation.buttonGroup.at(0)); + button = qobject_cast(widget); + if (button) { + addDefaultButton(button, uiRelation.buttonGroup.at(0)); + } break; case reload_button: - button=qobject_cast(widget); - if(button) - addReloadButton(button,uiRelation.buttonGroup.at(0)); + button = qobject_cast(widget); + if (button) { + addReloadButton(button, uiRelation.buttonGroup.at(0)); + } break; case help_button: - button=qobject_cast(widget); - if(button) - addHelpButton(button,uiRelation.url); + button = qobject_cast(widget); + if (button) { + addHelpButton(button, uiRelation.url); + } break; default: break; } - } - else - { - QWidget * wid=qobject_cast(widget); - if(wid) - addUAVObjectToWidgetRelation(uiRelation.objname,uiRelation.fieldname,wid,uiRelation.element,uiRelation.scale,uiRelation.haslimits,&uiRelation.buttonGroup); + } else { + QWidget *wid = qobject_cast(widget); + if (wid) { + addUAVObjectToWidgetRelation(uiRelation.objname, uiRelation.fieldname, wid, uiRelation.element, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup); + } } } } refreshWidgetsValues(); forceShadowUpdates(); - foreach(objectToWidget * ow,objOfInterest) - { - if(ow->widget) - qDebug()<<"Master:"<widget->objectName(); - foreach(shadow * sh,ow->shadowsList) - { - if(sh->widget) - qDebug()<<"Child"<widget->objectName(); + foreach(objectToWidget * ow, objOfInterest) { + if (ow->widget) { + qDebug() << "Master:" << ow->widget->objectName(); + } + foreach(shadow * sh, ow->shadowsList) { + if (sh->widget) { + qDebug() << "Child" << sh->widget->objectName(); + } } } } @@ -808,32 +806,26 @@ void ConfigTaskWidget::autoLoadWidgets() * @param widget pointer to the widget to be added to the groups * @param groups list of the groups on which to add the widget */ -void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList * groups) +void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList *groups) { - foreach(objectToWidget * oTw,objOfInterest) - { - bool addOTW=false; - if(oTw->widget==widget) - addOTW=true; - else - { - foreach(shadow * sh, oTw->shadowsList) - { - if(sh->widget==widget) - addOTW=true; + foreach(objectToWidget * oTw, objOfInterest) { + bool addOTW = false; + + if (oTw->widget == widget) { + addOTW = true; + } else { + foreach(shadow * sh, oTw->shadowsList) { + if (sh->widget == widget) { + addOTW = true; + } } } - if(addOTW) - { - foreach(int i,*groups) - { - if(defaultReloadGroups.contains(i)) - { + if (addOTW) { + foreach(int i, *groups) { + if (defaultReloadGroups.contains(i)) { defaultReloadGroups.value(i)->append(oTw); - } - else - { - defaultReloadGroups.insert(i,new QList()); + } else { + defaultReloadGroups.insert(i, new QList()); defaultReloadGroups.value(i)->append(oTw); } } @@ -847,8 +839,8 @@ void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QListsetProperty("group",buttonGroup); - connect(button,SIGNAL(clicked()),this,SLOT(defaultButtonClicked())); + button->setProperty("group", buttonGroup); + connect(button, SIGNAL(clicked()), this, SLOT(defaultButtonClicked())); } /** * Adds a button to a reload group @@ -857,24 +849,25 @@ void ConfigTaskWidget::addDefaultButton(QPushButton *button, int buttonGroup) */ void ConfigTaskWidget::addReloadButton(QPushButton *button, int buttonGroup) { - button->setProperty("group",buttonGroup); + button->setProperty("group", buttonGroup); reloadButtonList.append(button); - connect(button,SIGNAL(clicked()),this,SLOT(reloadButtonClicked())); + connect(button, SIGNAL(clicked()), this, SLOT(reloadButtonClicked())); } /** * Called when a default button is clicked */ void ConfigTaskWidget::defaultButtonClicked() { - int group=sender()->property("group").toInt(); + int group = sender()->property("group").toInt(); emit defaultRequested(group); - QList * list=defaultReloadGroups.value(group); - foreach(objectToWidget * oTw,*list) - { - if(!oTw->object || !oTw->field) + + QList *list = defaultReloadGroups.value(group); + foreach(objectToWidget * oTw, *list) { + if (!oTw->object || !oTw->field) { continue; - UAVDataObject * temp=((UAVDataObject*)oTw->object)->dirtyClone(); - setWidgetFromField(oTw->widget,temp->getField(oTw->field->getName()),oTw->index,oTw->scale,oTw->isLimited); + } + UAVDataObject *temp = ((UAVDataObject *)oTw->object)->dirtyClone(); + setWidgetFromField(oTw->widget, temp->getField(oTw->field->getName()), oTw->index, oTw->scale, oTw->isLimited); } } /** @@ -882,145 +875,114 @@ void ConfigTaskWidget::defaultButtonClicked() */ void ConfigTaskWidget::reloadButtonClicked() { - if(timeOut) + if (timeOut) { return; - int group=sender()->property("group").toInt(); - QList * list=defaultReloadGroups.value(group,NULL); - if(!list) + } + int group = sender()->property("group").toInt(); + QList *list = defaultReloadGroups.value(group, NULL); + if (!list) { return; - ObjectPersistence* objper = dynamic_cast( getObjectManager()->getObject(ObjectPersistence::NAME) ); - timeOut=new QTimer(this); - QEventLoop * eventLoop=new QEventLoop(this); - connect(timeOut, SIGNAL(timeout()),eventLoop,SLOT(quit())); - connect(objper, SIGNAL(objectUpdated(UAVObject*)), eventLoop, SLOT(quit())); + } + ObjectPersistence *objper = dynamic_cast(getObjectManager()->getObject(ObjectPersistence::NAME)); + timeOut = new QTimer(this); + QEventLoop *eventLoop = new QEventLoop(this); + connect(timeOut, SIGNAL(timeout()), eventLoop, SLOT(quit())); + connect(objper, SIGNAL(objectUpdated(UAVObject *)), eventLoop, SLOT(quit())); QList temp; - foreach(objectToWidget * oTw,*list) - { - if (oTw->object != NULL) - { + foreach(objectToWidget * oTw, *list) { + if (oTw->object != NULL) { temphelper value; - value.objid=oTw->object->getObjID(); - value.objinstid=oTw->object->getInstID(); - if(temp.contains(value)) + value.objid = oTw->object->getObjID(); + value.objinstid = oTw->object->getInstID(); + if (temp.contains(value)) { continue; - else + } else { temp.append(value); + } ObjectPersistence::DataFields data; - data.Operation = ObjectPersistence::OPERATION_LOAD; - data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT; - data.ObjectID = oTw->object->getObjID(); + data.Operation = ObjectPersistence::OPERATION_LOAD; + data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT; + data.ObjectID = oTw->object->getObjID(); data.InstanceID = oTw->object->getInstID(); objper->setData(data); objper->updated(); timeOut->start(500); eventLoop->exec(); - if(timeOut->isActive()) - { + if (timeOut->isActive()) { oTw->object->requestUpdate(); - if(oTw->widget) - setWidgetFromField(oTw->widget,oTw->field,oTw->index,oTw->scale,oTw->isLimited); + if (oTw->widget) { + setWidgetFromField(oTw->widget, oTw->field, oTw->index, oTw->scale, oTw->isLimited); + } } timeOut->stop(); } } - if(eventLoop) - { + if (eventLoop) { delete eventLoop; - eventLoop=NULL; + eventLoop = NULL; } - if(timeOut) - { + if (timeOut) { delete timeOut; - timeOut=NULL; + timeOut = NULL; } } /** * Connects widgets "contents changed" signals to a slot */ -void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget * widget,const char* function) +void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget *widget, const char *function) { - if(!widget) + if (!widget) { return; - if(QComboBox * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(currentIndexChanged(int)),this,function); } - else if(QSlider * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(valueChanged(int)),this,function); + if (QComboBox * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(currentIndexChanged(int)), this, function); + } else if (QSlider * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(valueChanged(int)), this, function); + } else if (MixerCurveWidget * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(curveUpdated()), this, function); + } else if (QTableWidget * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(cellChanged(int, int)), this, function); + } else if (QSpinBox * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(valueChanged(int)), this, function); + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(valueChanged(double)), this, function); + } else if (QCheckBox * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(stateChanged(int)), this, function); + } else if (QPushButton * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(clicked()), this, function); + } else { + qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); } - else if(MixerCurveWidget * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(curveUpdated()),this,function); - } - else if(QTableWidget * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(cellChanged(int,int)),this,function); - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(valueChanged(int)),this,function); - } - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(valueChanged(double)),this,function); - } - else if(QCheckBox * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(stateChanged(int)),this,function); - } - else if(QPushButton * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(clicked()),this,function); - } - else - qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<metaObject()->className(); - } /** * Disconnects widgets "contents changed" signals to a slot */ -void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget * widget,const char* function) +void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function) { - if(!widget) + if (!widget) { return; - if(QComboBox * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(currentIndexChanged(int)),this,function); } - else if(QSlider * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(valueChanged(int)),this,function); + if (QComboBox * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(currentIndexChanged(int)), this, function); + } else if (QSlider * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(valueChanged(int)), this, function); + } else if (MixerCurveWidget * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(curveUpdated()), this, function); + } else if (QTableWidget * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(cellChanged(int, int)), this, function); + } else if (QSpinBox * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(valueChanged(int)), this, function); + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(valueChanged(double)), this, function); + } else if (QCheckBox * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(stateChanged(int)), this, function); + } else if (QPushButton * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(clicked()), this, function); + } else { + qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); } - else if(MixerCurveWidget * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(curveUpdated()),this,function); - } - else if(QTableWidget * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(cellChanged(int,int)),this,function); - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(valueChanged(int)),this,function); - } - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(valueChanged(double)),this,function); - } - else if(QCheckBox * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(stateChanged(int)),this,function); - } - else if(QPushButton * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(clicked()),this,function); - } - else - qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<metaObject()->className(); - } /** * Sets a widget value from an UAVObject field @@ -1030,18 +992,18 @@ void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget * widget,const char * @param scale scale to be used on the assignement * @return returns true if the assignement was successfull */ -bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * field,int index,double scale) +bool ConfigTaskWidget::setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale) { - if(!widget || !field) + if (!widget || !field) { return false; + } QVariant ret = getVariantFromWidget(widget, scale, field->getUnits()); - if(ret.isValid()) - { - field->setValue(ret,index); + if (ret.isValid()) { + field->setValue(ret, index); return true; } { - qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<metaObject()->className(); + qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); return false; } } @@ -1053,38 +1015,27 @@ bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * fiel */ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, QString units) { - if(QComboBox * cb=qobject_cast(widget)) - { + if (QComboBox * cb = qobject_cast(widget)) { return (QString)cb->currentText(); - } - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - return (double)(cb->value()* scale); - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - return (double)(cb->value()* scale); - } - else if(QSlider * cb=qobject_cast(widget)) - { - return(double)(cb->value()* scale); - } - else if(QCheckBox * cb=qobject_cast(widget)) - { - return (QString)(cb->isChecked()?"TRUE":"FALSE"); - } - else if(QLineEdit * cb=qobject_cast(widget)) - { + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + return (double)(cb->value() * scale); + } else if (QSpinBox * cb = qobject_cast(widget)) { + return (double)(cb->value() * scale); + } else if (QSlider * cb = qobject_cast(widget)) { + return (double)(cb->value() * scale); + } else if (QCheckBox * cb = qobject_cast(widget)) { + return (QString)(cb->isChecked() ? "TRUE" : "FALSE"); + } else if (QLineEdit * cb = qobject_cast(widget)) { QString value = (QString)cb->displayText(); - if(units == "hex") { + if (units == "hex") { bool ok; return value.toUInt(&ok, 16); } else { return value; } - } - else + } else { return QVariant(); + } } /** * Sets a widget from a variant @@ -1096,55 +1047,43 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, Q */ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units) { - if(QComboBox * cb=qobject_cast(widget)) - { + if (QComboBox * cb = qobject_cast(widget)) { cb->setCurrentIndex(cb->findText(value.toString())); return true; - } - else if(QLabel * cb=qobject_cast(widget)) - { - if(scale==0) + } else if (QLabel * cb = qobject_cast(widget)) { + if (scale == 0) { cb->setText(value.toString()); - else - cb->setText(QString::number((value.toDouble()/scale))); + } else { + cb->setText(QString::number((value.toDouble() / scale))); + } return true; - } - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - cb->setValue((double)(value.toDouble()/scale)); + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + cb->setValue((double)(value.toDouble() / scale)); return true; - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - cb->setValue((int)qRound(value.toDouble()/scale)); + } else if (QSpinBox * cb = qobject_cast(widget)) { + cb->setValue((int)qRound(value.toDouble() / scale)); return true; - } - else if(QSlider * cb=qobject_cast(widget)) - { - cb->setValue((int)qRound(value.toDouble()/scale)); + } else if (QSlider * cb = qobject_cast(widget)) { + cb->setValue((int)qRound(value.toDouble() / scale)); return true; - } - else if(QCheckBox * cb=qobject_cast(widget)) - { - bool bvalue=value.toString()=="TRUE"; + } else if (QCheckBox * cb = qobject_cast(widget)) { + bool bvalue = value.toString() == "TRUE"; cb->setChecked(bvalue); return true; - } - else if(QLineEdit * cb=qobject_cast(widget)) - { - if ((scale== 0) || (scale == 1)) { - if(units == "hex") { + } else if (QLineEdit * cb = qobject_cast(widget)) { + if ((scale == 0) || (scale == 1)) { + if (units == "hex") { cb->setText(QString::number(value.toUInt(), 16).toUpper()); } else { cb->setText(value.toString()); } } else { - cb->setText(QString::number((value.toDouble()/scale))); + cb->setText(QString::number((value.toDouble() / scale))); } return true; - } - else + } else { return false; + } } /** @@ -1168,178 +1107,154 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou * @param hasLimits set to true if you want to limit the values (check wiki) * @return returns true if the assignement was successfull */ -bool ConfigTaskWidget::setWidgetFromField(QWidget * widget,UAVObjectField * field,int index,double scale,bool hasLimits) +bool ConfigTaskWidget::setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits) { - if(!widget || !field) + if (!widget || !field) { return false; - if(QComboBox * cb=qobject_cast(widget)) - { - if(cb->count()==0) - loadWidgetLimits(cb,field,index,hasLimits,scale); } - QVariant var=field->getValue(index); - checkWidgetsLimits(widget,field,index,hasLimits,var,scale); - bool ret = setWidgetFromVariant(widget, var, scale, field->getUnits()); - if(ret) + if (QComboBox * cb = qobject_cast(widget)) { + if (cb->count() == 0) { + loadWidgetLimits(cb, field, index, hasLimits, scale); + } + } + QVariant var = field->getValue(index); + checkWidgetsLimits(widget, field, index, hasLimits, var, scale); + bool ret = setWidgetFromVariant(widget, var, scale, field->getUnits()); + if (ret) { return true; - else - { - qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<metaObject()->className(); + } else { + qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); return false; } } -void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits, QVariant value, double scale) +void ConfigTaskWidget::checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale) { - if(!hasLimits) + if (!hasLimits) { return; - if(!field->isWithinLimits(value,index,currentBoard)) - { - if(!widget->property("styleBackup").isValid()) - widget->setProperty("styleBackup",widget->styleSheet()); - widget->setStyleSheet(outOfLimitsStyle); - widget->setProperty("wasOverLimits",(bool)true); - if(QComboBox * cb=qobject_cast(widget)) - { - if(cb->findText(value.toString())==-1) - cb->addItem(value.toString()); - } - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - if((double)(value.toDouble()/scale)>cb->maximum()) - { - cb->setMaximum((double)(value.toDouble()/scale)); - } - else if((double)(value.toDouble()/scale)minimum()) - { - cb->setMinimum((double)(value.toDouble()/scale)); - } - - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - if((int)qRound(value.toDouble()/scale)>cb->maximum()) - { - cb->setMaximum((int)qRound(value.toDouble()/scale)); - } - else if((int)qRound(value.toDouble()/scale)minimum()) - { - cb->setMinimum((int)qRound(value.toDouble()/scale)); - } - } - else if(QSlider * cb=qobject_cast(widget)) - { - if((int)qRound(value.toDouble()/scale)>cb->maximum()) - { - cb->setMaximum((int)qRound(value.toDouble()/scale)); - } - else if((int)qRound(value.toDouble()/scale)minimum()) - { - cb->setMinimum((int)qRound(value.toDouble()/scale)); - } - } - } - else if(widget->property("wasOverLimits").isValid()) - { - if(widget->property("wasOverLimits").toBool()) - { - widget->setProperty("wasOverLimits",(bool)false); - if(widget->property("styleBackup").isValid()) - { - QString style=widget->property("styleBackup").toString(); + if (!field->isWithinLimits(value, index, currentBoard)) { + if (!widget->property("styleBackup").isValid()) { + widget->setProperty("styleBackup", widget->styleSheet()); + } + widget->setStyleSheet(outOfLimitsStyle); + widget->setProperty("wasOverLimits", (bool)true); + if (QComboBox * cb = qobject_cast(widget)) { + if (cb->findText(value.toString()) == -1) { + cb->addItem(value.toString()); + } + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + if ((double)(value.toDouble() / scale) > cb->maximum()) { + cb->setMaximum((double)(value.toDouble() / scale)); + } else if ((double)(value.toDouble() / scale) < cb->minimum()) { + cb->setMinimum((double)(value.toDouble() / scale)); + } + } else if (QSpinBox * cb = qobject_cast(widget)) { + if ((int)qRound(value.toDouble() / scale) > cb->maximum()) { + cb->setMaximum((int)qRound(value.toDouble() / scale)); + } else if ((int)qRound(value.toDouble() / scale) < cb->minimum()) { + cb->setMinimum((int)qRound(value.toDouble() / scale)); + } + } else if (QSlider * cb = qobject_cast(widget)) { + if ((int)qRound(value.toDouble() / scale) > cb->maximum()) { + cb->setMaximum((int)qRound(value.toDouble() / scale)); + } else if ((int)qRound(value.toDouble() / scale) < cb->minimum()) { + cb->setMinimum((int)qRound(value.toDouble() / scale)); + } + } + } else if (widget->property("wasOverLimits").isValid()) { + if (widget->property("wasOverLimits").toBool()) { + widget->setProperty("wasOverLimits", (bool)false); + if (widget->property("styleBackup").isValid()) { + QString style = widget->property("styleBackup").toString(); widget->setStyleSheet(style); } - loadWidgetLimits(widget,field,index,hasLimits,scale); + loadWidgetLimits(widget, field, index, hasLimits, scale); } } } -void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits,double scale) -{ - if(!widget || !field) +void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double scale) +{ + if (!widget || !field) { return; - if(QComboBox * cb=qobject_cast(widget)) - { + } + if (QComboBox * cb = qobject_cast(widget)) { cb->clear(); - QStringList option=field->getOptions(); - if(hasLimits) - { - foreach(QString str,option) - { - if(field->isWithinLimits(str,index,currentBoard)) + QStringList option = field->getOptions(); + if (hasLimits) { + foreach(QString str, option) { + if (field->isWithinLimits(str, index, currentBoard)) { cb->addItem(str); + } } - } - else + } else { cb->addItems(option); + } } - if(!hasLimits) + if (!hasLimits) { return; - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - if(field->getMaxLimit(index).isValid()) - { - cb->setMaximum((double)(field->getMaxLimit(index,currentBoard).toDouble()/scale)); + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + if (field->getMaxLimit(index).isValid()) { + cb->setMaximum((double)(field->getMaxLimit(index, currentBoard).toDouble() / scale)); } - if(field->getMinLimit(index,currentBoard).isValid()) - { - cb->setMinimum((double)(field->getMinLimit(index,currentBoard).toDouble()/scale)); - } - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - if(field->getMaxLimit(index,currentBoard).isValid()) - { - cb->setMaximum((int)qRound(field->getMaxLimit(index,currentBoard).toDouble()/scale)); - } - if(field->getMinLimit(index,currentBoard).isValid()) - { - cb->setMinimum((int)qRound(field->getMinLimit(index,currentBoard).toDouble()/scale)); - } - } - else if(QSlider * cb=qobject_cast(widget)) - { - if(field->getMaxLimit(index,currentBoard).isValid()) - { - cb->setMaximum((int)qRound(field->getMaxLimit(index,currentBoard).toDouble()/scale)); - } - if(field->getMinLimit(index,currentBoard).isValid()) - { - cb->setMinimum((int)(field->getMinLimit(index,currentBoard).toDouble()/scale)); + if (field->getMinLimit(index, currentBoard).isValid()) { + cb->setMinimum((double)(field->getMinLimit(index, currentBoard).toDouble() / scale)); + } + } else if (QSpinBox * cb = qobject_cast(widget)) { + if (field->getMaxLimit(index, currentBoard).isValid()) { + cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale)); + } + if (field->getMinLimit(index, currentBoard).isValid()) { + cb->setMinimum((int)qRound(field->getMinLimit(index, currentBoard).toDouble() / scale)); + } + } else if (QSlider * cb = qobject_cast(widget)) { + if (field->getMaxLimit(index, currentBoard).isValid()) { + cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale)); + } + if (field->getMinLimit(index, currentBoard).isValid()) { + cb->setMinimum((int)(field->getMinLimit(index, currentBoard).toDouble() / scale)); } } } +void ConfigTaskWidget::updateEnableControls() +{ + TelemetryManager *telMngr = pm->getObject(); + + Q_ASSERT(telMngr); + enableControls(telMngr->isConnected()); +} + void ConfigTaskWidget::disableMouseWheelEvents() { - //Disable mouse wheel events - foreach( QSpinBox * sp, findChildren() ) { - sp->installEventFilter( this ); + // Disable mouse wheel events + foreach(QSpinBox * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QDoubleSpinBox * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QDoubleSpinBox * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QSlider * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QSlider * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QComboBox * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QComboBox * sp, findChildren()) { + sp->installEventFilter(this); } } -bool ConfigTaskWidget::eventFilter( QObject * obj, QEvent * evt ) { - //Filter all wheel events, and ignore them - if ( evt->type() == QEvent::Wheel && - (qobject_cast( obj ) || - qobject_cast( obj ) || - qobject_cast( obj ) )) - { +bool ConfigTaskWidget::eventFilter(QObject *obj, QEvent *evt) +{ + // Filter all wheel events, and ignore them + if (evt->type() == QEvent::Wheel && + (qobject_cast(obj) || + qobject_cast(obj) || + qobject_cast(obj))) { evt->ignore(); return true; } - return QWidget::eventFilter( obj, evt ); + return QWidget::eventFilter(obj, evt); } /** - @} - @} - */ + @} + @} + */ diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index 78f0c5b0c..461366251 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -48,53 +48,49 @@ #include #include -class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget: public QWidget -{ +class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget : public QWidget { Q_OBJECT public: - struct shadow - { - QWidget * widget; - double scale; - bool isLimited; + struct shadow { + QWidget *widget; + double scale; + bool isLimited; }; - struct objectToWidget - { - UAVObject * object; - UAVObjectField * field; - QWidget * widget; + struct objectToWidget { + UAVObject *object; + UAVObjectField *field; + QWidget *widget; int index; - double scale; + double scale; bool isLimited; QList shadowsList; - QString getUnits() const { + QString getUnits() const + { if (field) { return field->getUnits(); } - return QString(""); + return QString(""); } }; - struct temphelper - { + struct temphelper { quint32 objid; quint32 objinstid; - bool operator==(const temphelper& lhs) + bool operator==(const temphelper & lhs) { - return (lhs.objid==this->objid && lhs.objinstid==this->objinstid); + return lhs.objid == this->objid && lhs.objinstid == this->objinstid; } }; - enum buttonTypeEnum {none,save_button,apply_button,reload_button,default_button,help_button}; - struct uiRelationAutomation - { - QString objname; - QString fieldname; - QString element; - QString url; + enum buttonTypeEnum { none, save_button, apply_button, reload_button, default_button, help_button }; + struct uiRelationAutomation { + QString objname; + QString fieldname; + QString element; + QString url; buttonTypeEnum buttonType; - QList buttonGroup; + QList buttonGroup; double scale; bool haslimits; }; @@ -103,37 +99,37 @@ public: virtual ~ConfigTaskWidget(); void disableMouseWheelEvents(); - bool eventFilter( QObject * obj, QEvent * evt ); + bool eventFilter(QObject *obj, QEvent *evt); void saveObjectToSD(UAVObject *obj); - UAVObjectManager* getObjectManager(); + UAVObjectManager *getObjectManager(); static double listMean(QList list); static double listVar(QList list); - void addUAVObject(QString objectName, QList *reloadGroups=NULL); - void addUAVObject(UAVObject * objectName, QList *reloadGroups=NULL); + void addUAVObject(QString objectName, QList *reloadGroups = NULL); + void addUAVObject(UAVObject *objectName, QList *reloadGroups = NULL); - void addWidget(QWidget * widget); + void addWidget(QWidget *widget); - void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,double scale=1,bool isLimited=false,QList* defaultReloadGroups=0,quint32 instID=0); - void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field, QWidget *widget, int index=0, double scale=1, bool isLimited=false, QList *defaultReloadGroups=0, quint32 instID=0); + void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList *defaultReloadGroups = 0, quint32 instID = 0); + void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList *defaultReloadGroups = 0, quint32 instID = 0); - void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,QString element,double scale,bool isLimited=false,QList* defaultReloadGroups=0,quint32 instID=0); - void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field,QWidget * widget,QString element,double scale,bool isLimited=false,QList* defaultReloadGroups=0,quint32 instID=0); + void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited = false, QList *defaultReloadGroups = 0, quint32 instID = 0); + void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited = false, QList *defaultReloadGroups = 0, quint32 instID = 0); void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index); - void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field, QWidget *widget, QString index); + void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString index); - //BUTTONS// - void addApplySaveButtons(QPushButton * update,QPushButton * save); - void addReloadButton(QPushButton * button,int buttonGroup); - void addDefaultButton(QPushButton * button,int buttonGroup); + // BUTTONS// + void addApplySaveButtons(QPushButton *update, QPushButton *save); + void addReloadButton(QPushButton *button, int buttonGroup); + void addDefaultButton(QPushButton *button, int buttonGroup); ////////// - void addWidgetToDefaultReloadGroups(QWidget * widget, QList *groups); + void addWidgetToDefaultReloadGroups(QWidget *widget, QList *groups); - bool addShadowWidget(QWidget * masterWidget, QWidget * shadowWidget,double shadowScale=1,bool shadowIsLimited=false); - bool addShadowWidget(QString object,QString field,QWidget * widget,int index=0,double scale=1,bool isLimited=false, QList *defaultReloadGroups=NULL, quint32 instID=0); + bool addShadowWidget(QWidget *masterWidget, QWidget *shadowWidget, double shadowScale = 1, bool shadowIsLimited = false); + bool addShadowWidget(QString object, QString field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList *defaultReloadGroups = NULL, quint32 instID = 0); void autoLoadWidgets(); @@ -141,8 +137,11 @@ public: void setDirty(bool value); bool allObjectsUpdated(); - void setOutOfLimitsStyle(QString style){outOfLimitsStyle=style;} - void addHelpButton(QPushButton * button,QString url); + void setOutOfLimitsStyle(QString style) + { + outOfLimitsStyle = style; + } + void addHelpButton(QPushButton *button, QString url); void forceShadowUpdates(); void forceConnectedState(); public slots: @@ -152,21 +151,21 @@ public slots: void apply(); void save(); signals: - //fired when a widgets contents changes - void widgetContentsChanged(QWidget * widget); - //fired when the framework requests that the widgets values be populated, use for custom behaviour + // fired when a widgets contents changes + void widgetContentsChanged(QWidget *widget); + // fired when the framework requests that the widgets values be populated, use for custom behaviour void populateWidgetsRequested(); - //fired when the framework requests that the widgets values be refreshed, use for custom behaviour + // fired when the framework requests that the widgets values be refreshed, use for custom behaviour void refreshWidgetsValuesRequested(); - //fired when the framework requests that the UAVObject values be updated from the widgets value, use for custom behaviour + // fired when the framework requests that the UAVObject values be updated from the widgets value, use for custom behaviour void updateObjectsFromWidgetsRequested(); - //fired when the autopilot connects + // fired when the autopilot connects void autoPilotConnected(); - //fired when the autopilot disconnects + // fired when the autopilot disconnects void autoPilotDisconnected(); void defaultRequested(int group); private slots: - void objectUpdated(UAVObject*); + void objectUpdated(UAVObject *); void defaultButtonClicked(); void reloadButtonClicked(); private: @@ -174,15 +173,15 @@ private: bool isConnected; bool allowWidgetUpdates; QStringList objectsList; - QList objOfInterest; + QList objOfInterest; ExtensionSystem::PluginManager *pm; UAVObjectManager *objManager; - UAVObjectUtilManager* utilMngr; + UAVObjectUtilManager *utilMngr; smartSaveButton *smartsave; - QMap objectUpdates; - QMap *> defaultReloadGroups; - QMap shadowsList; - QMap helpButtonList; + QMap objectUpdates; + QMap *> defaultReloadGroups; + QMap shadowsList; + QMap helpButtonList; QList reloadButtonList; bool dirty; bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale); @@ -194,19 +193,21 @@ private: void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function); void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale); QString outOfLimitsStyle; - QTimer * timeOut; + QTimer *timeOut; + protected slots: virtual void disableObjUpdates(); virtual void enableObjUpdates(); virtual void clearDirty(); virtual void widgetsContentsChanged(); virtual void populateWidgets(); - virtual void refreshWidgetsValues(UAVObject * obj=NULL); + virtual void refreshWidgetsValues(UAVObject *obj = NULL); virtual void updateObjectsFromWidgets(); virtual void helpButtonPressed(); protected: virtual void enableControls(bool enable); void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale); + void updateEnableControls(); }; #endif // CONFIGTASKWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp index c4462fc94..2ad7d4b95 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp @@ -43,17 +43,15 @@ MixerNode::MixerNode(MixerCurveWidget *graphWidget) setFlag(ItemSendsGeometryChanges); setCacheMode(DeviceCoordinateCache); setZValue(-1); - cmdActive = false; vertical = false; - cmdNode = false; - cmdToggle = true; drawNode = true; drawText = true; - posColor0 = "#1c870b"; //greenish? - posColor1 = "#116703"; //greenish? - negColor0 = "#aa0000"; //red - negColor1 = "#aa0000"; //red + positiveColor = "#609FF2"; //blueish? + neutralColor = "#14CE24"; //greenish? + negativeColor = "#EF5F5F"; //redish? + disabledColor = "#dddddd"; + disabledTextColor = "#aaaaaa"; } void MixerNode::addEdge(Edge *edge) @@ -70,7 +68,7 @@ QList MixerNode::edges() const QRectF MixerNode::boundingRect() const { - return cmdNode ? QRectF(-4, -4, 15, 10) : QRectF(-13, -13, 26, 26); + return QRectF(-13, -13, 26, 26); } QPainterPath MixerNode::shape() const @@ -82,48 +80,50 @@ QPainterPath MixerNode::shape() const void MixerNode::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *) { - QString text = cmdNode ? cmdText : QString().sprintf("%.2f", value()); + QString text = QString().sprintf("%.2f", value()); painter->setFont(graph->font()); if (drawNode) { QRadialGradient gradient(-3, -3, 10); + + QColor color; + if (value() < 0) { + color = negativeColor; + } + else if (value() == 0) { + color = neutralColor; + } + else { + color = positiveColor; + } + if (option->state & QStyle::State_Sunken) { gradient.setCenter(3, 3); gradient.setFocalPoint(3, 3); - gradient.setColorAt(1, Qt::darkBlue); - gradient.setColorAt(0, Qt::darkBlue); + QColor selColor = color.darker(); + gradient.setColorAt(1, selColor.darker()); + gradient.setColorAt(0, selColor); } else { - if (cmdNode) { - gradient.setColorAt(0, cmdActive ? posColor0 : negColor0); - gradient.setColorAt(1, cmdActive ? posColor1 : negColor1); - } - else { - if (value() < 0) { - gradient.setColorAt(0, negColor0); - gradient.setColorAt(1, negColor1); - } - else { - gradient.setColorAt(0, posColor0); - gradient.setColorAt(1, posColor1); - } - } + gradient.setColorAt(0, graph->isEnabled() ? color : disabledColor); + gradient.setColorAt(1, graph->isEnabled() ? color.darker() : disabledColor); } painter->setBrush(gradient); - painter->setPen(QPen(Qt::black, 0)); + painter->setPen(graph->isEnabled() ? QPen(Qt::black, 0) : QPen(disabledTextColor)); painter->drawEllipse(boundingRect()); - if (!image.isNull()) - painter->drawImage(boundingRect().adjusted(1,1,-1,-1), image); + if (!image.isNull()) { + painter->drawImage(boundingRect().adjusted(1, 1, -1, -1), image); + } } if (drawText) { - painter->setPen(QPen(drawNode ? Qt::white : Qt::black, 0)); - if (cmdNode) { - painter->drawText(0,4,text); - } - else { - painter->drawText( (value() < 0) ? -13 : -11, 4, text); + if(graph->isEnabled()) { + painter->setPen(QPen(drawNode ? Qt::white : Qt::black, 0)); + } else { + painter->setPen(QPen(disabledTextColor)); } + + painter->drawText( (value() < 0) ? -10 : -8, 3, text); } } @@ -131,13 +131,6 @@ void MixerNode::verticalMove(bool flag){ vertical = flag; } -void MixerNode::commandNode(bool enable){ - cmdNode = enable; -} -void MixerNode::commandText(QString text){ - cmdText = text; -} - double MixerNode::value() { double h = graph->sceneRect().height(); double ratio = (h - pos().y()) / h; @@ -186,10 +179,6 @@ QVariant MixerNode::itemChange(GraphicsItemChange change, const QVariant &val) void MixerNode::mousePressEvent(QGraphicsSceneMouseEvent *event) { - if (cmdNode) { - graph->cmdActivated(this); - //return; - } update(); QGraphicsItem::mousePressEvent(event); } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h index 3c4b0cc5d..6da0bcb95 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h @@ -39,8 +39,7 @@ QT_BEGIN_NAMESPACE class QGraphicsSceneMouseEvent; QT_END_NAMESPACE -class MixerNode : public QObject,public QGraphicsItem -{ +class MixerNode : public QObject, public QGraphicsItem { Q_OBJECT public: MixerNode(MixerCurveWidget *graphWidget); @@ -48,27 +47,37 @@ public: QList edges() const; enum { Type = UserType + 10 }; - int type() const { return Type; } - - void setName(QString name) { cmdName = name; } - const QString& getName() { return cmdName; } + int type() const + { + return Type; + } void verticalMove(bool flag); - void commandNode(bool enable); - void commandText(QString text); - int getCommandIndex() { return index; } - void setCommandIndex(int idx) { index = idx; } - bool getCommandActive() { return cmdActive; } - void setCommandActive(bool enable) { cmdActive = enable; } - void setToggle(bool enable) { cmdToggle = enable; } - bool getToggle() { return cmdToggle; } + void setPositiveColor(QColor color = "#609FF2") + { + positiveColor = color; + } - void setPositiveColor(QString color0 = "#00ff00", QString color1 = "#00ff00") { posColor0 = color0; posColor1 = color1; } - void setNegativeColor(QString color0 = "#ff0000", QString color1 = "#ff0000") { negColor0 = color0; negColor1 = color1; } - void setImage(QImage img) { image = img; } - void setDrawNode(bool draw) { drawNode = draw; } - void setDrawText(bool draw) { drawText = draw; } + void setNegativeColor(QColor color = "#EF5F5F") + { + negativeColor = color; + } + + void setImage(QImage img) + { + image = img; + } + + void setDrawNode(bool draw) + { + drawNode = draw; + } + + void setDrawText(bool draw) + { + drawText = draw; + } QRectF boundingRect() const; QPainterPath shape() const; @@ -76,35 +85,29 @@ public: double value(); -signals: - void commandActivated(QString text); - protected: QVariant itemChange(GraphicsItemChange change, const QVariant &val); void mousePressEvent(QGraphicsSceneMouseEvent *event); void mouseReleaseEvent(QGraphicsSceneMouseEvent *event); - + private: - QList edgeList; - QPointF newPos; - MixerCurveWidget* graph; - QString posColor0; - QString posColor1; - QString negColor0; - QString negColor1; - QImage image; + QList edgeList; + QPointF newPos; + MixerCurveWidget *graph; - bool vertical; - QString cmdName; - bool cmdActive; - bool cmdNode; - bool cmdToggle; - QString cmdText; - bool drawNode; - bool drawText; - int index; + QColor positiveColor; + QColor neutralColor; + QColor negativeColor; + QColor disabledColor; + QColor disabledTextColor; + QImage image; + + bool vertical; + bool drawNode; + bool drawText; + int index; }; -#endif // MIXERCURVEPOINT_H +#endif // MIXERCURVEPOINT_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index 4c52d1afb..03e2be777 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -66,286 +66,42 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) plot = new QGraphicsSvgItem(); renderer->load(QString(":/uavobjectwidgetutils/images/curve-bg.svg")); plot->setSharedRenderer(renderer); - //plot->setElementId("map"); + scene->addItem(plot); plot->setZValue(-1); scene->setSceneRect(plot->boundingRect()); setScene(scene); - posColor0 = "#1c870b"; //greenish? - posColor1 = "#116703"; //greenish? - negColor0 = "#ff0000"; //red - negColor1 = "#ff0000"; //red - - // commmand nodes - // reset - MixerNode* node = getCommandNode(0); - node->setName("Reset"); - node->setToolTip("Reset Curve to Defaults"); - node->setToggle(false); - node->setPositiveColor("#ffffff", "#ffffff"); //white - node->setNegativeColor("#ffffff", "#ffffff"); - scene->addItem(node); - - // linear - node = getCommandNode(1); - node->setName("Linear"); - node->setToolTip("Generate a Linear Curve"); - QImage img = QImage(":/core/images/curve_linear.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("/"); - - scene->addItem(node); - - // log - node = getCommandNode(2); - node->setName("Log"); - node->setToolTip("Generate a Logarithmic Curve"); - img = QImage(":/core/images/curve_log.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("("); - scene->addItem(node); - - // exp - node = getCommandNode(3); - node->setName("Exp"); - node->setToolTip("Generate an Exponential Curve"); - img = QImage(":/core/images/curve_exp.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText(")"); - scene->addItem(node); - - // flat - node = getCommandNode(4); - node->setName("Flat"); - node->setToolTip("Generate a Flat Curve"); - img = QImage(":/core/images/curve_flat.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("--"); - scene->addItem(node); - - // step - node = getCommandNode(5); - node->setName("Step"); - node->setToolTip("Generate a Stepped Curve"); - img = QImage(":/core/images/curve_step.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("z"); - scene->addItem(node); - - - // curve min/max nodes - node = getCommandNode(6); - node->setName("MinPlus"); - node->setToolTip("Increase Curve Minimum"); - img = QImage(":/core/images/curve_plus.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("+"); - node->setToggle(false); - node->setPositiveColor("#00aa00", "#00aa00"); //green - node->setNegativeColor("#00aa00", "#00aa00"); - scene->addItem(node); - - node = getCommandNode(7); - node->setName("MinMinus"); - node->setToolTip("Decrease Curve Minimum"); - img = QImage(":/core/images/curve_minus.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("-"); - - node->setToggle(false); - node->setPositiveColor("#aa0000", "#aa0000"); //red - node->setNegativeColor("#aa0000", "#aa0000"); - scene->addItem(node); - - node = getCommandNode(8); - node->setName("MaxPlus"); - node->setToolTip("Increase Curve Maximum"); - img = QImage(":/core/images/curve_plus.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("+"); - - node->setToggle(false); - node->setPositiveColor("#00aa00", "#00aa00"); //green - node->setNegativeColor("#00aa00", "#00aa00"); - scene->addItem(node); - - node = getCommandNode(9); - node->setName("MaxMinus"); - node->setToolTip("Decrease Curve Maximum"); - img = QImage(":/core/images/curve_plus.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("-"); - - node->setToggle(false); - node->setPositiveColor("#aa0000", "#aa0000"); //red - node->setNegativeColor("#aa0000", "#aa0000"); - scene->addItem(node); - - node = getCommandNode(10); - node->setName("StepPlus"); - node->setToolTip("Increase Step/Power Value"); - img = QImage(":/core/images/curve_plus.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("+"); - node->setToggle(false); - node->setPositiveColor("#00aa00", "#00aa00"); //green - node->setNegativeColor("#00aa00", "#00aa00"); - scene->addItem(node); - - node = getCommandNode(11); - node->setName("StepMinus"); - node->setToolTip("Decrease Step/Power Value"); - img = QImage(":/core/images/curve_minus.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("-"); - - node->setToggle(false); - node->setPositiveColor("#aa0000", "#aa0000"); //red - node->setNegativeColor("#aa0000", "#aa0000"); - scene->addItem(node); - - node = getCommandNode(12); - node->setName("StepValue"); - node->setDrawNode(false); - node->setToolTip("Current Step/Power Value"); - node->setToggle(false); - node->setPositiveColor("#0000aa", "#0000aa"); //blue - node->setNegativeColor("#0000aa", "#0000aa"); - scene->addItem(node); - - // commands toggle - node = getCommandNode(13); - node->setName("Commands"); - node->setToolTip("Toggle Command Buttons On/Off"); - node->setToggle(true); - node->setPositiveColor("#00aa00", "#00aa00"); //greenish - node->setNegativeColor("#000000", "#000000"); - scene->addItem(node); - - // popup - node = getCommandNode(14); - node->setName("Popup"); - node->setToolTip("Advanced Mode..."); - node->commandText(""); - node->setToggle(false); - node->setPositiveColor("#ff0000", "#ff0000"); //red - node->setNegativeColor("#ff0000", "#ff0000"); - scene->addItem(node); - - resizeCommands(); - initNodes(MixerCurveWidget::NODE_NUMELEM); - } MixerCurveWidget::~MixerCurveWidget() { - while (!nodePool.isEmpty()) - delete nodePool.takeFirst(); + while (!nodeList.isEmpty()) { + delete nodeList.takeFirst(); + } - while (!edgePool.isEmpty()) - delete edgePool.takeFirst(); - - while (!cmdNodePool.isEmpty()) - delete cmdNodePool.takeFirst(); + while (!edgeList.isEmpty()) { + delete edgeList.takeFirst(); + } } -MixerNode* MixerCurveWidget::getCommandNode(int index) +void MixerCurveWidget::setPositiveColor(QString color) { - MixerNode* node; - - if (index >= 0 && index < cmdNodePool.count()) - { - node = cmdNodePool.at(index); + for (int i=0; i < nodeList.count(); i++) { + MixerNode* node = nodeList.at(i); + node->setPositiveColor(color); } - else { - node = new MixerNode(this); - node->commandNode(true); - node->commandText(""); - node->setCommandIndex(index); - node->setActive(false); - node->setPositiveColor("#aaaa00", "#aaaa00"); - node->setNegativeColor("#1c870b", "#116703"); - cmdNodePool.append(node); - } - return node; - } -MixerNode* MixerCurveWidget::getNode(int index) +void MixerCurveWidget::setNegativeColor(QString color) { - MixerNode* node; - - if (index >= 0 && index < nodePool.count()) - { - node = nodePool.at(index); - } - else { - node = new MixerNode(this); - nodePool.append(node); - } - return node; -} -Edge* MixerCurveWidget::getEdge(int index, MixerNode* sourceNode, MixerNode* destNode) -{ - Edge* edge; - - if (index >= 0 && index < edgePool.count()) - { - edge = edgePool.at(index); - edge->setSourceNode(sourceNode); - edge->setDestNode(destNode); - } - else { - edge = new Edge(sourceNode,destNode); - edgePool.append(edge); - } - return edge; -} - -void MixerCurveWidget::setPositiveColor(QString color0, QString color1) -{ - posColor0 = color0; - posColor1 = color1; - for (int i=0; isetPositiveColor(color0, color1); + for (int i=0; i < nodeList.count(); i++) { + MixerNode* node = nodeList.at(i); + node->setNegativeColor(color); } } -void MixerCurveWidget::setNegativeColor(QString color0, QString color1) -{ - negColor0 = color0; - negColor1 = color1; - for (int i=0; isetNegativeColor(color0, color1); - } -} - /** Init curve: create a (flat) curve with a specified number of points. @@ -370,9 +126,11 @@ void MixerCurveWidget::initNodes(int numPoints) foreach(Edge *edge, node->edges()) { if (edge->sourceNode() == node) { scene()->removeItem(edge); + delete edge; } } scene()->removeItem(node); + delete node; } nodeList.clear(); @@ -380,9 +138,9 @@ void MixerCurveWidget::initNodes(int numPoints) // Create the nodes and edges MixerNode* prevNode = 0; - for (int i=0; iaddItem(node); @@ -390,7 +148,7 @@ void MixerCurveWidget::initNodes(int numPoints) node->setPos(0,0); if (prevNode) { - scene()->addItem(getEdge(i, prevNode, node)); + scene()->addItem(new Edge(prevNode, node)); } prevNode = node; @@ -469,7 +227,6 @@ void MixerCurveWidget::showEvent(QShowEvent *event) // the result is usually a ahrsbargraph that is way too small. QRectF rect = plot->boundingRect(); - resizeCommands(); fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio); } @@ -478,61 +235,17 @@ void MixerCurveWidget::resizeEvent(QResizeEvent* event) Q_UNUSED(event); QRectF rect = plot->boundingRect(); - resizeCommands(); fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio); } -void MixerCurveWidget::resizeCommands() +void MixerCurveWidget::changeEvent(QEvent *event) { - QRectF rect = plot->boundingRect(); - - MixerNode* node; - //popup - node = getCommandNode(14); - node->setPos((rect.left() + rect.width() / 2) - 20, rect.height() + 10); - - //reset - node = getCommandNode(0); - node->setPos((rect.left() + rect.width() / 2) + 20, rect.height() + 10); - - //commands on/off - node = getCommandNode(13); - node->setPos(rect.right() - 15, rect.bottomRight().x() - 14); - - for (int i = 1; i<6; i++) { - node = getCommandNode(i); - - //bottom right of widget - node->setPos(rect.right() - 130 + (i * 18), rect.bottomRight().x() - 14); + QGraphicsView::changeEvent(event); + if(event->type() == QEvent::EnabledChange) { + foreach (MixerNode *node, nodeList) { + node->update(); + } } - - //curveminplus - node = getCommandNode(6); - node->setPos(rect.bottomLeft().x() + 15, rect.bottomLeft().y() - 10); - - //curveminminus - node = getCommandNode(7); - node->setPos(rect.bottomLeft().x() + 15, rect.bottomLeft().y() + 5); - - //curvemaxplus - node = getCommandNode(8); - node->setPos(rect.topRight().x() - 20, rect.topRight().y() - 7); - - //curvemaxminus - node = getCommandNode(9); - node->setPos(rect.topRight().x() - 20, rect.topRight().y() + 8); - - //stepplus - node = getCommandNode(10); - node->setPos(rect.bottomRight().x() - 40, rect.bottomRight().y() + 5); - - //stepminus - node = getCommandNode(11); - node->setPos(rect.bottomRight().x() - 40, rect.bottomRight().y() + 15); - - //step - node = getCommandNode(12); - node->setPos(rect.bottomRight().x() - 22, rect.bottomRight().y() + 9); } void MixerCurveWidget::itemMoved(double itemValue) @@ -575,87 +288,3 @@ double MixerCurveWidget::setRange(double min, double max) return curveMax - curveMin; } -MixerNode* MixerCurveWidget::getCmdNode(const QString& name) -{ - MixerNode* node = 0; - for (int i=0; igetName() == name) - node = n; - } - return node; -} - -void MixerCurveWidget::setCommandText(const QString& name, const QString& text) -{ - for (int i=0; igetName() == name) { - n->commandText(text); - n->update(); - } - } -} -void MixerCurveWidget::activateCommand(const QString& name) -{ - for (int i=1; isetCommandActive(node->getName() == name); - node->update(); - } -} - -void MixerCurveWidget::showCommand(const QString& name, bool show) -{ - MixerNode* node = getCmdNode(name); - if (node) { - if (show) - node->show(); - else - node->hide(); - } -} -void MixerCurveWidget::showCommands(bool show) -{ - for (int i=1; ishow(); - else - node->hide(); - - node->update(); - } -} -bool MixerCurveWidget::isCommandActive(const QString& name) -{ - bool active = false; - MixerNode* node = getCmdNode(name); - if (node) { - active = node->getCommandActive(); - } - return active; -} - -void MixerCurveWidget::cmdActivated(MixerNode* node) -{ - if (node->getToggle()) { - if (node->getName() == "Commands") { - node->setCommandActive(!node->getCommandActive()); - showCommands(node->getCommandActive()); - } - else { - for (int i=1; isetCommandActive(false); - n->update(); - } - - node->setCommandActive(true); - } - - } - node->update(); - emit commandActivated(node); -} - diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h index d9469ba58..8cc64d8b5 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h @@ -37,76 +37,54 @@ #include "mixercurveline.h" #include "uavobjectwidgetutils_global.h" -class UAVOBJECTWIDGETUTILS_EXPORT MixerCurveWidget : public QGraphicsView -{ +class UAVOBJECTWIDGETUTILS_EXPORT MixerCurveWidget : public QGraphicsView { Q_OBJECT public: MixerCurveWidget(QWidget *parent = 0); - ~MixerCurveWidget(); + ~MixerCurveWidget(); friend class MixerCurve; - void itemMoved(double itemValue); // Callback when a point is moved, to be updated - void initCurve (const QList* points); - QList getCurve(); - void initLinearCurve(int numPoints, double maxValue = 1, double minValue = 0); - void setCurve(const QList* points); - void setMin(double value); - double getMin(); - void setMax(double value); - double getMax(); - double setRange(double min, double max); + void itemMoved(double itemValue); // Callback when a point is moved, to be updated + void initCurve(const QList *points); + QList getCurve(); + void initLinearCurve(int numPoints, double maxValue = 1, double minValue = 0); + void setCurve(const QList *points); + void setMin(double value); + double getMin(); + void setMax(double value); + double getMax(); + double setRange(double min, double max); - - void cmdActivated(MixerNode* node); - void activateCommand(const QString& name); - bool isCommandActive(const QString& name); - void showCommand(const QString& name, bool show); - void showCommands(bool show); - MixerNode* getCmdNode(const QString& name); - void setCommandText(const QString& name, const QString& text); - - static const int NODE_NUMELEM = 5; + static const int NODE_NUMELEM = 5; signals: - void curveUpdated(); - void curveMinChanged(double value); - void curveMaxChanged(double value); - void commandActivated(MixerNode* node); + void curveUpdated(); + void curveMinChanged(double value); + void curveMaxChanged(double value); private slots: private: - QGraphicsSvgItem *plot; + QGraphicsSvgItem *plot; - QList nodePool; - QList cmdNodePool; - QList edgePool; - QList nodeList; + QList edgeList; + QList nodeList; - double curveMin; - double curveMax; - bool curveUpdating; + double curveMin; + double curveMax; + bool curveUpdating; - QString posColor0; - QString posColor1; - QString negColor0; - QString negColor1; + void initNodes(int numPoints); + void setPositiveColor(QString color); + void setNegativeColor(QString color); - void initNodes(int numPoints); - MixerNode* getNode(int index); - MixerNode* getCommandNode(int index); - Edge* getEdge(int index, MixerNode* sourceNode, MixerNode* destNode); - void setPositiveColor(QString color0 = "#00ff00", QString color1 = "#00ff00"); - void setNegativeColor(QString color0 = "#ff0000", QString color1 = "#ff0000"); - - void resizeCommands(); + void resizeCommands(); protected: void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); - - + void changeEvent(QEvent *event); }; #endif /* MIXERCURVEWIDGET_H_ */ diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h index 55f19956d..6f828eb67 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h @@ -12,19 +12,24 @@ namespace Ui { class PopupWidget; } -class UAVOBJECTWIDGETUTILS_EXPORT PopupWidget : public QDialog -{ +class UAVOBJECTWIDGETUTILS_EXPORT PopupWidget : public QDialog { Q_OBJECT public: explicit PopupWidget(QWidget *parent = 0); - - void popUp(QWidget* widget = 0); - void setWidget(QWidget* widget); - QWidget* getWidget() { return m_widget; } - QHBoxLayout* getLayout() { return m_layout; } -signals: - + void popUp(QWidget *widget = 0); + void setWidget(QWidget *widget); + + QWidget *getWidget() + { + return m_widget; + } + + QHBoxLayout *getLayout() + { + return m_layout; + } + public slots: bool close(); void done(int result); @@ -33,12 +38,12 @@ private slots: void closePopup(); private: - QHBoxLayout* m_layout; - QWidget* m_widget; - QWidget* m_widgetParent; - QPushButton* m_closeButton; - int m_widgetWidth; - int m_widgetHeight; + QHBoxLayout *m_layout; + QWidget *m_widget; + QWidget *m_widgetParent; + QPushButton *m_closeButton; + int m_widgetWidth; + int m_widgetHeight; }; #endif // POPUPWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.h index 03b96ff39..275ea3c44 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.h @@ -37,14 +37,15 @@ #include "uavobjectutilmanager.h" #include #include -class smartSaveButton:public QObject -{ - enum buttonTypeEnum {save_button,apply_button}; + +class smartSaveButton : public QObject { + enum buttonTypeEnum { save_button, apply_button }; public: Q_OBJECT + public: smartSaveButton(); - void addButtons(QPushButton * save,QPushButton * apply); + void addButtons(QPushButton *save, QPushButton *apply); void setObjects(QList); void addObject(UAVDataObject *); void clearObjects(); @@ -53,32 +54,34 @@ public: void addApplyButton(QPushButton *apply); void addSaveButton(QPushButton *save); void resetIcons(); + signals: void preProcessOperations(); void saveSuccessfull(); void beginOp(); void endOp(); + public slots: void apply(); void save(); + private slots: void processClick(); void processOperation(QPushButton *button, bool save); - void transaction_finished(UAVObject* obj, bool result); - void saving_finished(int,bool); + void transaction_finished(UAVObject *obj, bool result); + void saving_finished(int, bool); private: quint32 current_objectID; - UAVDataObject * current_object; + UAVDataObject *current_object; bool up_result; bool sv_result; QEventLoop loop; QList objects; - QMap buttonList; -protected: + QMap buttonList; + public slots: void enableControls(bool value); - }; diff --git a/make/common-defs.mk b/make/common-defs.mk index 76cb43746..a06625f2d 100644 --- a/make/common-defs.mk +++ b/make/common-defs.mk @@ -120,6 +120,7 @@ CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer CFLAGS += -Wall -Wextra CFLAGS += -Wfloat-equal -Wunsuffixed-float-constants -Wdouble-promotion +CFLAGS += -Wshadow CFLAGS += -Werror CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) diff --git a/shared/uavobjectdefinition/altitudeholdsettings.xml b/shared/uavobjectdefinition/altitudeholdsettings.xml index 9b805458b..25c75aca3 100644 --- a/shared/uavobjectdefinition/altitudeholdsettings.xml +++ b/shared/uavobjectdefinition/altitudeholdsettings.xml @@ -8,6 +8,8 @@ + +