1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-27 16:54:15 +01:00

Merge remote-tracking branch 'origin/next' into amorale/usb_fixes

This commit is contained in:
Alessio Morale 2013-05-17 22:46:42 +02:00
commit 67e41c34fc
98 changed files with 10914 additions and 9677 deletions

View File

@ -654,6 +654,7 @@ ut_$(1)_%: $$(UT_OUT_DIR)
$(V1) cd $(ROOT_DIR)/flight/tests/$(1) && \ $(V1) cd $(ROOT_DIR)/flight/tests/$(1) && \
$$(MAKE) -r --no-print-directory \ $$(MAKE) -r --no-print-directory \
BUILD_TYPE=ut \ BUILD_TYPE=ut \
BOARD_SHORT_NAME=$(1) \
TOPDIR=$(ROOT_DIR)/flight/tests/$(1) \ TOPDIR=$(ROOT_DIR)/flight/tests/$(1) \
OUTDIR="$(UT_OUT_DIR)/$(1)" \ OUTDIR="$(UT_OUT_DIR)/$(1)" \
TARGET=$(1) \ TARGET=$(1) \

View File

@ -32,6 +32,7 @@
#include "insgps.h" #include "insgps.h"
#include <math.h> #include <math.h>
#include <stdint.h> #include <stdint.h>
#include <pios_math.h>
// constants/macros/typdefs // constants/macros/typdefs
#define NUMX 13 // number of states, X is the state vector #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 NUMV 10 // number of measurements, v is the measurement noise vector
#define NUMU 6 // number of deterministic inputs, U is the input 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 // Private functions
void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW],
float Q[NUMW], float dT, float P[NUMX][NUMX]); float Q[NUMW], float dT, float P[NUMX][NUMX]);
void SerialUpdate(float H[NUMV][NUMX], float R[NUMV], float Z[NUMV], 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); uint16_t SensorsUsed);
void RungeKutta(float X[NUMX], float U[NUMU], float dT); void RungeKutta(float X[NUMX], float U[NUMU], float dT);
void StateEq(float X[NUMX], float U[NUMU], float Xdot[NUMX]); 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]); void LinearizeH(float X[NUMX], float Be[3], float H[NUMV][NUMX]);
// Private variables // Private variables
float F[NUMX][NUMX], G[NUMX][NUMW], H[NUMV][NUMX]; // linearized system matrices
// global to init to zero and maintain zero elements // speed optimizations, describe matrix sparsity
float Be[3]; // local magnetic unit vector in NED frame // derived from state equations in
float P[NUMX][NUMX], X[NUMX]; // covariance matrix and state vector // LinearizeFG() and LinearizeH():
float Q[NUMW], R[NUMV]; // input noise and measurement noise variances //
// 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 float K[NUMX][NUMV]; // feedback gain matrix
} ekf;
// Global variables // Global variables
struct NavStruct Nav; struct NavStruct Nav;
@ -79,52 +113,52 @@ uint16_t ins_get_num_states()
void INSGPSInit() //pretty much just a place holder for now void INSGPSInit() //pretty much just a place holder for now
{ {
Be[0] = 1.0f; ekf.Be[0] = 1.0f;
Be[1] = 0.0f; ekf.Be[1] = 0.0f;
Be[2] = 0.0f; // local magnetic unit vector ekf.Be[2] = 0.0f; // local magnetic unit vector
for (int i = 0; i < NUMX; i++) { for (int i = 0; i < NUMX; i++) {
for (int j = 0; j < NUMX; j++) { for (int j = 0; j < NUMX; j++) {
P[i][j] = 0.0f; // zero all terms ekf.P[i][j] = 0.0f; // zero all terms
F[i][j] = 0.0f; ekf.F[i][j] = 0.0f;
} }
for (int j = 0; j < NUMW; j++) 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++) { for (int j = 0; j < NUMV; j++) {
H[j][i] = 0.0f; ekf.H[j][i] = 0.0f;
K[i][j] = 0.0f; ekf.K[i][j] = 0.0f;
} }
X[i] = 0.0f; ekf.X[i] = 0.0f;
} }
for (int i = 0; i < NUMW; i++) for (int i = 0; i < NUMW; i++)
Q[i] = 0.0f; ekf.Q[i] = 0.0f;
for (int i = 0; i < NUMV; i++) 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) ekf.P[0][0] = ekf.P[1][1] = ekf.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 ekf.P[3][3] = ekf.P[4][4] = ekf.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 ekf.P[6][6] = ekf.P[7][7] = ekf.P[8][8] = ekf.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[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) 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)
X[6] = 1.0f; ekf.X[6] = 1.0f;
X[7] = X[8] = X[9] = 0.0f; // initial quaternion (level and North) (m/s) ekf.X[7] = ekf.X[8] = ekf.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[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 ekf.Q[0] = ekf.Q[1] = ekf.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 ekf.Q[3] = ekf.Q[4] = ekf.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[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) ekf.R[0] = ekf.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) ekf.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 ekf.R[3] = ekf.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 ekf.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 ekf.R[6] = ekf.R[7] = ekf.R[8] = 0.005f; // magnetometer unit vector noise variance
R[9] = .25f; // High freq altimeter noise variance (m^2) ekf.R[9] = .25f; // High freq altimeter noise variance (m^2)
} }
void INSResetP(float PDiag[NUMX]) void INSResetP(float PDiag[NUMX])
@ -135,8 +169,8 @@ void INSResetP(float PDiag[NUMX])
for (i=0;i<NUMX;i++){ for (i=0;i<NUMX;i++){
if (PDiag != 0){ if (PDiag != 0){
for (j=0;j<NUMX;j++) for (j=0;j<NUMX;j++)
P[i][j]=P[j][i]=0.0f; ekf.P[i][j]=ekf.P[j][i]=0.0f;
P[i][i]=PDiag[i]; ekf.P[i][i]=PDiag[i];
} }
} }
} }
@ -148,7 +182,7 @@ void INSGetP(float PDiag[NUMX])
// retrieve diagonal elements (aka state variance) // retrieve diagonal elements (aka state variance)
for (i=0;i<NUMX;i++){ for (i=0;i<NUMX;i++){
if (PDiag != 0){ if (PDiag != 0){
PDiag[i] = P[i][i]; PDiag[i] = ekf.P[i][i];
} }
} }
} }
@ -156,97 +190,97 @@ void INSGetP(float PDiag[NUMX])
void INSSetState(float pos[3], float vel[3], float q[4], float gyro_bias[3], __attribute__((unused)) float accel_bias[3]) void INSSetState(float pos[3], float vel[3], float q[4], float gyro_bias[3], __attribute__((unused)) float accel_bias[3])
{ {
/* Note: accel_bias not used in 13 state INS */ /* Note: accel_bias not used in 13 state INS */
X[0] = pos[0]; ekf.X[0] = pos[0];
X[1] = pos[1]; ekf.X[1] = pos[1];
X[2] = pos[2]; ekf.X[2] = pos[2];
X[3] = vel[0]; ekf.X[3] = vel[0];
X[4] = vel[1]; ekf.X[4] = vel[1];
X[5] = vel[2]; ekf.X[5] = vel[2];
X[6] = q[0]; ekf.X[6] = q[0];
X[7] = q[1]; ekf.X[7] = q[1];
X[8] = q[2]; ekf.X[8] = q[2];
X[9] = q[3]; ekf.X[9] = q[3];
X[10] = gyro_bias[0]; ekf.X[10] = gyro_bias[0];
X[11] = gyro_bias[1]; ekf.X[11] = gyro_bias[1];
X[12] = gyro_bias[2]; ekf.X[12] = gyro_bias[2];
} }
void INSPosVelReset(float pos[3], float vel[3]) void INSPosVelReset(float pos[3], float vel[3])
{ {
for (int i = 0; i < 6; i++) { for (int i = 0; i < 6; i++) {
for(int j = i; j < NUMX; j++) { for(int j = i; j < NUMX; j++) {
P[i][j] = 0; // zero the first 6 rows and columns ekf.P[i][j] = 0; // zero the first 6 rows and columns
P[j][i] = 0; ekf.P[j][i] = 0;
} }
} }
P[0][0] = P[1][1] = P[2][2] = 25; // initial position variance (m^2) ekf.P[0][0] = ekf.P[1][1] = ekf.P[2][2] = 25; // initial position variance (m^2)
P[3][3] = P[4][4] = P[5][5] = 5; // initial velocity variance (m/s)^2 ekf.P[3][3] = ekf.P[4][4] = ekf.P[5][5] = 5; // initial velocity variance (m/s)^2
X[0] = pos[0]; ekf.X[0] = pos[0];
X[1] = pos[1]; ekf.X[1] = pos[1];
X[2] = pos[2]; ekf.X[2] = pos[2];
X[3] = vel[0]; ekf.X[3] = vel[0];
X[4] = vel[1]; ekf.X[4] = vel[1];
X[5] = vel[2]; ekf.X[5] = vel[2];
} }
void INSSetPosVelVar(float PosVar[3], float VelVar[3]) void INSSetPosVelVar(float PosVar[3], float VelVar[3])
{ {
R[0] = PosVar[0]; ekf.R[0] = PosVar[0];
R[1] = PosVar[1]; ekf.R[1] = PosVar[1];
R[2] = PosVar[2]; ekf.R[2] = PosVar[2];
R[3] = VelVar[0]; ekf.R[3] = VelVar[0];
R[4] = VelVar[1]; ekf.R[4] = VelVar[1];
R[5] = VelVar[2]; ekf.R[5] = VelVar[2];
} }
void INSSetGyroBias(float gyro_bias[3]) void INSSetGyroBias(float gyro_bias[3])
{ {
X[10] = gyro_bias[0]; ekf.X[10] = gyro_bias[0];
X[11] = gyro_bias[1]; ekf.X[11] = gyro_bias[1];
X[12] = gyro_bias[2]; ekf.X[12] = gyro_bias[2];
} }
void INSSetAccelVar(float accel_var[3]) void INSSetAccelVar(float accel_var[3])
{ {
Q[3] = accel_var[0]; ekf.Q[3] = accel_var[0];
Q[4] = accel_var[1]; ekf.Q[4] = accel_var[1];
Q[5] = accel_var[2]; ekf.Q[5] = accel_var[2];
} }
void INSSetGyroVar(float gyro_var[3]) void INSSetGyroVar(float gyro_var[3])
{ {
Q[0] = gyro_var[0]; ekf.Q[0] = gyro_var[0];
Q[1] = gyro_var[1]; ekf.Q[1] = gyro_var[1];
Q[2] = gyro_var[2]; ekf.Q[2] = gyro_var[2];
} }
void INSSetGyroBiasVar(float gyro_bias_var[3]) void INSSetGyroBiasVar(float gyro_bias_var[3])
{ {
Q[6] = gyro_bias_var[0]; ekf.Q[6] = gyro_bias_var[0];
Q[7] = gyro_bias_var[1]; ekf.Q[7] = gyro_bias_var[1];
Q[8] = gyro_bias_var[2]; ekf.Q[8] = gyro_bias_var[2];
} }
void INSSetMagVar(float scaled_mag_var[3]) void INSSetMagVar(float scaled_mag_var[3])
{ {
R[6] = scaled_mag_var[0]; ekf.R[6] = scaled_mag_var[0];
R[7] = scaled_mag_var[1]; ekf.R[7] = scaled_mag_var[1];
R[8] = scaled_mag_var[2]; ekf.R[8] = scaled_mag_var[2];
} }
void INSSetBaroVar(float baro_var) void INSSetBaroVar(float baro_var)
{ {
R[9] = baro_var; ekf.R[9] = baro_var;
} }
void INSSetMagNorth(float B[3]) void INSSetMagNorth(float B[3])
{ {
float mag = sqrtf(B[0] * B[0] + B[1] * B[1] + B[2] * B[2]); float mag = sqrtf(B[0] * B[0] + B[1] * B[1] + B[2] * B[2]);
Be[0] = B[0] / mag; ekf.Be[0] = B[0] / mag;
Be[1] = B[1] / mag; ekf.Be[1] = B[1] / mag;
Be[2] = B[2] / mag; ekf.Be[2] = B[2] / mag;
} }
void INSStatePrediction(float gyro_data[3], float accel_data[3], float dT) void INSStatePrediction(float gyro_data[3], float accel_data[3], float dT)
@ -265,34 +299,34 @@ void INSStatePrediction(float gyro_data[3], float accel_data[3], float dT)
U[5] = accel_data[2]; U[5] = accel_data[2];
// EKF prediction step // EKF prediction step
LinearizeFG(X, U, F, G); LinearizeFG(ekf.X, U, ekf.F, ekf.G);
RungeKutta(X, U, dT); RungeKutta(ekf.X, U, dT);
qmag = sqrtf(X[6] * X[6] + X[7] * X[7] + X[8] * X[8] + X[9] * X[9]); qmag = sqrtf(ekf.X[6] * ekf.X[6] + ekf.X[7] * ekf.X[7] + ekf.X[8] * ekf.X[8] + ekf.X[9] * ekf.X[9]);
X[6] /= qmag; ekf.X[6] /= qmag;
X[7] /= qmag; ekf.X[7] /= qmag;
X[8] /= qmag; ekf.X[8] /= qmag;
X[9] /= qmag; ekf.X[9] /= qmag;
//CovariancePrediction(F,G,Q,dT,P); //CovariancePrediction(ekf.F,ekf.G,ekf.Q,dT,ekf.P);
// Update Nav solution structure // Update Nav solution structure
Nav.Pos[0] = X[0]; Nav.Pos[0] = ekf.X[0];
Nav.Pos[1] = X[1]; Nav.Pos[1] = ekf.X[1];
Nav.Pos[2] = X[2]; Nav.Pos[2] = ekf.X[2];
Nav.Vel[0] = X[3]; Nav.Vel[0] = ekf.X[3];
Nav.Vel[1] = X[4]; Nav.Vel[1] = ekf.X[4];
Nav.Vel[2] = X[5]; Nav.Vel[2] = ekf.X[5];
Nav.q[0] = X[6]; Nav.q[0] = ekf.X[6];
Nav.q[1] = X[7]; Nav.q[1] = ekf.X[7];
Nav.q[2] = X[8]; Nav.q[2] = ekf.X[8];
Nav.q[3] = X[9]; Nav.q[3] = ekf.X[9];
Nav.gyro_bias[0] = X[10]; Nav.gyro_bias[0] = ekf.X[10];
Nav.gyro_bias[1] = X[11]; Nav.gyro_bias[1] = ekf.X[11];
Nav.gyro_bias[2] = X[12]; Nav.gyro_bias[2] = ekf.X[12];
} }
void INSCovariancePrediction(float dT) void INSCovariancePrediction(float dT)
{ {
CovariancePrediction(F, G, Q, dT, P); CovariancePrediction(ekf.F, ekf.G, ekf.Q, dT, ekf.P);
} }
float zeros[3] = { 0, 0, 0 }; float zeros[3] = { 0, 0, 0 };
@ -361,29 +395,29 @@ void INSCorrection(float mag_data[3], float Pos[3], float Vel[3],
Z[9] = BaroAlt; Z[9] = BaroAlt;
// EKF correction step // EKF correction step
LinearizeH(X, Be, H); LinearizeH(ekf.X, ekf.Be, ekf.H);
MeasurementEq(X, Be, Y); MeasurementEq(ekf.X, ekf.Be, Y);
SerialUpdate(H, R, Z, Y, P, X, SensorsUsed); SerialUpdate(ekf.H, ekf.R, Z, Y, ekf.P, ekf.X, ekf.K, SensorsUsed);
qmag = sqrtf(X[6] * X[6] + X[7] * X[7] + X[8] * X[8] + X[9] * X[9]); qmag = sqrtf(ekf.X[6] * ekf.X[6] + ekf.X[7] * ekf.X[7] + ekf.X[8] * ekf.X[8] + ekf.X[9] * ekf.X[9]);
X[6] /= qmag; ekf.X[6] /= qmag;
X[7] /= qmag; ekf.X[7] /= qmag;
X[8] /= qmag; ekf.X[8] /= qmag;
X[9] /= qmag; ekf.X[9] /= qmag;
// Update Nav solution structure // Update Nav solution structure
Nav.Pos[0] = X[0]; Nav.Pos[0] = ekf.X[0];
Nav.Pos[1] = X[1]; Nav.Pos[1] = ekf.X[1];
Nav.Pos[2] = X[2]; Nav.Pos[2] = ekf.X[2];
Nav.Vel[0] = X[3]; Nav.Vel[0] = ekf.X[3];
Nav.Vel[1] = X[4]; Nav.Vel[1] = ekf.X[4];
Nav.Vel[2] = X[5]; Nav.Vel[2] = ekf.X[5];
Nav.q[0] = X[6]; Nav.q[0] = ekf.X[6];
Nav.q[1] = X[7]; Nav.q[1] = ekf.X[7];
Nav.q[2] = X[8]; Nav.q[2] = ekf.X[8];
Nav.q[3] = X[9]; Nav.q[3] = ekf.X[9];
Nav.gyro_bias[0] = X[10]; Nav.gyro_bias[0] = ekf.X[10];
Nav.gyro_bias[1] = X[11]; Nav.gyro_bias[1] = ekf.X[11];
Nav.gyro_bias[2] = X[12]; Nav.gyro_bias[2] = ekf.X[12];
} }
// ************* CovariancePrediction ************* // ************* CovariancePrediction *************
@ -397,972 +431,71 @@ void INSCorrection(float mag_data[3], float Pos[3], float Vel[3],
// The first Method is very specific to this implementation // The first Method is very specific to this implementation
// ************************************************ // ************************************************
#ifdef COVARIANCE_PREDICTION_GENERAL __attribute__((optimize("O3")))
void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW],
float Q[NUMW], float dT, float P[NUMX][NUMX]) float Q[NUMW], float dT, float P[NUMX][NUMX])
{ {
float Dummy[NUMX][NUMX], dTsq;
uint8_t i, j, k;
// Pnew = (I+F*T)*P*(I+F*T)' + T^2*G*Q*G' = T^2[(P/T + F*P)*(I/T + F') + G*Q*G')] // Pnew = (I+F*T)*P*(I+F*T)' + (T^2)*G*Q*G' = (T^2)[(P/T + F*P)*(I/T + F') + G*Q*G')]
dTsq = dT * dT; float dT1 = 1.0f / dT; // multiplication is faster than division on fpu.
float dTsq = dT * dT;
for (i = 0; i < NUMX; i++) // Calculate Dummy = (P/T +F*P) float Dummy[NUMX][NUMX];
int8_t i;
for (i = 0; i < NUMX; i++) { // Calculate Dummy = (P/T +F*P)
float *Firow = F[i];
float *Pirow = P[i];
float *Dirow = Dummy[i];
int8_t Fistart = FrowMin[i];
int8_t Fiend = FrowMax[i];
int8_t j;
for (j = 0; j < NUMX; j++) { for (j = 0; j < NUMX; j++) {
Dummy[i][j] = P[i][j] / dT;
for (k = 0; k < NUMX; k++) Dirow[j] = Pirow[j] * dT1; // Dummy = P / T ...
Dummy[i][j] += F[i][k] * P[k][j]; int8_t k;
for (k = Fistart; k <= Fiend; k++) {
Dirow[j] += Firow[k] * P[k][j]; // [] + F * P
} }
for (i = 0; i < NUMX; i++) // Calculate Pnew = Dummy/T + Dummy*F' + G*Qw*G' }
}
for (i = 0; i < NUMX; i++) { // Calculate Pnew = (T^2) [Dummy/T + Dummy*F' + G*Qw*G']
float *Dirow = Dummy[i];
float *Girow = G[i];
float *Pirow = P[i];
int8_t Gistart = GrowMin[i];
int8_t Giend = GrowMax[i];
int8_t j;
for (j = i; j < NUMX; j++) { // Use symmetry, ie only find upper triangular for (j = i; j < NUMX; j++) { // Use symmetry, ie only find upper triangular
P[i][j] = Dummy[i][j] / dT;
for (k = 0; k < NUMX; k++)
P[i][j] += Dummy[i][k] * F[j][k]; // P = Dummy/T + Dummy*F'
for (k = 0; k < NUMW; k++)
P[i][j] += Q[k] * G[i][k] * G[j][k]; // P = Dummy/T + Dummy*F' + G*Q*G'
P[j][i] = P[i][j] = P[i][j] * dTsq; // Pnew = T^2*P and fill in lower triangular;
}
}
#else float Ptmp = Dirow[j] * dT1; // Pnew = Dummy / T ...
void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW],
float Q[NUMW], float dT, float P[NUMX][NUMX])
{ {
float D[NUMX][NUMX], T, Tsq; float *Fjrow = F[j];
uint8_t i, j; int8_t Fjstart = FrowMin[j];
int8_t Fjend = FrowMax[j];
// Pnew = (I+F*T)*P*(I+F*T)' + T^2*G*Q*G' = scalar expansion from symbolic manipulator int8_t k;
for (k = Fjstart; k <= Fjend; k++) {
T = dT; Ptmp += Dirow[k] * Fjrow[k]; // [] + Dummy*F' ...
Tsq = dT * dT; }
}
for (i = 0; i < NUMX; i++) // Create a copy of the upper triangular of P
for (j = i; j < NUMX; j++) {
D[i][j] = P[i][j]; float *Gjrow = G[j];
int8_t Gjstart = MAX(Gistart, GrowMin[j]);
// Brute force calculation of the elements of P int8_t Gjend = MIN(Giend, GrowMax[j]);
P[0][0] = D[3][3] * Tsq + (2 * D[0][3]) * T + D[0][0]; int8_t k;
P[0][1] = P[1][0] = for (k = Gjstart; k <= Gjend; k++) {
D[3][4] * Tsq + (D[0][4] + D[1][3]) * T + D[0][1]; Ptmp += Q[k] * Girow[k] * Gjrow[k]; // [] + G*Q*G' ...
P[0][2] = P[2][0] = }
D[3][5] * Tsq + (D[0][5] + D[2][3]) * T + D[0][2]; }
P[0][3] = P[3][0] =
(F[3][6] * D[3][6] + F[3][7] * D[3][7] + F[3][8] * D[3][8] + P[j][i] = Pirow[j] = Ptmp * dTsq; // [] * (T^2)
F[3][9] * D[3][9]) * Tsq + (D[3][3] + F[3][6] * D[0][6] + }
F[3][7] * D[0][7] + }
F[3][8] * D[0][8] +
F[3][9] * D[0][9]) * T + D[0][3];
P[0][4] = P[4][0] =
(F[4][6] * D[3][6] + F[4][7] * D[3][7] + F[4][8] * D[3][8] +
F[4][9] * D[3][9]) * Tsq + (D[3][4] + F[4][6] * D[0][6] +
F[4][7] * D[0][7] +
F[4][8] * D[0][8] +
F[4][9] * D[0][9]) * T + D[0][4];
P[0][5] = P[5][0] =
(F[5][6] * D[3][6] + F[5][7] * D[3][7] + F[5][8] * D[3][8] +
F[5][9] * D[3][9]) * Tsq + (D[3][5] + F[5][6] * D[0][6] +
F[5][7] * D[0][7] +
F[5][8] * D[0][8] +
F[5][9] * D[0][9]) * T + D[0][5];
P[0][6] = P[6][0] =
(F[6][7] * D[3][7] + F[6][8] * D[3][8] + F[6][9] * D[3][9] +
F[6][10] * D[3][10] + F[6][11] * D[3][11] +
F[6][12] * D[3][12]) * Tsq + (D[3][6] + F[6][7] * D[0][7] +
F[6][8] * D[0][8] +
F[6][9] * D[0][9] +
F[6][10] * D[0][10] +
F[6][11] * D[0][11] +
F[6][12] * D[0][12]) * T +
D[0][6];
P[0][7] = P[7][0] =
(F[7][6] * D[3][6] + F[7][8] * D[3][8] + F[7][9] * D[3][9] +
F[7][10] * D[3][10] + F[7][11] * D[3][11] +
F[7][12] * D[3][12]) * Tsq + (D[3][7] + F[7][6] * D[0][6] +
F[7][8] * D[0][8] +
F[7][9] * D[0][9] +
F[7][10] * D[0][10] +
F[7][11] * D[0][11] +
F[7][12] * D[0][12]) * T +
D[0][7];
P[0][8] = P[8][0] =
(F[8][6] * D[3][6] + F[8][7] * D[3][7] + F[8][9] * D[3][9] +
F[8][10] * D[3][10] + F[8][11] * D[3][11] +
F[8][12] * D[3][12]) * Tsq + (D[3][8] + F[8][6] * D[0][6] +
F[8][7] * D[0][7] +
F[8][9] * D[0][9] +
F[8][10] * D[0][10] +
F[8][11] * D[0][11] +
F[8][12] * D[0][12]) * T +
D[0][8];
P[0][9] = P[9][0] =
(F[9][6] * D[3][6] + F[9][7] * D[3][7] + F[9][8] * D[3][8] +
F[9][10] * D[3][10] + F[9][11] * D[3][11] +
F[9][12] * D[3][12]) * Tsq + (D[3][9] + F[9][6] * D[0][6] +
F[9][7] * D[0][7] +
F[9][8] * D[0][8] +
F[9][10] * D[0][10] +
F[9][11] * D[0][11] +
F[9][12] * D[0][12]) * T +
D[0][9];
P[0][10] = P[10][0] = D[3][10] * T + D[0][10];
P[0][11] = P[11][0] = D[3][11] * T + D[0][11];
P[0][12] = P[12][0] = D[3][12] * T + D[0][12];
P[1][1] = D[4][4] * Tsq + (2 * D[1][4]) * T + D[1][1];
P[1][2] = P[2][1] =
D[4][5] * Tsq + (D[1][5] + D[2][4]) * T + D[1][2];
P[1][3] = P[3][1] =
(F[3][6] * D[4][6] + F[3][7] * D[4][7] + F[3][8] * D[4][8] +
F[3][9] * D[4][9]) * Tsq + (D[3][4] + F[3][6] * D[1][6] +
F[3][7] * D[1][7] +
F[3][8] * D[1][8] +
F[3][9] * D[1][9]) * T + D[1][3];
P[1][4] = P[4][1] =
(F[4][6] * D[4][6] + F[4][7] * D[4][7] + F[4][8] * D[4][8] +
F[4][9] * D[4][9]) * Tsq + (D[4][4] + F[4][6] * D[1][6] +
F[4][7] * D[1][7] +
F[4][8] * D[1][8] +
F[4][9] * D[1][9]) * T + D[1][4];
P[1][5] = P[5][1] =
(F[5][6] * D[4][6] + F[5][7] * D[4][7] + F[5][8] * D[4][8] +
F[5][9] * D[4][9]) * Tsq + (D[4][5] + F[5][6] * D[1][6] +
F[5][7] * D[1][7] +
F[5][8] * D[1][8] +
F[5][9] * D[1][9]) * T + D[1][5];
P[1][6] = P[6][1] =
(F[6][7] * D[4][7] + F[6][8] * D[4][8] + F[6][9] * D[4][9] +
F[6][10] * D[4][10] + F[6][11] * D[4][11] +
F[6][12] * D[4][12]) * Tsq + (D[4][6] + F[6][7] * D[1][7] +
F[6][8] * D[1][8] +
F[6][9] * D[1][9] +
F[6][10] * D[1][10] +
F[6][11] * D[1][11] +
F[6][12] * D[1][12]) * T +
D[1][6];
P[1][7] = P[7][1] =
(F[7][6] * D[4][6] + F[7][8] * D[4][8] + F[7][9] * D[4][9] +
F[7][10] * D[4][10] + F[7][11] * D[4][11] +
F[7][12] * D[4][12]) * Tsq + (D[4][7] + F[7][6] * D[1][6] +
F[7][8] * D[1][8] +
F[7][9] * D[1][9] +
F[7][10] * D[1][10] +
F[7][11] * D[1][11] +
F[7][12] * D[1][12]) * T +
D[1][7];
P[1][8] = P[8][1] =
(F[8][6] * D[4][6] + F[8][7] * D[4][7] + F[8][9] * D[4][9] +
F[8][10] * D[4][10] + F[8][11] * D[4][11] +
F[8][12] * D[4][12]) * Tsq + (D[4][8] + F[8][6] * D[1][6] +
F[8][7] * D[1][7] +
F[8][9] * D[1][9] +
F[8][10] * D[1][10] +
F[8][11] * D[1][11] +
F[8][12] * D[1][12]) * T +
D[1][8];
P[1][9] = P[9][1] =
(F[9][6] * D[4][6] + F[9][7] * D[4][7] + F[9][8] * D[4][8] +
F[9][10] * D[4][10] + F[9][11] * D[4][11] +
F[9][12] * D[4][12]) * Tsq + (D[4][9] + F[9][6] * D[1][6] +
F[9][7] * D[1][7] +
F[9][8] * D[1][8] +
F[9][10] * D[1][10] +
F[9][11] * D[1][11] +
F[9][12] * D[1][12]) * T +
D[1][9];
P[1][10] = P[10][1] = D[4][10] * T + D[1][10];
P[1][11] = P[11][1] = D[4][11] * T + D[1][11];
P[1][12] = P[12][1] = D[4][12] * T + D[1][12];
P[2][2] = D[5][5] * Tsq + (2 * D[2][5]) * T + D[2][2];
P[2][3] = P[3][2] =
(F[3][6] * D[5][6] + F[3][7] * D[5][7] + F[3][8] * D[5][8] +
F[3][9] * D[5][9]) * Tsq + (D[3][5] + F[3][6] * D[2][6] +
F[3][7] * D[2][7] +
F[3][8] * D[2][8] +
F[3][9] * D[2][9]) * T + D[2][3];
P[2][4] = P[4][2] =
(F[4][6] * D[5][6] + F[4][7] * D[5][7] + F[4][8] * D[5][8] +
F[4][9] * D[5][9]) * Tsq + (D[4][5] + F[4][6] * D[2][6] +
F[4][7] * D[2][7] +
F[4][8] * D[2][8] +
F[4][9] * D[2][9]) * T + D[2][4];
P[2][5] = P[5][2] =
(F[5][6] * D[5][6] + F[5][7] * D[5][7] + F[5][8] * D[5][8] +
F[5][9] * D[5][9]) * Tsq + (D[5][5] + F[5][6] * D[2][6] +
F[5][7] * D[2][7] +
F[5][8] * D[2][8] +
F[5][9] * D[2][9]) * T + D[2][5];
P[2][6] = P[6][2] =
(F[6][7] * D[5][7] + F[6][8] * D[5][8] + F[6][9] * D[5][9] +
F[6][10] * D[5][10] + F[6][11] * D[5][11] +
F[6][12] * D[5][12]) * Tsq + (D[5][6] + F[6][7] * D[2][7] +
F[6][8] * D[2][8] +
F[6][9] * D[2][9] +
F[6][10] * D[2][10] +
F[6][11] * D[2][11] +
F[6][12] * D[2][12]) * T +
D[2][6];
P[2][7] = P[7][2] =
(F[7][6] * D[5][6] + F[7][8] * D[5][8] + F[7][9] * D[5][9] +
F[7][10] * D[5][10] + F[7][11] * D[5][11] +
F[7][12] * D[5][12]) * Tsq + (D[5][7] + F[7][6] * D[2][6] +
F[7][8] * D[2][8] +
F[7][9] * D[2][9] +
F[7][10] * D[2][10] +
F[7][11] * D[2][11] +
F[7][12] * D[2][12]) * T +
D[2][7];
P[2][8] = P[8][2] =
(F[8][6] * D[5][6] + F[8][7] * D[5][7] + F[8][9] * D[5][9] +
F[8][10] * D[5][10] + F[8][11] * D[5][11] +
F[8][12] * D[5][12]) * Tsq + (D[5][8] + F[8][6] * D[2][6] +
F[8][7] * D[2][7] +
F[8][9] * D[2][9] +
F[8][10] * D[2][10] +
F[8][11] * D[2][11] +
F[8][12] * D[2][12]) * T +
D[2][8];
P[2][9] = P[9][2] =
(F[9][6] * D[5][6] + F[9][7] * D[5][7] + F[9][8] * D[5][8] +
F[9][10] * D[5][10] + F[9][11] * D[5][11] +
F[9][12] * D[5][12]) * Tsq + (D[5][9] + F[9][6] * D[2][6] +
F[9][7] * D[2][7] +
F[9][8] * D[2][8] +
F[9][10] * D[2][10] +
F[9][11] * D[2][11] +
F[9][12] * D[2][12]) * T +
D[2][9];
P[2][10] = P[10][2] = D[5][10] * T + D[2][10];
P[2][11] = P[11][2] = D[5][11] * T + D[2][11];
P[2][12] = P[12][2] = D[5][12] * T + D[2][12];
P[3][3] =
(Q[3] * G[3][3] * G[3][3] + Q[4] * G[3][4] * G[3][4] +
Q[5] * G[3][5] * G[3][5] + F[3][9] * (F[3][9] * D[9][9] +
F[3][6] * D[6][9] +
F[3][7] * D[7][9] +
F[3][8] * D[8][9]) +
F[3][6] * (F[3][6] * D[6][6] + F[3][7] * D[6][7] +
F[3][8] * D[6][8] + F[3][9] * D[6][9]) +
F[3][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] +
F[3][8] * D[7][8] + F[3][9] * D[7][9]) +
F[3][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] +
F[3][8] * D[8][8] + F[3][9] * D[8][9])) * Tsq +
(2 * F[3][6] * D[3][6] + 2 * F[3][7] * D[3][7] +
2 * F[3][8] * D[3][8] + 2 * F[3][9] * D[3][9]) * T + D[3][3];
P[3][4] = P[4][3] =
(F[4][9] *
(F[3][9] * D[9][9] + F[3][6] * D[6][9] + F[3][7] * D[7][9] +
F[3][8] * D[8][9]) + F[4][6] * (F[3][6] * D[6][6] +
F[3][7] * D[6][7] +
F[3][8] * D[6][8] +
F[3][9] * D[6][9]) +
F[4][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] +
F[3][8] * D[7][8] + F[3][9] * D[7][9]) +
F[4][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] +
F[3][8] * D[8][8] + F[3][9] * D[8][9]) +
G[3][3] * G[4][3] * Q[3] + G[3][4] * G[4][4] * Q[4] +
G[3][5] * G[4][5] * Q[5]) * Tsq + (F[3][6] * D[4][6] +
F[4][6] * D[3][6] +
F[3][7] * D[4][7] +
F[4][7] * D[3][7] +
F[3][8] * D[4][8] +
F[4][8] * D[3][8] +
F[3][9] * D[4][9] +
F[4][9] * D[3][9]) * T +
D[3][4];
P[3][5] = P[5][3] =
(F[5][9] *
(F[3][9] * D[9][9] + F[3][6] * D[6][9] + F[3][7] * D[7][9] +
F[3][8] * D[8][9]) + F[5][6] * (F[3][6] * D[6][6] +
F[3][7] * D[6][7] +
F[3][8] * D[6][8] +
F[3][9] * D[6][9]) +
F[5][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] +
F[3][8] * D[7][8] + F[3][9] * D[7][9]) +
F[5][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] +
F[3][8] * D[8][8] + F[3][9] * D[8][9]) +
G[3][3] * G[5][3] * Q[3] + G[3][4] * G[5][4] * Q[4] +
G[3][5] * G[5][5] * Q[5]) * Tsq + (F[3][6] * D[5][6] +
F[5][6] * D[3][6] +
F[3][7] * D[5][7] +
F[5][7] * D[3][7] +
F[3][8] * D[5][8] +
F[5][8] * D[3][8] +
F[3][9] * D[5][9] +
F[5][9] * D[3][9]) * T +
D[3][5];
P[3][6] = P[6][3] =
(F[6][9] *
(F[3][9] * D[9][9] + F[3][6] * D[6][9] + F[3][7] * D[7][9] +
F[3][8] * D[8][9]) + F[6][10] * (F[3][9] * D[9][10] +
F[3][6] * D[6][10] +
F[3][7] * D[7][10] +
F[3][8] * D[8][10]) +
F[6][11] * (F[3][9] * D[9][11] + F[3][6] * D[6][11] +
F[3][7] * D[7][11] + F[3][8] * D[8][11]) +
F[6][12] * (F[3][9] * D[9][12] + F[3][6] * D[6][12] +
F[3][7] * D[7][12] + F[3][8] * D[8][12]) +
F[6][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] +
F[3][8] * D[7][8] + F[3][9] * D[7][9]) +
F[6][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] +
F[3][8] * D[8][8] + F[3][9] * D[8][9])) * Tsq +
(F[3][6] * D[6][6] + F[3][7] * D[6][7] + F[6][7] * D[3][7] +
F[3][8] * D[6][8] + F[6][8] * D[3][8] + F[3][9] * D[6][9] +
F[6][9] * D[3][9] + F[6][10] * D[3][10] +
F[6][11] * D[3][11] + F[6][12] * D[3][12]) * T + D[3][6];
P[3][7] = P[7][3] =
(F[7][9] *
(F[3][9] * D[9][9] + F[3][6] * D[6][9] + F[3][7] * D[7][9] +
F[3][8] * D[8][9]) + F[7][10] * (F[3][9] * D[9][10] +
F[3][6] * D[6][10] +
F[3][7] * D[7][10] +
F[3][8] * D[8][10]) +
F[7][11] * (F[3][9] * D[9][11] + F[3][6] * D[6][11] +
F[3][7] * D[7][11] + F[3][8] * D[8][11]) +
F[7][12] * (F[3][9] * D[9][12] + F[3][6] * D[6][12] +
F[3][7] * D[7][12] + F[3][8] * D[8][12]) +
F[7][6] * (F[3][6] * D[6][6] + F[3][7] * D[6][7] +
F[3][8] * D[6][8] + F[3][9] * D[6][9]) +
F[7][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] +
F[3][8] * D[8][8] + F[3][9] * D[8][9])) * Tsq +
(F[3][6] * D[6][7] + F[7][6] * D[3][6] + F[3][7] * D[7][7] +
F[3][8] * D[7][8] + F[7][8] * D[3][8] + F[3][9] * D[7][9] +
F[7][9] * D[3][9] + F[7][10] * D[3][10] +
F[7][11] * D[3][11] + F[7][12] * D[3][12]) * T + D[3][7];
P[3][8] = P[8][3] =
(F[8][9] *
(F[3][9] * D[9][9] + F[3][6] * D[6][9] + F[3][7] * D[7][9] +
F[3][8] * D[8][9]) + F[8][10] * (F[3][9] * D[9][10] +
F[3][6] * D[6][10] +
F[3][7] * D[7][10] +
F[3][8] * D[8][10]) +
F[8][11] * (F[3][9] * D[9][11] + F[3][6] * D[6][11] +
F[3][7] * D[7][11] + F[3][8] * D[8][11]) +
F[8][12] * (F[3][9] * D[9][12] + F[3][6] * D[6][12] +
F[3][7] * D[7][12] + F[3][8] * D[8][12]) +
F[8][6] * (F[3][6] * D[6][6] + F[3][7] * D[6][7] +
F[3][8] * D[6][8] + F[3][9] * D[6][9]) +
F[8][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] +
F[3][8] * D[7][8] + F[3][9] * D[7][9])) * Tsq +
(F[3][6] * D[6][8] + F[3][7] * D[7][8] + F[8][6] * D[3][6] +
F[8][7] * D[3][7] + F[3][8] * D[8][8] + F[3][9] * D[8][9] +
F[8][9] * D[3][9] + F[8][10] * D[3][10] +
F[8][11] * D[3][11] + F[8][12] * D[3][12]) * T + D[3][8];
P[3][9] = P[9][3] =
(F[9][10] *
(F[3][9] * D[9][10] + F[3][6] * D[6][10] +
F[3][7] * D[7][10] + F[3][8] * D[8][10]) +
F[9][11] * (F[3][9] * D[9][11] + F[3][6] * D[6][11] +
F[3][7] * D[7][11] + F[3][8] * D[8][11]) +
F[9][12] * (F[3][9] * D[9][12] + F[3][6] * D[6][12] +
F[3][7] * D[7][12] + F[3][8] * D[8][12]) +
F[9][6] * (F[3][6] * D[6][6] + F[3][7] * D[6][7] +
F[3][8] * D[6][8] + F[3][9] * D[6][9]) +
F[9][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] +
F[3][8] * D[7][8] + F[3][9] * D[7][9]) +
F[9][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] +
F[3][8] * D[8][8] + F[3][9] * D[8][9])) * Tsq +
(F[9][6] * D[3][6] + F[9][7] * D[3][7] + F[9][8] * D[3][8] +
F[3][9] * D[9][9] + F[9][10] * D[3][10] +
F[9][11] * D[3][11] + F[9][12] * D[3][12] +
F[3][6] * D[6][9] + F[3][7] * D[7][9] +
F[3][8] * D[8][9]) * T + D[3][9];
P[3][10] = P[10][3] =
(F[3][9] * D[9][10] + F[3][6] * D[6][10] + F[3][7] * D[7][10] +
F[3][8] * D[8][10]) * T + D[3][10];
P[3][11] = P[11][3] =
(F[3][9] * D[9][11] + F[3][6] * D[6][11] + F[3][7] * D[7][11] +
F[3][8] * D[8][11]) * T + D[3][11];
P[3][12] = P[12][3] =
(F[3][9] * D[9][12] + F[3][6] * D[6][12] + F[3][7] * D[7][12] +
F[3][8] * D[8][12]) * T + D[3][12];
P[4][4] =
(Q[3] * G[4][3] * G[4][3] + Q[4] * G[4][4] * G[4][4] +
Q[5] * G[4][5] * G[4][5] + F[4][9] * (F[4][9] * D[9][9] +
F[4][6] * D[6][9] +
F[4][7] * D[7][9] +
F[4][8] * D[8][9]) +
F[4][6] * (F[4][6] * D[6][6] + F[4][7] * D[6][7] +
F[4][8] * D[6][8] + F[4][9] * D[6][9]) +
F[4][7] * (F[4][6] * D[6][7] + F[4][7] * D[7][7] +
F[4][8] * D[7][8] + F[4][9] * D[7][9]) +
F[4][8] * (F[4][6] * D[6][8] + F[4][7] * D[7][8] +
F[4][8] * D[8][8] + F[4][9] * D[8][9])) * Tsq +
(2 * F[4][6] * D[4][6] + 2 * F[4][7] * D[4][7] +
2 * F[4][8] * D[4][8] + 2 * F[4][9] * D[4][9]) * T + D[4][4];
P[4][5] = P[5][4] =
(F[5][9] *
(F[4][9] * D[9][9] + F[4][6] * D[6][9] + F[4][7] * D[7][9] +
F[4][8] * D[8][9]) + F[5][6] * (F[4][6] * D[6][6] +
F[4][7] * D[6][7] +
F[4][8] * D[6][8] +
F[4][9] * D[6][9]) +
F[5][7] * (F[4][6] * D[6][7] + F[4][7] * D[7][7] +
F[4][8] * D[7][8] + F[4][9] * D[7][9]) +
F[5][8] * (F[4][6] * D[6][8] + F[4][7] * D[7][8] +
F[4][8] * D[8][8] + F[4][9] * D[8][9]) +
G[4][3] * G[5][3] * Q[3] + G[4][4] * G[5][4] * Q[4] +
G[4][5] * G[5][5] * Q[5]) * Tsq + (F[4][6] * D[5][6] +
F[5][6] * D[4][6] +
F[4][7] * D[5][7] +
F[5][7] * D[4][7] +
F[4][8] * D[5][8] +
F[5][8] * D[4][8] +
F[4][9] * D[5][9] +
F[5][9] * D[4][9]) * T +
D[4][5];
P[4][6] = P[6][4] =
(F[6][9] *
(F[4][9] * D[9][9] + F[4][6] * D[6][9] + F[4][7] * D[7][9] +
F[4][8] * D[8][9]) + F[6][10] * (F[4][9] * D[9][10] +
F[4][6] * D[6][10] +
F[4][7] * D[7][10] +
F[4][8] * D[8][10]) +
F[6][11] * (F[4][9] * D[9][11] + F[4][6] * D[6][11] +
F[4][7] * D[7][11] + F[4][8] * D[8][11]) +
F[6][12] * (F[4][9] * D[9][12] + F[4][6] * D[6][12] +
F[4][7] * D[7][12] + F[4][8] * D[8][12]) +
F[6][7] * (F[4][6] * D[6][7] + F[4][7] * D[7][7] +
F[4][8] * D[7][8] + F[4][9] * D[7][9]) +
F[6][8] * (F[4][6] * D[6][8] + F[4][7] * D[7][8] +
F[4][8] * D[8][8] + F[4][9] * D[8][9])) * Tsq +
(F[4][6] * D[6][6] + F[4][7] * D[6][7] + F[6][7] * D[4][7] +
F[4][8] * D[6][8] + F[6][8] * D[4][8] + F[4][9] * D[6][9] +
F[6][9] * D[4][9] + F[6][10] * D[4][10] +
F[6][11] * D[4][11] + F[6][12] * D[4][12]) * T + D[4][6];
P[4][7] = P[7][4] =
(F[7][9] *
(F[4][9] * D[9][9] + F[4][6] * D[6][9] + F[4][7] * D[7][9] +
F[4][8] * D[8][9]) + F[7][10] * (F[4][9] * D[9][10] +
F[4][6] * D[6][10] +
F[4][7] * D[7][10] +
F[4][8] * D[8][10]) +
F[7][11] * (F[4][9] * D[9][11] + F[4][6] * D[6][11] +
F[4][7] * D[7][11] + F[4][8] * D[8][11]) +
F[7][12] * (F[4][9] * D[9][12] + F[4][6] * D[6][12] +
F[4][7] * D[7][12] + F[4][8] * D[8][12]) +
F[7][6] * (F[4][6] * D[6][6] + F[4][7] * D[6][7] +
F[4][8] * D[6][8] + F[4][9] * D[6][9]) +
F[7][8] * (F[4][6] * D[6][8] + F[4][7] * D[7][8] +
F[4][8] * D[8][8] + F[4][9] * D[8][9])) * Tsq +
(F[4][6] * D[6][7] + F[7][6] * D[4][6] + F[4][7] * D[7][7] +
F[4][8] * D[7][8] + F[7][8] * D[4][8] + F[4][9] * D[7][9] +
F[7][9] * D[4][9] + F[7][10] * D[4][10] +
F[7][11] * D[4][11] + F[7][12] * D[4][12]) * T + D[4][7];
P[4][8] = P[8][4] =
(F[8][9] *
(F[4][9] * D[9][9] + F[4][6] * D[6][9] + F[4][7] * D[7][9] +
F[4][8] * D[8][9]) + F[8][10] * (F[4][9] * D[9][10] +
F[4][6] * D[6][10] +
F[4][7] * D[7][10] +
F[4][8] * D[8][10]) +
F[8][11] * (F[4][9] * D[9][11] + F[4][6] * D[6][11] +
F[4][7] * D[7][11] + F[4][8] * D[8][11]) +
F[8][12] * (F[4][9] * D[9][12] + F[4][6] * D[6][12] +
F[4][7] * D[7][12] + F[4][8] * D[8][12]) +
F[8][6] * (F[4][6] * D[6][6] + F[4][7] * D[6][7] +
F[4][8] * D[6][8] + F[4][9] * D[6][9]) +
F[8][7] * (F[4][6] * D[6][7] + F[4][7] * D[7][7] +
F[4][8] * D[7][8] + F[4][9] * D[7][9])) * Tsq +
(F[4][6] * D[6][8] + F[4][7] * D[7][8] + F[8][6] * D[4][6] +
F[8][7] * D[4][7] + F[4][8] * D[8][8] + F[4][9] * D[8][9] +
F[8][9] * D[4][9] + F[8][10] * D[4][10] +
F[8][11] * D[4][11] + F[8][12] * D[4][12]) * T + D[4][8];
P[4][9] = P[9][4] =
(F[9][10] *
(F[4][9] * D[9][10] + F[4][6] * D[6][10] +
F[4][7] * D[7][10] + F[4][8] * D[8][10]) +
F[9][11] * (F[4][9] * D[9][11] + F[4][6] * D[6][11] +
F[4][7] * D[7][11] + F[4][8] * D[8][11]) +
F[9][12] * (F[4][9] * D[9][12] + F[4][6] * D[6][12] +
F[4][7] * D[7][12] + F[4][8] * D[8][12]) +
F[9][6] * (F[4][6] * D[6][6] + F[4][7] * D[6][7] +
F[4][8] * D[6][8] + F[4][9] * D[6][9]) +
F[9][7] * (F[4][6] * D[6][7] + F[4][7] * D[7][7] +
F[4][8] * D[7][8] + F[4][9] * D[7][9]) +
F[9][8] * (F[4][6] * D[6][8] + F[4][7] * D[7][8] +
F[4][8] * D[8][8] + F[4][9] * D[8][9])) * Tsq +
(F[9][6] * D[4][6] + F[9][7] * D[4][7] + F[9][8] * D[4][8] +
F[4][9] * D[9][9] + F[9][10] * D[4][10] +
F[9][11] * D[4][11] + F[9][12] * D[4][12] +
F[4][6] * D[6][9] + F[4][7] * D[7][9] +
F[4][8] * D[8][9]) * T + D[4][9];
P[4][10] = P[10][4] =
(F[4][9] * D[9][10] + F[4][6] * D[6][10] + F[4][7] * D[7][10] +
F[4][8] * D[8][10]) * T + D[4][10];
P[4][11] = P[11][4] =
(F[4][9] * D[9][11] + F[4][6] * D[6][11] + F[4][7] * D[7][11] +
F[4][8] * D[8][11]) * T + D[4][11];
P[4][12] = P[12][4] =
(F[4][9] * D[9][12] + F[4][6] * D[6][12] + F[4][7] * D[7][12] +
F[4][8] * D[8][12]) * T + D[4][12];
P[5][5] =
(Q[3] * G[5][3] * G[5][3] + Q[4] * G[5][4] * G[5][4] +
Q[5] * G[5][5] * G[5][5] + F[5][9] * (F[5][9] * D[9][9] +
F[5][6] * D[6][9] +
F[5][7] * D[7][9] +
F[5][8] * D[8][9]) +
F[5][6] * (F[5][6] * D[6][6] + F[5][7] * D[6][7] +
F[5][8] * D[6][8] + F[5][9] * D[6][9]) +
F[5][7] * (F[5][6] * D[6][7] + F[5][7] * D[7][7] +
F[5][8] * D[7][8] + F[5][9] * D[7][9]) +
F[5][8] * (F[5][6] * D[6][8] + F[5][7] * D[7][8] +
F[5][8] * D[8][8] + F[5][9] * D[8][9])) * Tsq +
(2 * F[5][6] * D[5][6] + 2 * F[5][7] * D[5][7] +
2 * F[5][8] * D[5][8] + 2 * F[5][9] * D[5][9]) * T + D[5][5];
P[5][6] = P[6][5] =
(F[6][9] *
(F[5][9] * D[9][9] + F[5][6] * D[6][9] + F[5][7] * D[7][9] +
F[5][8] * D[8][9]) + F[6][10] * (F[5][9] * D[9][10] +
F[5][6] * D[6][10] +
F[5][7] * D[7][10] +
F[5][8] * D[8][10]) +
F[6][11] * (F[5][9] * D[9][11] + F[5][6] * D[6][11] +
F[5][7] * D[7][11] + F[5][8] * D[8][11]) +
F[6][12] * (F[5][9] * D[9][12] + F[5][6] * D[6][12] +
F[5][7] * D[7][12] + F[5][8] * D[8][12]) +
F[6][7] * (F[5][6] * D[6][7] + F[5][7] * D[7][7] +
F[5][8] * D[7][8] + F[5][9] * D[7][9]) +
F[6][8] * (F[5][6] * D[6][8] + F[5][7] * D[7][8] +
F[5][8] * D[8][8] + F[5][9] * D[8][9])) * Tsq +
(F[5][6] * D[6][6] + F[5][7] * D[6][7] + F[6][7] * D[5][7] +
F[5][8] * D[6][8] + F[6][8] * D[5][8] + F[5][9] * D[6][9] +
F[6][9] * D[5][9] + F[6][10] * D[5][10] +
F[6][11] * D[5][11] + F[6][12] * D[5][12]) * T + D[5][6];
P[5][7] = P[7][5] =
(F[7][9] *
(F[5][9] * D[9][9] + F[5][6] * D[6][9] + F[5][7] * D[7][9] +
F[5][8] * D[8][9]) + F[7][10] * (F[5][9] * D[9][10] +
F[5][6] * D[6][10] +
F[5][7] * D[7][10] +
F[5][8] * D[8][10]) +
F[7][11] * (F[5][9] * D[9][11] + F[5][6] * D[6][11] +
F[5][7] * D[7][11] + F[5][8] * D[8][11]) +
F[7][12] * (F[5][9] * D[9][12] + F[5][6] * D[6][12] +
F[5][7] * D[7][12] + F[5][8] * D[8][12]) +
F[7][6] * (F[5][6] * D[6][6] + F[5][7] * D[6][7] +
F[5][8] * D[6][8] + F[5][9] * D[6][9]) +
F[7][8] * (F[5][6] * D[6][8] + F[5][7] * D[7][8] +
F[5][8] * D[8][8] + F[5][9] * D[8][9])) * Tsq +
(F[5][6] * D[6][7] + F[7][6] * D[5][6] + F[5][7] * D[7][7] +
F[5][8] * D[7][8] + F[7][8] * D[5][8] + F[5][9] * D[7][9] +
F[7][9] * D[5][9] + F[7][10] * D[5][10] +
F[7][11] * D[5][11] + F[7][12] * D[5][12]) * T + D[5][7];
P[5][8] = P[8][5] =
(F[8][9] *
(F[5][9] * D[9][9] + F[5][6] * D[6][9] + F[5][7] * D[7][9] +
F[5][8] * D[8][9]) + F[8][10] * (F[5][9] * D[9][10] +
F[5][6] * D[6][10] +
F[5][7] * D[7][10] +
F[5][8] * D[8][10]) +
F[8][11] * (F[5][9] * D[9][11] + F[5][6] * D[6][11] +
F[5][7] * D[7][11] + F[5][8] * D[8][11]) +
F[8][12] * (F[5][9] * D[9][12] + F[5][6] * D[6][12] +
F[5][7] * D[7][12] + F[5][8] * D[8][12]) +
F[8][6] * (F[5][6] * D[6][6] + F[5][7] * D[6][7] +
F[5][8] * D[6][8] + F[5][9] * D[6][9]) +
F[8][7] * (F[5][6] * D[6][7] + F[5][7] * D[7][7] +
F[5][8] * D[7][8] + F[5][9] * D[7][9])) * Tsq +
(F[5][6] * D[6][8] + F[5][7] * D[7][8] + F[8][6] * D[5][6] +
F[8][7] * D[5][7] + F[5][8] * D[8][8] + F[5][9] * D[8][9] +
F[8][9] * D[5][9] + F[8][10] * D[5][10] +
F[8][11] * D[5][11] + F[8][12] * D[5][12]) * T + D[5][8];
P[5][9] = P[9][5] =
(F[9][10] *
(F[5][9] * D[9][10] + F[5][6] * D[6][10] +
F[5][7] * D[7][10] + F[5][8] * D[8][10]) +
F[9][11] * (F[5][9] * D[9][11] + F[5][6] * D[6][11] +
F[5][7] * D[7][11] + F[5][8] * D[8][11]) +
F[9][12] * (F[5][9] * D[9][12] + F[5][6] * D[6][12] +
F[5][7] * D[7][12] + F[5][8] * D[8][12]) +
F[9][6] * (F[5][6] * D[6][6] + F[5][7] * D[6][7] +
F[5][8] * D[6][8] + F[5][9] * D[6][9]) +
F[9][7] * (F[5][6] * D[6][7] + F[5][7] * D[7][7] +
F[5][8] * D[7][8] + F[5][9] * D[7][9]) +
F[9][8] * (F[5][6] * D[6][8] + F[5][7] * D[7][8] +
F[5][8] * D[8][8] + F[5][9] * D[8][9])) * Tsq +
(F[9][6] * D[5][6] + F[9][7] * D[5][7] + F[9][8] * D[5][8] +
F[5][9] * D[9][9] + F[9][10] * D[5][10] +
F[9][11] * D[5][11] + F[9][12] * D[5][12] +
F[5][6] * D[6][9] + F[5][7] * D[7][9] +
F[5][8] * D[8][9]) * T + D[5][9];
P[5][10] = P[10][5] =
(F[5][9] * D[9][10] + F[5][6] * D[6][10] + F[5][7] * D[7][10] +
F[5][8] * D[8][10]) * T + D[5][10];
P[5][11] = P[11][5] =
(F[5][9] * D[9][11] + F[5][6] * D[6][11] + F[5][7] * D[7][11] +
F[5][8] * D[8][11]) * T + D[5][11];
P[5][12] = P[12][5] =
(F[5][9] * D[9][12] + F[5][6] * D[6][12] + F[5][7] * D[7][12] +
F[5][8] * D[8][12]) * T + D[5][12];
P[6][6] =
(Q[0] * G[6][0] * G[6][0] + Q[1] * G[6][1] * G[6][1] +
Q[2] * G[6][2] * G[6][2] + F[6][9] * (F[6][9] * D[9][9] +
F[6][10] * D[9][10] +
F[6][11] * D[9][11] +
F[6][12] * D[9][12] +
F[6][7] * D[7][9] +
F[6][8] * D[8][9]) +
F[6][10] * (F[6][9] * D[9][10] + F[6][10] * D[10][10] +
F[6][11] * D[10][11] + F[6][12] * D[10][12] +
F[6][7] * D[7][10] + F[6][8] * D[8][10]) +
F[6][11] * (F[6][9] * D[9][11] + F[6][10] * D[10][11] +
F[6][11] * D[11][11] + F[6][12] * D[11][12] +
F[6][7] * D[7][11] + F[6][8] * D[8][11]) +
F[6][12] * (F[6][9] * D[9][12] + F[6][10] * D[10][12] +
F[6][11] * D[11][12] + F[6][12] * D[12][12] +
F[6][7] * D[7][12] + F[6][8] * D[8][12]) +
F[6][7] * (F[6][7] * D[7][7] + F[6][8] * D[7][8] +
F[6][9] * D[7][9] + F[6][10] * D[7][10] +
F[6][11] * D[7][11] + F[6][12] * D[7][12]) +
F[6][8] * (F[6][7] * D[7][8] + F[6][8] * D[8][8] +
F[6][9] * D[8][9] + F[6][10] * D[8][10] +
F[6][11] * D[8][11] + F[6][12] * D[8][12])) * Tsq +
(2 * F[6][7] * D[6][7] + 2 * F[6][8] * D[6][8] +
2 * F[6][9] * D[6][9] + 2 * F[6][10] * D[6][10] +
2 * F[6][11] * D[6][11] + 2 * F[6][12] * D[6][12]) * T +
D[6][6];
P[6][7] = P[7][6] =
(F[7][9] *
(F[6][9] * D[9][9] + F[6][10] * D[9][10] +
F[6][11] * D[9][11] + F[6][12] * D[9][12] +
F[6][7] * D[7][9] + F[6][8] * D[8][9]) +
F[7][10] * (F[6][9] * D[9][10] + F[6][10] * D[10][10] +
F[6][11] * D[10][11] + F[6][12] * D[10][12] +
F[6][7] * D[7][10] + F[6][8] * D[8][10]) +
F[7][11] * (F[6][9] * D[9][11] + F[6][10] * D[10][11] +
F[6][11] * D[11][11] + F[6][12] * D[11][12] +
F[6][7] * D[7][11] + F[6][8] * D[8][11]) +
F[7][12] * (F[6][9] * D[9][12] + F[6][10] * D[10][12] +
F[6][11] * D[11][12] + F[6][12] * D[12][12] +
F[6][7] * D[7][12] + F[6][8] * D[8][12]) +
F[7][6] * (F[6][7] * D[6][7] + F[6][8] * D[6][8] +
F[6][9] * D[6][9] + F[6][10] * D[6][10] +
F[6][11] * D[6][11] + F[6][12] * D[6][12]) +
F[7][8] * (F[6][7] * D[7][8] + F[6][8] * D[8][8] +
F[6][9] * D[8][9] + F[6][10] * D[8][10] +
F[6][11] * D[8][11] + F[6][12] * D[8][12]) +
G[6][0] * G[7][0] * Q[0] + G[6][1] * G[7][1] * Q[1] +
G[6][2] * G[7][2] * Q[2]) * Tsq + (F[7][6] * D[6][6] +
F[6][7] * D[7][7] +
F[6][8] * D[7][8] +
F[7][8] * D[6][8] +
F[6][9] * D[7][9] +
F[7][9] * D[6][9] +
F[6][10] * D[7][10] +
F[7][10] * D[6][10] +
F[6][11] * D[7][11] +
F[7][11] * D[6][11] +
F[6][12] * D[7][12] +
F[7][12] * D[6][12]) * T +
D[6][7];
P[6][8] = P[8][6] =
(F[8][9] *
(F[6][9] * D[9][9] + F[6][10] * D[9][10] +
F[6][11] * D[9][11] + F[6][12] * D[9][12] +
F[6][7] * D[7][9] + F[6][8] * D[8][9]) +
F[8][10] * (F[6][9] * D[9][10] + F[6][10] * D[10][10] +
F[6][11] * D[10][11] + F[6][12] * D[10][12] +
F[6][7] * D[7][10] + F[6][8] * D[8][10]) +
F[8][11] * (F[6][9] * D[9][11] + F[6][10] * D[10][11] +
F[6][11] * D[11][11] + F[6][12] * D[11][12] +
F[6][7] * D[7][11] + F[6][8] * D[8][11]) +
F[8][12] * (F[6][9] * D[9][12] + F[6][10] * D[10][12] +
F[6][11] * D[11][12] + F[6][12] * D[12][12] +
F[6][7] * D[7][12] + F[6][8] * D[8][12]) +
F[8][6] * (F[6][7] * D[6][7] + F[6][8] * D[6][8] +
F[6][9] * D[6][9] + F[6][10] * D[6][10] +
F[6][11] * D[6][11] + F[6][12] * D[6][12]) +
F[8][7] * (F[6][7] * D[7][7] + F[6][8] * D[7][8] +
F[6][9] * D[7][9] + F[6][10] * D[7][10] +
F[6][11] * D[7][11] + F[6][12] * D[7][12]) +
G[6][0] * G[8][0] * Q[0] + G[6][1] * G[8][1] * Q[1] +
G[6][2] * G[8][2] * Q[2]) * Tsq + (F[6][7] * D[7][8] +
F[8][6] * D[6][6] +
F[8][7] * D[6][7] +
F[6][8] * D[8][8] +
F[6][9] * D[8][9] +
F[8][9] * D[6][9] +
F[6][10] * D[8][10] +
F[8][10] * D[6][10] +
F[6][11] * D[8][11] +
F[8][11] * D[6][11] +
F[6][12] * D[8][12] +
F[8][12] * D[6][12]) * T +
D[6][8];
P[6][9] = P[9][6] =
(F[9][10] *
(F[6][9] * D[9][10] + F[6][10] * D[10][10] +
F[6][11] * D[10][11] + F[6][12] * D[10][12] +
F[6][7] * D[7][10] + F[6][8] * D[8][10]) +
F[9][11] * (F[6][9] * D[9][11] + F[6][10] * D[10][11] +
F[6][11] * D[11][11] + F[6][12] * D[11][12] +
F[6][7] * D[7][11] + F[6][8] * D[8][11]) +
F[9][12] * (F[6][9] * D[9][12] + F[6][10] * D[10][12] +
F[6][11] * D[11][12] + F[6][12] * D[12][12] +
F[6][7] * D[7][12] + F[6][8] * D[8][12]) +
F[9][6] * (F[6][7] * D[6][7] + F[6][8] * D[6][8] +
F[6][9] * D[6][9] + F[6][10] * D[6][10] +
F[6][11] * D[6][11] + F[6][12] * D[6][12]) +
F[9][7] * (F[6][7] * D[7][7] + F[6][8] * D[7][8] +
F[6][9] * D[7][9] + F[6][10] * D[7][10] +
F[6][11] * D[7][11] + F[6][12] * D[7][12]) +
F[9][8] * (F[6][7] * D[7][8] + F[6][8] * D[8][8] +
F[6][9] * D[8][9] + F[6][10] * D[8][10] +
F[6][11] * D[8][11] + F[6][12] * D[8][12]) +
G[9][0] * G[6][0] * Q[0] + G[9][1] * G[6][1] * Q[1] +
G[9][2] * G[6][2] * Q[2]) * Tsq + (F[9][6] * D[6][6] +
F[9][7] * D[6][7] +
F[9][8] * D[6][8] +
F[6][9] * D[9][9] +
F[9][10] * D[6][10] +
F[6][10] * D[9][10] +
F[9][11] * D[6][11] +
F[6][11] * D[9][11] +
F[9][12] * D[6][12] +
F[6][12] * D[9][12] +
F[6][7] * D[7][9] +
F[6][8] * D[8][9]) * T +
D[6][9];
P[6][10] = P[10][6] =
(F[6][9] * D[9][10] + F[6][10] * D[10][10] +
F[6][11] * D[10][11] + F[6][12] * D[10][12] +
F[6][7] * D[7][10] + F[6][8] * D[8][10]) * T + D[6][10];
P[6][11] = P[11][6] =
(F[6][9] * D[9][11] + F[6][10] * D[10][11] +
F[6][11] * D[11][11] + F[6][12] * D[11][12] +
F[6][7] * D[7][11] + F[6][8] * D[8][11]) * T + D[6][11];
P[6][12] = P[12][6] =
(F[6][9] * D[9][12] + F[6][10] * D[10][12] +
F[6][11] * D[11][12] + F[6][12] * D[12][12] +
F[6][7] * D[7][12] + F[6][8] * D[8][12]) * T + D[6][12];
P[7][7] =
(Q[0] * G[7][0] * G[7][0] + Q[1] * G[7][1] * G[7][1] +
Q[2] * G[7][2] * G[7][2] + F[7][9] * (F[7][9] * D[9][9] +
F[7][10] * D[9][10] +
F[7][11] * D[9][11] +
F[7][12] * D[9][12] +
F[7][6] * D[6][9] +
F[7][8] * D[8][9]) +
F[7][10] * (F[7][9] * D[9][10] + F[7][10] * D[10][10] +
F[7][11] * D[10][11] + F[7][12] * D[10][12] +
F[7][6] * D[6][10] + F[7][8] * D[8][10]) +
F[7][11] * (F[7][9] * D[9][11] + F[7][10] * D[10][11] +
F[7][11] * D[11][11] + F[7][12] * D[11][12] +
F[7][6] * D[6][11] + F[7][8] * D[8][11]) +
F[7][12] * (F[7][9] * D[9][12] + F[7][10] * D[10][12] +
F[7][11] * D[11][12] + F[7][12] * D[12][12] +
F[7][6] * D[6][12] + F[7][8] * D[8][12]) +
F[7][6] * (F[7][6] * D[6][6] + F[7][8] * D[6][8] +
F[7][9] * D[6][9] + F[7][10] * D[6][10] +
F[7][11] * D[6][11] + F[7][12] * D[6][12]) +
F[7][8] * (F[7][6] * D[6][8] + F[7][8] * D[8][8] +
F[7][9] * D[8][9] + F[7][10] * D[8][10] +
F[7][11] * D[8][11] + F[7][12] * D[8][12])) * Tsq +
(2 * F[7][6] * D[6][7] + 2 * F[7][8] * D[7][8] +
2 * F[7][9] * D[7][9] + 2 * F[7][10] * D[7][10] +
2 * F[7][11] * D[7][11] + 2 * F[7][12] * D[7][12]) * T +
D[7][7];
P[7][8] = P[8][7] =
(F[8][9] *
(F[7][9] * D[9][9] + F[7][10] * D[9][10] +
F[7][11] * D[9][11] + F[7][12] * D[9][12] +
F[7][6] * D[6][9] + F[7][8] * D[8][9]) +
F[8][10] * (F[7][9] * D[9][10] + F[7][10] * D[10][10] +
F[7][11] * D[10][11] + F[7][12] * D[10][12] +
F[7][6] * D[6][10] + F[7][8] * D[8][10]) +
F[8][11] * (F[7][9] * D[9][11] + F[7][10] * D[10][11] +
F[7][11] * D[11][11] + F[7][12] * D[11][12] +
F[7][6] * D[6][11] + F[7][8] * D[8][11]) +
F[8][12] * (F[7][9] * D[9][12] + F[7][10] * D[10][12] +
F[7][11] * D[11][12] + F[7][12] * D[12][12] +
F[7][6] * D[6][12] + F[7][8] * D[8][12]) +
F[8][6] * (F[7][6] * D[6][6] + F[7][8] * D[6][8] +
F[7][9] * D[6][9] + F[7][10] * D[6][10] +
F[7][11] * D[6][11] + F[7][12] * D[6][12]) +
F[8][7] * (F[7][6] * D[6][7] + F[7][8] * D[7][8] +
F[7][9] * D[7][9] + F[7][10] * D[7][10] +
F[7][11] * D[7][11] + F[7][12] * D[7][12]) +
G[7][0] * G[8][0] * Q[0] + G[7][1] * G[8][1] * Q[1] +
G[7][2] * G[8][2] * Q[2]) * Tsq + (F[7][6] * D[6][8] +
F[8][6] * D[6][7] +
F[8][7] * D[7][7] +
F[7][8] * D[8][8] +
F[7][9] * D[8][9] +
F[8][9] * D[7][9] +
F[7][10] * D[8][10] +
F[8][10] * D[7][10] +
F[7][11] * D[8][11] +
F[8][11] * D[7][11] +
F[7][12] * D[8][12] +
F[8][12] * D[7][12]) * T +
D[7][8];
P[7][9] = P[9][7] =
(F[9][10] *
(F[7][9] * D[9][10] + F[7][10] * D[10][10] +
F[7][11] * D[10][11] + F[7][12] * D[10][12] +
F[7][6] * D[6][10] + F[7][8] * D[8][10]) +
F[9][11] * (F[7][9] * D[9][11] + F[7][10] * D[10][11] +
F[7][11] * D[11][11] + F[7][12] * D[11][12] +
F[7][6] * D[6][11] + F[7][8] * D[8][11]) +
F[9][12] * (F[7][9] * D[9][12] + F[7][10] * D[10][12] +
F[7][11] * D[11][12] + F[7][12] * D[12][12] +
F[7][6] * D[6][12] + F[7][8] * D[8][12]) +
F[9][6] * (F[7][6] * D[6][6] + F[7][8] * D[6][8] +
F[7][9] * D[6][9] + F[7][10] * D[6][10] +
F[7][11] * D[6][11] + F[7][12] * D[6][12]) +
F[9][7] * (F[7][6] * D[6][7] + F[7][8] * D[7][8] +
F[7][9] * D[7][9] + F[7][10] * D[7][10] +
F[7][11] * D[7][11] + F[7][12] * D[7][12]) +
F[9][8] * (F[7][6] * D[6][8] + F[7][8] * D[8][8] +
F[7][9] * D[8][9] + F[7][10] * D[8][10] +
F[7][11] * D[8][11] + F[7][12] * D[8][12]) +
G[9][0] * G[7][0] * Q[0] + G[9][1] * G[7][1] * Q[1] +
G[9][2] * G[7][2] * Q[2]) * Tsq + (F[9][6] * D[6][7] +
F[9][7] * D[7][7] +
F[9][8] * D[7][8] +
F[7][9] * D[9][9] +
F[9][10] * D[7][10] +
F[7][10] * D[9][10] +
F[9][11] * D[7][11] +
F[7][11] * D[9][11] +
F[9][12] * D[7][12] +
F[7][12] * D[9][12] +
F[7][6] * D[6][9] +
F[7][8] * D[8][9]) * T +
D[7][9];
P[7][10] = P[10][7] =
(F[7][9] * D[9][10] + F[7][10] * D[10][10] +
F[7][11] * D[10][11] + F[7][12] * D[10][12] +
F[7][6] * D[6][10] + F[7][8] * D[8][10]) * T + D[7][10];
P[7][11] = P[11][7] =
(F[7][9] * D[9][11] + F[7][10] * D[10][11] +
F[7][11] * D[11][11] + F[7][12] * D[11][12] +
F[7][6] * D[6][11] + F[7][8] * D[8][11]) * T + D[7][11];
P[7][12] = P[12][7] =
(F[7][9] * D[9][12] + F[7][10] * D[10][12] +
F[7][11] * D[11][12] + F[7][12] * D[12][12] +
F[7][6] * D[6][12] + F[7][8] * D[8][12]) * T + D[7][12];
P[8][8] =
(Q[0] * G[8][0] * G[8][0] + Q[1] * G[8][1] * G[8][1] +
Q[2] * G[8][2] * G[8][2] + F[8][9] * (F[8][9] * D[9][9] +
F[8][10] * D[9][10] +
F[8][11] * D[9][11] +
F[8][12] * D[9][12] +
F[8][6] * D[6][9] +
F[8][7] * D[7][9]) +
F[8][10] * (F[8][9] * D[9][10] + F[8][10] * D[10][10] +
F[8][11] * D[10][11] + F[8][12] * D[10][12] +
F[8][6] * D[6][10] + F[8][7] * D[7][10]) +
F[8][11] * (F[8][9] * D[9][11] + F[8][10] * D[10][11] +
F[8][11] * D[11][11] + F[8][12] * D[11][12] +
F[8][6] * D[6][11] + F[8][7] * D[7][11]) +
F[8][12] * (F[8][9] * D[9][12] + F[8][10] * D[10][12] +
F[8][11] * D[11][12] + F[8][12] * D[12][12] +
F[8][6] * D[6][12] + F[8][7] * D[7][12]) +
F[8][6] * (F[8][6] * D[6][6] + F[8][7] * D[6][7] +
F[8][9] * D[6][9] + F[8][10] * D[6][10] +
F[8][11] * D[6][11] + F[8][12] * D[6][12]) +
F[8][7] * (F[8][6] * D[6][7] + F[8][7] * D[7][7] +
F[8][9] * D[7][9] + F[8][10] * D[7][10] +
F[8][11] * D[7][11] + F[8][12] * D[7][12])) * Tsq +
(2 * F[8][6] * D[6][8] + 2 * F[8][7] * D[7][8] +
2 * F[8][9] * D[8][9] + 2 * F[8][10] * D[8][10] +
2 * F[8][11] * D[8][11] + 2 * F[8][12] * D[8][12]) * T +
D[8][8];
P[8][9] = P[9][8] =
(F[9][10] *
(F[8][9] * D[9][10] + F[8][10] * D[10][10] +
F[8][11] * D[10][11] + F[8][12] * D[10][12] +
F[8][6] * D[6][10] + F[8][7] * D[7][10]) +
F[9][11] * (F[8][9] * D[9][11] + F[8][10] * D[10][11] +
F[8][11] * D[11][11] + F[8][12] * D[11][12] +
F[8][6] * D[6][11] + F[8][7] * D[7][11]) +
F[9][12] * (F[8][9] * D[9][12] + F[8][10] * D[10][12] +
F[8][11] * D[11][12] + F[8][12] * D[12][12] +
F[8][6] * D[6][12] + F[8][7] * D[7][12]) +
F[9][6] * (F[8][6] * D[6][6] + F[8][7] * D[6][7] +
F[8][9] * D[6][9] + F[8][10] * D[6][10] +
F[8][11] * D[6][11] + F[8][12] * D[6][12]) +
F[9][7] * (F[8][6] * D[6][7] + F[8][7] * D[7][7] +
F[8][9] * D[7][9] + F[8][10] * D[7][10] +
F[8][11] * D[7][11] + F[8][12] * D[7][12]) +
F[9][8] * (F[8][6] * D[6][8] + F[8][7] * D[7][8] +
F[8][9] * D[8][9] + F[8][10] * D[8][10] +
F[8][11] * D[8][11] + F[8][12] * D[8][12]) +
G[9][0] * G[8][0] * Q[0] + G[9][1] * G[8][1] * Q[1] +
G[9][2] * G[8][2] * Q[2]) * Tsq + (F[9][6] * D[6][8] +
F[9][7] * D[7][8] +
F[9][8] * D[8][8] +
F[8][9] * D[9][9] +
F[9][10] * D[8][10] +
F[8][10] * D[9][10] +
F[9][11] * D[8][11] +
F[8][11] * D[9][11] +
F[9][12] * D[8][12] +
F[8][12] * D[9][12] +
F[8][6] * D[6][9] +
F[8][7] * D[7][9]) * T +
D[8][9];
P[8][10] = P[10][8] =
(F[8][9] * D[9][10] + F[8][10] * D[10][10] +
F[8][11] * D[10][11] + F[8][12] * D[10][12] +
F[8][6] * D[6][10] + F[8][7] * D[7][10]) * T + D[8][10];
P[8][11] = P[11][8] =
(F[8][9] * D[9][11] + F[8][10] * D[10][11] +
F[8][11] * D[11][11] + F[8][12] * D[11][12] +
F[8][6] * D[6][11] + F[8][7] * D[7][11]) * T + D[8][11];
P[8][12] = P[12][8] =
(F[8][9] * D[9][12] + F[8][10] * D[10][12] +
F[8][11] * D[11][12] + F[8][12] * D[12][12] +
F[8][6] * D[6][12] + F[8][7] * D[7][12]) * T + D[8][12];
P[9][9] =
(Q[0] * G[9][0] * G[9][0] + Q[1] * G[9][1] * G[9][1] +
Q[2] * G[9][2] * G[9][2] + F[9][10] * (F[9][10] * D[10][10] +
F[9][11] * D[10][11] +
F[9][12] * D[10][12] +
F[9][6] * D[6][10] +
F[9][7] * D[7][10] +
F[9][8] * D[8][10]) +
F[9][11] * (F[9][10] * D[10][11] + F[9][11] * D[11][11] +
F[9][12] * D[11][12] + F[9][6] * D[6][11] +
F[9][7] * D[7][11] + F[9][8] * D[8][11]) +
F[9][12] * (F[9][10] * D[10][12] + F[9][11] * D[11][12] +
F[9][12] * D[12][12] + F[9][6] * D[6][12] +
F[9][7] * D[7][12] + F[9][8] * D[8][12]) +
F[9][6] * (F[9][6] * D[6][6] + F[9][7] * D[6][7] +
F[9][8] * D[6][8] + F[9][10] * D[6][10] +
F[9][11] * D[6][11] + F[9][12] * D[6][12]) +
F[9][7] * (F[9][6] * D[6][7] + F[9][7] * D[7][7] +
F[9][8] * D[7][8] + F[9][10] * D[7][10] +
F[9][11] * D[7][11] + F[9][12] * D[7][12]) +
F[9][8] * (F[9][6] * D[6][8] + F[9][7] * D[7][8] +
F[9][8] * D[8][8] + F[9][10] * D[8][10] +
F[9][11] * D[8][11] + F[9][12] * D[8][12])) * Tsq +
(2 * F[9][10] * D[9][10] + 2 * F[9][11] * D[9][11] +
2 * F[9][12] * D[9][12] + 2 * F[9][6] * D[6][9] +
2 * F[9][7] * D[7][9] + 2 * F[9][8] * D[8][9]) * T + D[9][9];
P[9][10] = P[10][9] =
(F[9][10] * D[10][10] + F[9][11] * D[10][11] +
F[9][12] * D[10][12] + F[9][6] * D[6][10] +
F[9][7] * D[7][10] + F[9][8] * D[8][10]) * T + D[9][10];
P[9][11] = P[11][9] =
(F[9][10] * D[10][11] + F[9][11] * D[11][11] +
F[9][12] * D[11][12] + F[9][6] * D[6][11] +
F[9][7] * D[7][11] + F[9][8] * D[8][11]) * T + D[9][11];
P[9][12] = P[12][9] =
(F[9][10] * D[10][12] + F[9][11] * D[11][12] +
F[9][12] * D[12][12] + F[9][6] * D[6][12] +
F[9][7] * D[7][12] + F[9][8] * D[8][12]) * T + D[9][12];
P[10][10] = Q[6] * Tsq + D[10][10];
P[10][11] = P[11][10] = D[10][11];
P[10][12] = P[12][10] = D[10][12];
P[11][11] = Q[7] * Tsq + D[11][11];
P[11][12] = P[12][11] = D[11][12];
P[12][12] = Q[8] * Tsq + D[12][12];
} }
#endif
// ************* SerialUpdate ******************* // ************* SerialUpdate *******************
// Does the update step of the Kalman filter for the covariance and estimate // Does the update step of the Kalman filter for the covariance and estimate
@ -1381,7 +514,7 @@ void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW],
// ************************************************ // ************************************************
void SerialUpdate(float H[NUMV][NUMX], float R[NUMV], float Z[NUMV], 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) uint16_t SensorsUsed)
{ {
float HP[NUMX], HPHR, Error; float HP[NUMX], HPHR, Error;
@ -1393,11 +526,11 @@ void SerialUpdate(float H[NUMV][NUMX], float R[NUMV], float Z[NUMV],
for (j = 0; j < NUMX; j++) { // Find Hp = H*P for (j = 0; j < NUMX; j++) { // Find Hp = H*P
HP[j] = 0; HP[j] = 0;
for (k = 0; k < NUMX; k++) for (k = HrowMin[m] ; k <= HrowMax[m]; k++)
HP[j] += H[m][k] * P[k][j]; HP[j] += H[m][k] * P[k][j];
} }
HPHR = R[m]; // Find HPHR = H*P*H' + R HPHR = R[m]; // Find HPHR = H*P*H' + R
for (k = 0; k < NUMX; k++) for (k = HrowMin[m]; k <= HrowMax[m]; k++)
HPHR += HP[k] * H[m][k]; HPHR += HP[k] * H[m][k];
for (k = 0; k < NUMX; k++) for (k = 0; k < NUMX; k++)

View File

@ -63,8 +63,6 @@ uint8_t Data2;
uint8_t Data3; uint8_t Data3;
uint32_t Opt[3]; uint32_t Opt[3];
uint8_t offset = 0;
uint32_t aux;
//Download vars //Download vars
uint32_t downSizeOfLastPacket = 0; uint32_t downSizeOfLastPacket = 0;
uint32_t downPacketTotal = 0; uint32_t downPacketTotal = 0;
@ -227,6 +225,8 @@ void processComand(uint8_t *xReceive_Buffer) {
numberOfWords = SizeOfLastPacket; numberOfWords = SizeOfLastPacket;
} }
uint8_t result = 0; uint8_t result = 0;
uint32_t offset;
uint32_t aux;;
switch (currentProgrammingDestination) { switch (currentProgrammingDestination) {
case Self_flash: case Self_flash:
for (uint8_t x = 0; x < numberOfWords; ++x) { for (uint8_t x = 0; x < numberOfWords; ++x) {

View File

@ -103,7 +103,9 @@ int32_t ActuatorStart()
// Start main task // Start main task
xTaskCreate(actuatorTask, (signed char*)"Actuator", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); xTaskCreate(actuatorTask, (signed char*)"Actuator", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_ACTUATOR, taskHandle); PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_ACTUATOR, taskHandle);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_ACTUATOR); PIOS_WDG_RegisterFlag(PIOS_WDG_ACTUATOR);
#endif
return 0; return 0;
} }
@ -185,7 +187,9 @@ static void actuatorTask(__attribute__((unused)) void* parameters)
lastSysTime = xTaskGetTickCount(); lastSysTime = xTaskGetTickCount();
while (1) while (1)
{ {
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_ACTUATOR); PIOS_WDG_UpdateFlag(PIOS_WDG_ACTUATOR);
#endif
// Wait until the ActuatorDesired object is updated // Wait until the ActuatorDesired object is updated
uint8_t rc = xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS); uint8_t rc = xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS);

View File

@ -45,18 +45,19 @@
#include <openpilot.h> #include <openpilot.h>
#include "CoordinateConversions.h" #include <math.h>
#include "altholdsmoothed.h" #include <CoordinateConversions.h>
#include "attitudeactual.h" #include <altholdsmoothed.h>
#include "altitudeholdsettings.h" #include <attitudeactual.h>
#include "altitudeholddesired.h" // object that will be updated by the module #include <altitudeholdsettings.h>
#include "baroaltitude.h" #include <altitudeholddesired.h> // object that will be updated by the module
#include "positionactual.h" #include <baroaltitude.h>
#include "flightstatus.h" #include <positionactual.h>
#include "stabilizationdesired.h" #include <flightstatus.h>
#include "accels.h" #include <stabilizationdesired.h>
#include "taskinfo.h" #include <accels.h>
#include <taskinfo.h>
#include <pios_constants.h>
// Private constants // Private constants
#define MAX_QUEUE_SIZE 2 #define MAX_QUEUE_SIZE 2
#define STACK_SIZE_BYTES 1024 #define STACK_SIZE_BYTES 1024
@ -340,7 +341,8 @@ static void altitudeHoldTask(__attribute__((unused)) void *parameters)
// Verify that we are in altitude hold mode // Verify that we are in altitude hold mode
FlightStatusData flightStatus; FlightStatusData flightStatus;
FlightStatusGet(&flightStatus); FlightStatusGet(&flightStatus);
if(flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) { if(flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD ||
flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED) {
running = false; running = false;
} }

View File

@ -112,7 +112,7 @@ static int32_t fault_start(void)
} }
MODULE_INITCALL(fault_initialize, fault_start) MODULE_INITCALL(fault_initialize, fault_start)
static void fault_task(void *parameters) static void fault_task(__attribute__((unused))void *parameters)
{ {
switch (active_fault) { switch (active_fault) {
case FAULTSETTINGS_ACTIVATEFAULT_RUNAWAYTASK: case FAULTSETTINGS_ACTIVATEFAULT_RUNAWAYTASK:

View File

@ -191,9 +191,9 @@ static void FirmwareIAPCallback(UAVObjEvent* ev)
/* Note: Cant just wait timeout value, because first time is randomized */ /* Note: Cant just wait timeout value, because first time is randomized */
reset_count = 0; reset_count = 0;
lastResetSysTime = xTaskGetTickCount(); lastResetSysTime = xTaskGetTickCount();
UAVObjEvent * ev = pvPortMalloc(sizeof(UAVObjEvent)); UAVObjEvent *event = pvPortMalloc(sizeof(UAVObjEvent));
memset(ev,0,sizeof(UAVObjEvent)); memset(event, 0, sizeof(UAVObjEvent));
EventPeriodicCallbackCreate(ev, resetTask, 100); EventPeriodicCallbackCreate(event, resetTask, 100);
iap_state = IAP_STATE_RESETTING; iap_state = IAP_STATE_RESETTING;
} else { } else {
iap_state = IAP_STATE_READY; iap_state = IAP_STATE_READY;

View File

@ -377,7 +377,6 @@ static uint8_t updateFixedDesiredAttitude()
StabilizationDesiredData stabDesired; StabilizationDesiredData stabDesired;
AttitudeActualData attitudeActual; AttitudeActualData attitudeActual;
AccelsData accels; AccelsData accels;
FixedWingPathFollowerSettingsData fixedwingpathfollowerSettings;
StabilizationSettingsData stabSettings; StabilizationSettingsData stabSettings;
FixedWingPathFollowerStatusData fixedwingpathfollowerStatus; FixedWingPathFollowerStatusData fixedwingpathfollowerStatus;
AirspeedActualData airspeedActual; AirspeedActualData airspeedActual;
@ -397,8 +396,6 @@ static uint8_t updateFixedDesiredAttitude()
float bearingError; float bearingError;
float bearingCommand; float bearingCommand;
FixedWingPathFollowerSettingsGet(&fixedwingpathfollowerSettings);
FixedWingPathFollowerStatusGet(&fixedwingpathfollowerStatus); FixedWingPathFollowerStatusGet(&fixedwingpathfollowerStatus);
VelocityActualGet(&velocityActual); VelocityActualGet(&velocityActual);

View File

@ -51,7 +51,8 @@
#include "stabilizationdesired.h" #include "stabilizationdesired.h"
#include "receiveractivity.h" #include "receiveractivity.h"
#include "systemsettings.h" #include "systemsettings.h"
#include "taskinfo.h" #include <altitudeholdsettings.h>
#include <taskinfo.h>
#if defined(PIOS_INCLUDE_USB_RCTX) #if defined(PIOS_INCLUDE_USB_RCTX)
#include "pios_usb_rctx.h" #include "pios_usb_rctx.h"
@ -137,7 +138,9 @@ int32_t ManualControlStart()
// Start main task // Start main task
xTaskCreate(manualControlTask, (signed char *) "ManualControl", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle); xTaskCreate(manualControlTask, (signed char *) "ManualControl", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_MANUALCONTROL, taskHandle); PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_MANUALCONTROL, taskHandle);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL); PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL);
#endif
return 0; return 0;
} }
@ -202,12 +205,16 @@ static void manualControlTask(__attribute__((unused)) void *parameters)
// Main task loop // Main task loop
lastSysTime = xTaskGetTickCount(); lastSysTime = xTaskGetTickCount();
float scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM] = {0};
while (1) { while (1) {
float scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM];
// Wait until next update // Wait until next update
vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD_MS / portTICK_RATE_MS); vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD_MS / portTICK_RATE_MS);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_MANUAL); PIOS_WDG_UpdateFlag(PIOS_WDG_MANUAL);
#endif
// Read settings // Read settings
ManualControlSettingsGet(&settings); ManualControlSettingsGet(&settings);
@ -797,48 +804,59 @@ static void updateLandDesired(__attribute__((unused)) ManualControlCommandData *
*/ */
static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed) static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed)
{ {
const float DEADBAND_HIGH = 0.55f; const float DEADBAND = 0.10f;
const float DEADBAND_LOW = 0.45f; 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; static bool zeroed = false;
portTickType thisSysTime; portTickType thisSysTime;
float dT; float dT;
AltitudeHoldDesiredData altitudeHoldDesired;
AltitudeHoldDesiredGet(&altitudeHoldDesired); AltitudeHoldDesiredData altitudeHoldDesiredData;
AltitudeHoldDesiredGet(&altitudeHoldDesiredData);
AltitudeHoldSettingsThrottleExpGet(&throttleExp);
AltitudeHoldSettingsThrottleRateGet(&throttleRate);
StabilizationSettingsData stabSettings; StabilizationSettingsData stabSettings;
StabilizationSettingsGet(&stabSettings); StabilizationSettingsGet(&stabSettings);
thisSysTime = xTaskGetTickCount(); thisSysTime = xTaskGetTickCount();
dT = ((thisSysTime == lastSysTime)? 0.001f : (thisSysTime - lastSysTime) * portTICK_RATE_MS * 0.001f); dT = ((thisSysTime == lastSysTimeAH)? 0.001f : (thisSysTime - lastSysTimeAH) * portTICK_RATE_MS * 0.001f);
lastSysTime = thisSysTime; lastSysTimeAH = thisSysTime;
altitudeHoldDesired.Roll = cmd->Roll * stabSettings.RollMax; altitudeHoldDesiredData.Roll = cmd->Roll * stabSettings.RollMax;
altitudeHoldDesired.Pitch = cmd->Pitch * stabSettings.PitchMax; altitudeHoldDesiredData.Pitch = cmd->Pitch * stabSettings.PitchMax;
altitudeHoldDesired.Yaw = cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW]; altitudeHoldDesiredData.Yaw = cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW];
float currentDown; float currentDown;
PositionActualDownGet(&currentDown); PositionActualDownGet(&currentDown);
if(changed) { if(changed) {
// After not being in this mode for a while init at current height // After not being in this mode for a while init at current height
altitudeHoldDesired.Altitude = 0; altitudeHoldDesiredData.Altitude = 0;
zeroed = false; zeroed = false;
} else if (cmd->Throttle > DEADBAND_HIGH && zeroed) { } 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∙(256k)) / 256
altitudeHoldDesiredData.Altitude += (throttleExp * powf((cmd->Throttle - DEADBAND_HIGH) / (DEADBAND_LOW), 3) + (256 - throttleExp)) / 256 * throttleRate * dT;
} else if (cmd->Throttle < DEADBAND_LOW && zeroed) { } 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) { } else if (cmd->Throttle >= DEADBAND_LOW && cmd->Throttle <= DEADBAND_HIGH) {
// Require the stick to enter the dead band before they can move height // Require the stick to enter the dead band before they can move height
zeroed = true; zeroed = true;
} }
AltitudeHoldDesiredSet(&altitudeHoldDesired); AltitudeHoldDesiredSet(&altitudeHoldDesiredData);
} }
#else #else
// TODO: These functions should never be accessible on CC. Any configuration that // 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 // in flight
static void updatePathDesired(__attribute__((unused)) ManualControlCommandData * cmd, static void updatePathDesired(__attribute__((unused)) ManualControlCommandData * cmd,
__attribute__((unused)) bool changed, __attribute__((unused)) bool changed,
@ -903,6 +921,7 @@ static bool okToArm(void)
{ {
// read alarms // read alarms
SystemAlarmsData alarms; SystemAlarmsData alarms;
SystemAlarmsGet(&alarms); SystemAlarmsGet(&alarms);
// Check each alarm // Check each alarm
@ -911,11 +930,23 @@ static bool okToArm(void)
if (i == SYSTEMALARMS_ALARM_GPS || i == SYSTEMALARMS_ALARM_TELEMETRY) { if (i == SYSTEMALARMS_ALARM_GPS || i == SYSTEMALARMS_ALARM_TELEMETRY) {
continue; continue;
} }
return false; 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; return true;
default:
return false;
}
} }
/** /**
* @brief Determine if the aircraft is forced to disarm by an explicit alarm * @brief Determine if the aircraft is forced to disarm by an explicit alarm

View File

@ -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) void write_char16(char ch, unsigned int x, unsigned int y, int font)
{ {
unsigned int yy, addr_temp, row, row_temp, xshift; 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; struct FontEntry font_info;
//char lookup = 0; //char lookup = 0;
fetch_font_info(0, font, &font_info, NULL); 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; addr = addr_temp;
for (yy = y; yy < y + font_info.height; yy++) { for (yy = y; yy < y + font_info.height; yy++) {
if (font == 3) { if (font == 3) {
level_bits = font_frame12x18[row]; levels = font_frame12x18[row];
//if(!(flags & FONT_INVERT)) // data is normally inverted //if(!(flags & FONT_INVERT)) // data is normally inverted
level_bits = ~level_bits; levels = ~levels;
or_mask = font_mask12x18[row] << xshift; or_mask = font_mask12x18[row] << xshift;
and_mask = (font_mask12x18[row] & level_bits) << xshift; and_mask = (font_mask12x18[row] & levels) << xshift;
} else { } else {
level_bits = font_frame8x10[row]; levels = font_frame8x10[row];
//if(!(flags & FONT_INVERT)) // data is normally inverted //if(!(flags & FONT_INVERT)) // data is normally inverted
level_bits = ~level_bits; levels = ~levels;
or_mask = font_mask8x10[row] << xshift; 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); write_word_misaligned_OR(draw_buffer_level, or_mask, addr, wbit);
// If we're not bold write the AND mask. // 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) void write_char(char ch, unsigned int x, unsigned int y, int flags, int font)
{ {
unsigned int yy, addr_temp, row, row_temp, xshift; 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; struct FontEntry font_info;
char lookup = 0; char lookup = 0;
fetch_font_info(ch, font, &font_info, &lookup); 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; row = row_temp;
addr = addr_temp; addr = addr_temp;
for (yy = y; yy < y + font_info.height; yy++) { 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)) { if (!(flags & FONT_INVERT)) {
// data is normally inverted // data is normally inverted
level_bits = ~level_bits; levels = ~levels;
} }
or_mask = font_info.data[row] << xshift; 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); write_word_misaligned_OR(draw_buffer_level, or_mask, addr, wbit);
// If we're not bold write the AND mask. // If we're not bold write the AND mask.
//if(!(flags & FONT_BOLD)) //if(!(flags & FONT_BOLD))

View File

@ -215,29 +215,29 @@ void updatePathDesired(__attribute__((unused)) UAVObjEvent * ev) {
// use local variables, dont use stack since this is huge and a callback, // use local variables, dont use stack since this is huge and a callback,
// dont use the globals because we cant use mutexes here // dont use the globals because we cant use mutexes here
static WaypointActiveData waypointActive; static WaypointActiveData waypointActiveData;
static PathActionData pathAction; static PathActionData pathActionData;
static WaypointData waypoint; static WaypointData waypointData;
static PathDesiredData pathDesired; static PathDesiredData pathDesired;
// find out current waypoint // find out current waypoint
WaypointActiveGet(&waypointActive); WaypointActiveGet(&waypointActiveData);
WaypointInstGet(waypointActive.Index,&waypoint); WaypointInstGet(waypointActiveData.Index,&waypointData);
PathActionInstGet(waypoint.Action, &pathAction); PathActionInstGet(waypointData.Action, &pathActionData);
pathDesired.End[PATHDESIRED_END_NORTH] = waypoint.Position[WAYPOINT_POSITION_NORTH]; pathDesired.End[PATHDESIRED_END_NORTH] = waypointData.Position[WAYPOINT_POSITION_NORTH];
pathDesired.End[PATHDESIRED_END_EAST] = waypoint.Position[WAYPOINT_POSITION_EAST]; pathDesired.End[PATHDESIRED_END_EAST] = waypointData.Position[WAYPOINT_POSITION_EAST];
pathDesired.End[PATHDESIRED_END_DOWN] = waypoint.Position[WAYPOINT_POSITION_DOWN]; pathDesired.End[PATHDESIRED_END_DOWN] = waypointData.Position[WAYPOINT_POSITION_DOWN];
pathDesired.EndingVelocity = waypoint.Velocity; pathDesired.EndingVelocity = waypointData.Velocity;
pathDesired.Mode = pathAction.Mode; pathDesired.Mode = pathActionData.Mode;
pathDesired.ModeParameters[0] = pathAction.ModeParameters[0]; pathDesired.ModeParameters[0] = pathActionData.ModeParameters[0];
pathDesired.ModeParameters[1] = pathAction.ModeParameters[1]; pathDesired.ModeParameters[1] = pathActionData.ModeParameters[1];
pathDesired.ModeParameters[2] = pathAction.ModeParameters[2]; pathDesired.ModeParameters[2] = pathActionData.ModeParameters[2];
pathDesired.ModeParameters[3] = pathAction.ModeParameters[3]; pathDesired.ModeParameters[3] = pathActionData.ModeParameters[3];
pathDesired.UID = waypointActive.Index; pathDesired.UID = waypointActiveData.Index;
if(waypointActive.Index == 0) { if(waypointActiveData.Index == 0) {
PositionActualData positionActual; PositionActualData positionActual;
PositionActualGet(&positionActual); PositionActualGet(&positionActual);
// First waypoint has itself as start point (used to be home position but that proved dangerous when looping) // 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; pathDesired.StartingVelocity = waypointPrev.Velocity;
} }
PathDesiredSet(&pathDesired); PathDesiredSet(&pathDesired);
} }
// helper function to go to a specific waypoint // helper function to go to a specific waypoint

View File

@ -487,7 +487,7 @@ static void magOffsetEstimation(MagnetometerData *mag)
const float Rz = homeLocation.Be[2]; const float Rz = homeLocation.Be[2];
const float rate = cal.MagBiasNullingRate; const float rate = cal.MagBiasNullingRate;
float R[3][3]; float Rot[3][3];
float B_e[3]; float B_e[3];
float xy[2]; float xy[2];
float delta[3]; float delta[3];
@ -496,9 +496,9 @@ static void magOffsetEstimation(MagnetometerData *mag)
Quaternion2R(&attitude.q1, R); Quaternion2R(&attitude.q1, R);
// Rotate the mag into the NED frame // 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[0] = Rot[0][0] * mag->x + Rot[1][0] * mag->y + Rot[2][0] * mag->z;
B_e[1] = R[0][1] * mag->x + R[1][1] * mag->y + R[2][1] * mag->z; B_e[1] = Rot[0][1] * mag->x + Rot[1][1] * mag->y + Rot[2][1] * mag->z;
B_e[2] = R[0][2] * mag->x + R[1][2] * mag->y + R[2][2] * 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 cy = cosf(DEG2RAD(attitude.Yaw));
float sy = sinf(DEG2RAD(attitude.Yaw)); float sy = sinf(DEG2RAD(attitude.Yaw));

View File

@ -113,7 +113,9 @@ int32_t StabilizationStart()
// Start main task // Start main task
xTaskCreate(stabilizationTask, (signed char*)"Stabilization", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); xTaskCreate(stabilizationTask, (signed char*)"Stabilization", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_STABILIZATION, taskHandle); PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_STABILIZATION, taskHandle);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_STABILIZATION); PIOS_WDG_RegisterFlag(PIOS_WDG_STABILIZATION);
#endif
return 0; return 0;
} }
@ -161,7 +163,9 @@ static void stabilizationTask(__attribute__((unused)) void* parameters)
while(1) { while(1) {
float dT; float dT;
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION); PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION);
#endif
// Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe // 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 ) if ( xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE )

View File

@ -566,7 +566,6 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
StabilizationDesiredData stabDesired; StabilizationDesiredData stabDesired;
AttitudeActualData attitudeActual; AttitudeActualData attitudeActual;
NedAccelData nedAccel; NedAccelData nedAccel;
VtolPathFollowerSettingsData vtolpathfollowerSettings;
StabilizationSettingsData stabSettings; StabilizationSettingsData stabSettings;
SystemSettingsData systemSettings; SystemSettingsData systemSettings;
@ -580,8 +579,6 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
float downCommand; float downCommand;
SystemSettingsGet(&systemSettings); SystemSettingsGet(&systemSettings);
VtolPathFollowerSettingsGet(&vtolpathfollowerSettings);
VelocityActualGet(&velocityActual); VelocityActualGet(&velocityActual);
VelocityDesiredGet(&velocityDesired); VelocityDesiredGet(&velocityDesired);
StabilizationDesiredGet(&stabDesired); StabilizationDesiredGet(&stabDesired);

View File

@ -70,13 +70,13 @@ static struct adxl345_dev * PIOS_ADXL345_alloc(void)
* @brief Validate the handle to the spi device * @brief Validate the handle to the spi device
* @returns 0 for valid device or -1 otherwise * @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; return -1;
if (dev->magic != PIOS_ADXL345_DEV_MAGIC) if (vdev->magic != PIOS_ADXL345_DEV_MAGIC)
return -2; return -2;
if (dev->spi_id == 0) if (vdev->spi_id == 0)
return -3; return -3;
return 0; return 0;
} }

View File

@ -86,13 +86,13 @@ static struct bma180_dev * PIOS_BMA180_alloc(void)
* @brief Validate the handle to the spi device * @brief Validate the handle to the spi device
* @returns 0 for valid device or -1 otherwise * @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; return -1;
if (dev->magic != PIOS_BMA180_DEV_MAGIC) if (vdev->magic != PIOS_BMA180_DEV_MAGIC)
return -2; return -2;
if (dev->spi_id == 0) if (vdev->spi_id == 0)
return -3; return -3;
return 0; return 0;
} }
@ -128,8 +128,9 @@ int32_t PIOS_BMA180_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_
*/ */
int32_t PIOS_BMA180_ClaimBus() int32_t PIOS_BMA180_ClaimBus()
{ {
if(PIOS_BMA180_Validate(dev) != 0) if (PIOS_BMA180_Validate(dev) != 0) {
return -1; return -1;
}
if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) { if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) {
return -1; return -1;
@ -141,15 +142,18 @@ 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 * @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) if (PIOS_BMA180_Validate(dev) != 0) {
return -1; return -1;
}
if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) { if (PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) {
return -1; return -1;
} }
@ -162,13 +166,29 @@ int32_t PIOS_BMA180_ClaimBusISR()
* @return 0 if successful * @return 0 if successful
*/ */
int32_t PIOS_BMA180_ReleaseBus() 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) if(PIOS_BMA180_Validate(dev) != 0)
return -1; 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; int32_t bma180_irqs = 0;
bool PIOS_BMA180_IRQHandler(void) 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}; 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]; uint8_t pios_bma180_dmabuf[8];
bma180_irqs++;
// If we can't get the bus then just move on for efficiency // If we can't get the bus then just move on for efficiency
if(PIOS_BMA180_ClaimBusISR() != 0) { if (PIOS_BMA180_ClaimBusISR(&woken) != 0) {
return false; // Something else is using bus, miss this data 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, 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; struct pios_bma180_data data;
// Don't release bus till data has copied // Don't release bus till data has copied
PIOS_BMA180_ReleaseBus(); PIOS_BMA180_ReleaseBusISR(&woken);
// Must not return before releasing bus // Must not return before releasing bus
if(fifoBuf_getFree(&dev->fifo) < sizeof(data)) if (fifoBuf_getFree(&dev->fifo) < sizeof(data)) {
return false; return woken;
}
// Bottom two bits indicate new data and are constant zeros. Don't right // Bottom two bits indicate new data and are constant zeros. Don't right
// shift because it drops sign bit // shift because it drops sign bit
@ -471,7 +494,7 @@ bool PIOS_BMA180_IRQHandler(void)
fifoBuf_putData(&dev->fifo, (uint8_t *) &data, sizeof(data)); fifoBuf_putData(&dev->fifo, (uint8_t *) &data, sizeof(data));
return false; return woken;
} }
#endif /* PIOS_INCLUDE_BMA180 */ #endif /* PIOS_INCLUDE_BMA180 */

View File

@ -29,13 +29,12 @@
#ifdef PIOS_INCLUDE_FLASH #ifdef PIOS_INCLUDE_FLASH
#include "openpilot.h" #include <stdbool.h>
#include <openpilot.h>
#include <pios_math.h>
#include "pios_flashfs_logfs_priv.h" #include "pios_flashfs_logfs_priv.h"
#include <stdbool.h>
/* /*
* Filesystem state data tracked in RAM * Filesystem state data tracked in RAM
*/ */

View File

@ -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 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_SetReg(uint8_t address, uint8_t buffer);
static int32_t PIOS_L3GD20_GetReg(uint8_t address); 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_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_ReleaseBus();
static int32_t PIOS_L3GD20_ReleaseBusISR(bool *woken);
volatile bool l3gd20_configured = false; 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 * @brief Validate the handle to the spi device
* @returns 0 for valid device or -1 otherwise * @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; return -1;
if (dev->magic != PIOS_L3GD20_DEV_MAGIC) if (vdev->magic != PIOS_L3GD20_DEV_MAGIC)
return -2; return -2;
if (dev->spi_id == 0) if (vdev->spi_id == 0)
return -3; return -3;
return 0; return 0;
} }
@ -191,16 +193,18 @@ static int32_t PIOS_L3GD20_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
* @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 * @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; return -1;
}
if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) if(PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) {
return -2; 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; return 0;
} }
@ -211,14 +215,28 @@ static int32_t PIOS_L3GD20_ClaimBusIsr()
*/ */
int32_t PIOS_L3GD20_ReleaseBus() int32_t PIOS_L3GD20_ReleaseBus()
{ {
if(PIOS_L3GD20_Validate(dev) != 0) if(PIOS_L3GD20_Validate(dev) != 0) {
return -1; 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_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 * @brief Read a register from L3GD20
* @returns The register value or -1 if failure to get bus * @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; 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 * @brief Writes one byte to the L3GD20
* \param[in] reg Register address * \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) bool PIOS_L3GD20_IRQHandler(void)
{ {
l3gd20_irq++; bool woken = false;
struct pios_l3gd20_data data; 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 buf[7] = {PIOS_L3GD20_GYRO_X_OUT_LSB | 0x80 | 0x40, 0, 0, 0, 0, 0, 0};
uint8_t rec[7]; uint8_t rec[7];
/* This code duplicates ReadGyros above but uses ClaimBusIsr */ l3gd20_irq++;
if(PIOS_L3GD20_ClaimBusIsr() != 0)
return false;
if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) { /* This code duplicates ReadGyros above but uses ClaimBusIsr */
PIOS_L3GD20_ReleaseBus(); if (PIOS_L3GD20_ClaimBusISR(&woken) != 0) {
return false; 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); 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; signed portBASE_TYPE higherPriorityTaskWoken;
xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken); xQueueSendToBackFromISR(dev->queue, (void *) &data, &higherPriorityTaskWoken);
return xHigherPriorityTaskWoken == pdTRUE; return (woken || higherPriorityTaskWoken == pdTRUE);
} }
#endif /* PIOS_INCLUDE_L3GD20 */ #endif /* PIOS_INCLUDE_L3GD20 */

View File

@ -91,13 +91,13 @@ static struct mpu6000_dev * PIOS_MPU6000_alloc(void)
* @brief Validate the handle to the spi device * @brief Validate the handle to the spi device
* @returns 0 for valid device or -1 otherwise * @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; return -1;
if (dev->magic != PIOS_MPU6000_DEV_MAGIC) if (vdev->magic != PIOS_MPU6000_DEV_MAGIC)
return -2; return -2;
if (dev->spi_id == 0) if (vdev->spi_id == 0)
return -3; return -3;
return 0; return 0;
} }
@ -197,7 +197,12 @@ int32_t PIOS_MPU6000_ConfigureRanges(
{ {
if(dev == NULL) if(dev == NULL)
return -1; 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); PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_256);
// update filter settings // update filter settings
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_DLPF_CFG_REG, filterSetting) != 0); while (PIOS_MPU6000_SetReg(PIOS_MPU6000_DLPF_CFG_REG, filterSetting) != 0);
@ -225,17 +230,31 @@ int32_t PIOS_MPU6000_ConfigureRanges(
/** /**
* @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
* @return 0 if successful, -1 for invalid device, -2 if unable to claim bus * @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; return -1;
if(fromIsr){ }
if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) {
return -2; return -2;
} else { }
if(PIOS_SPI_ClaimBus(dev->spi_id) != 0) 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; return -2;
} }
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0); PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
@ -245,19 +264,29 @@ static int32_t PIOS_MPU6000_ClaimBus(bool fromIsr)
/** /**
* @brief Release the SPI bus for the accel communications and end the transaction * @brief Release the SPI bus for the accel communications and end the transaction
* @return 0 if successful * @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; return -1;
}
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 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); 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; uint8_t data;
if(PIOS_MPU6000_ClaimBus(false) != 0) if(PIOS_MPU6000_ClaimBus() != 0) {
return -1; return -1;
}
PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte
data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response
PIOS_MPU6000_ReleaseBus(false); PIOS_MPU6000_ReleaseBus();
return data; 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) 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; return -1;
}
if (PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg) != 0) { if (PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg) != 0) {
PIOS_MPU6000_ReleaseBus(false); PIOS_MPU6000_ReleaseBus();
return -2; return -2;
} }
if (PIOS_SPI_TransferByte(dev->spi_id, data) != 0) { if (PIOS_SPI_TransferByte(dev->spi_id, data) != 0) {
PIOS_MPU6000_ReleaseBus(false); PIOS_MPU6000_ReleaseBus();
return -3; return -3;
} }
PIOS_MPU6000_ReleaseBus(false); PIOS_MPU6000_ReleaseBus();
return 0; 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 buf[7] = {PIOS_MPU6000_GYRO_X_OUT_MSB | 0x80, 0, 0, 0, 0, 0, 0};
uint8_t rec[7]; uint8_t rec[7];
if(PIOS_MPU6000_ClaimBus(false) != 0) if (PIOS_MPU6000_ClaimBus() != 0) {
return -1; 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; return -2;
}
PIOS_MPU6000_ReleaseBus(false); PIOS_MPU6000_ReleaseBus();
data->gyro_x = rec[1] << 8 | rec[2]; data->gyro_x = rec[1] << 8 | rec[2];
data->gyro_y = rec[3] << 8 | rec[4]; data->gyro_y = rec[3] << 8 | rec[4];
@ -407,31 +440,34 @@ int32_t PIOS_MPU6000_Test(void)
} }
/** /**
* @brief Run self-test operation. * @brief Obtains the number of bytes in the FIFO. Call from ISR only.
* \return 0 if test succeeded * @return the number of bytes in the FIFO
* \return non-zero value if test succeeded * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* @param fromIsr[in] Tells if the function is being called from a ISR or not * 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_send_buf[3] = {PIOS_MPU6000_FIFO_CNT_MSB | 0x80, 0, 0};
uint8_t mpu6000_rec_buf[3]; uint8_t mpu6000_rec_buf[3];
if(PIOS_MPU6000_ClaimBus(fromIsr) != 0) if(PIOS_MPU6000_ClaimBusISR(woken) != 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);
return -1; 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]; 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; uint32_t mpu6000_irq = 0;
int32_t mpu6000_count; int32_t mpu6000_count;
@ -446,46 +482,50 @@ uint32_t mpu6000_transfer_size;
bool PIOS_MPU6000_IRQHandler(void) bool PIOS_MPU6000_IRQHandler(void)
{ {
bool woken = false;
static uint32_t timeval; static uint32_t timeval;
mpu6000_interval_us = PIOS_DELAY_DiffuS(timeval); mpu6000_interval_us = PIOS_DELAY_DiffuS(timeval);
timeval = PIOS_DELAY_GetRaw(); timeval = PIOS_DELAY_GetRaw();
if (!mpu6000_configured) if (!mpu6000_configured) {
return false; return false;
}
mpu6000_count = PIOS_MPU6000_FifoDepth(true); mpu6000_count = PIOS_MPU6000_FifoDepthISR(&woken);
if (mpu6000_count < (int32_t)sizeof(struct pios_mpu6000_data)) if (mpu6000_count < (int32_t)sizeof(struct pios_mpu6000_data)) {
return false; return woken;
}
if (PIOS_MPU6000_ClaimBus(true) != 0) if (PIOS_MPU6000_ClaimBusISR(&woken) != 0) {
return false; 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_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) ]; 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) { 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++; mpu6000_fails++;
return false; return woken;
} }
PIOS_MPU6000_ReleaseBus(true); PIOS_MPU6000_ReleaseBusISR(&woken);
static struct pios_mpu6000_data data; static struct pios_mpu6000_data data;
// In the case where extras samples backed up grabbed an extra // In the case where extras samples backed up grabbed an extra
if (mpu6000_count >= (int32_t)(sizeof(data) * 2)) { if (mpu6000_count >= (int32_t)(sizeof(data) * 2)) {
mpu6000_fifo_backup++; mpu6000_fifo_backup++;
if (PIOS_MPU6000_ClaimBus(true) != 0) if (PIOS_MPU6000_ClaimBusISR(&woken) != 0)
return false; return woken;
if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { 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++; 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 // 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]; data.temperature = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2];
#endif #endif
portBASE_TYPE xHigherPriorityTaskWoken; signed portBASE_TYPE higherPriorityTaskWoken;
xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken); xQueueSendToBackFromISR(dev->queue, (void *) &data, &higherPriorityTaskWoken);
mpu6000_irq++; mpu6000_irq++;
mpu6000_time_us = PIOS_DELAY_DiffuS(timeval); mpu6000_time_us = PIOS_DELAY_DiffuS(timeval);
return xHigherPriorityTaskWoken == pdTRUE; return (woken || higherPriorityTaskWoken == pdTRUE);
} }
#endif /* PIOS_INCLUDE_MPU6000 */ #endif /* PIOS_INCLUDE_MPU6000 */

View File

@ -2017,6 +2017,7 @@ static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *radio_d
#endif #endif
#if defined(PIOS_INCLUDE_RFM22B_RCVR) #if defined(PIOS_INCLUDE_RFM22B_RCVR)
ppm_output = true; ppm_output = true;
radio_dev->ppm_fresh = true;
for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) { for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) {
radio_dev->ppm_channel[i] = ppmp->channels[i]; radio_dev->ppm_channel[i] = ppmp->channels[i];
} }

View File

@ -102,7 +102,7 @@ static void PIOS_RFM22B_RCVR_Supervisor(uint32_t rcvr_id) {
} }
// RTC runs at 625Hz. // 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; return;
} }
rfm22b_dev->ppm_supv_timer = 0; 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? // Have we received fresh values since the last update?
if (!rfm22b_dev->ppm_fresh) { if (!rfm22b_dev->ppm_fresh) {
for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) { 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; rfm22b_dev->ppm_fresh = false;

View File

@ -33,8 +33,6 @@
#include <pios.h> #include <pios.h>
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 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); extern void PIOS_RCVR_IRQ_Handler(uint32_t rcvr_id);

View File

@ -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_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_Busy(uint32_t spi_id);
extern int32_t PIOS_SPI_ClaimBus(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_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_IRQ_Handler(uint32_t spi_id);
extern void PIOS_SPI_SetPrescalar(uint32_t spi_id, uint32_t prescalar); extern void PIOS_SPI_SetPrescalar(uint32_t spi_id, uint32_t prescalar);

View File

@ -37,6 +37,7 @@
struct pios_usb_cfg { struct pios_usb_cfg {
struct stm32_irq irq; struct stm32_irq irq;
struct stm32_gpio vsense; struct stm32_gpio vsense;
bool vsense_active_low;
}; };
extern int32_t PIOS_USB_Init(uint32_t * usb_id, const struct pios_usb_cfg * cfg); extern int32_t PIOS_USB_Init(uint32_t * usb_id, const struct pios_usb_cfg * cfg);

View File

@ -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); 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] = { [I2C_STATE_FSM_FAULT] = {
.entry_fn = go_fsm_fault, .entry_fn = go_fsm_fault,
.next_state = { .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 * guarantee that the entry function never depends on the previous
* state. This way, it cannot ever know what the previous state was. * 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]; i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[event];
/* Call the entry function (if any) for the next state. */ /* 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) static void i2c_adapter_process_auto(struct pios_i2c_adapter *i2c_adapter)
{ {
PIOS_IRQ_Disable(); 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]) { 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]; 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. * in spinning on this bit in the ISR forever.
*/ */
#define I2C_CR1_STOP_REQUESTED 0x0200 #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--) guard && (i2c_adapter->cfg->regs->CR1 & I2C_CR1_STOP_REQUESTED); guard--)
continue; continue;
if (!guard) { if (!guard) {

View File

@ -50,7 +50,7 @@ const struct pios_rcvr_driver pios_ppm_rcvr_driver = {
#define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds #define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds
/* Local Variables */ /* Local Variables */
static TIM_ICInitTypeDef TIM_ICInitStructure; //static TIM_ICInitTypeDef TIM_ICInitStructure;
static void PIOS_PPM_Supervisor(uint32_t ppm_id); 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; return -1;
} }
TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init;
/* Configure the channels to be in capture/compare mode */ /* Configure the channels to be in capture/compare mode */
for (uint8_t i = 0; i < cfg->num_channels; i++) { for (uint8_t i = 0; i < cfg->num_channels; i++) {
const struct pios_tim_channel * chan = &cfg->channels[i]; const struct pios_tim_channel * chan = &cfg->channels[i];
/* Configure timer for input capture */ /* Configure timer for input capture */
TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init;
TIM_ICInitStructure.TIM_Channel = chan->timer_chan; TIM_ICInitStructure.TIM_Channel = chan->timer_chan;
TIM_ICInit(chan->timer, &TIM_ICInitStructure); 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; ppm_dev->supv_timer = 0;
if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) { if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) {
PIOS_DEBUG_Assert(0); PIOS_DEBUG_Assert(0);

View File

@ -265,22 +265,33 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id)
/** /**
* Claim the SPI bus semaphore from an ISR. Has no timeout. * Claim the SPI bus semaphore from an ISR. Has no timeout.
* \param[in] spi SPI number (0 or 1) * \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 0 if no error
* \return -1 if timeout before claiming semaphore * \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) #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); bool valid = PIOS_SPI_validate(spi_dev);
PIOS_Assert(valid) PIOS_Assert(valid)
if (xSemaphoreTakeFromISR(spi_dev->busy, NULL) != pdTRUE){ if (xSemaphoreTakeFromISR(spi_dev->busy, &higherPriorityTaskWoken) != pdTRUE){
return -1; return -1;
} }
#endif if (woken) {
*woken = *woken || (higherPriorityTaskWoken == pdTRUE);
}
return 0; 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(); PIOS_IRQ_Disable();
spi_dev->busy = 0; spi_dev->busy = 0;
PIOS_IRQ_Enable(); PIOS_IRQ_Enable();
#endif #endif
return 0; 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 * Release the SPI bus semaphore from ISR. Calling the SPI functions does not require this
* \param[in] spi SPI number (0 or 1) * \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 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) #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); bool valid = PIOS_SPI_validate(spi_dev);
PIOS_Assert(valid) PIOS_Assert(valid)
xSemaphoreGiveFromISR(spi_dev->busy, NULL); xSemaphoreGiveFromISR(spi_dev->busy, &higherPriorityTaskWoken);
#else if (woken) {
struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; *woken = *woken || (higherPriorityTaskWoken == pdTRUE);
PIOS_IRQ_Disable(); }
spi_dev->busy = 0;
PIOS_IRQ_Enable();
#endif
return 0; return 0;
#else
if (woken) {
*woken = false;
}
return PIOS_SPI_ReleaseBus(spi_id);
#endif
} }

View File

@ -215,7 +215,7 @@ bool PIOS_USB_CableConnected(__attribute__((unused)) uint8_t id)
if (PIOS_USB_validate(usb_dev) != 0) if (PIOS_USB_validate(usb_dev) != 0)
return false; 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;
} }
/** /**

View File

@ -393,7 +393,7 @@ static void SetSysClock(void)
} }
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */ /* 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 */ /* Select the main PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));

View File

@ -1330,7 +1330,6 @@ USB_OTG_STS USB_OTG_CoreInitDev (USB_OTG_CORE_HANDLE *pdev)
} }
for (i = 0; i < pdev->cfg.dev_endpoints; i++) 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); depctl.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[i]->DOEPCTL);
if (depctl.b.epena) if (depctl.b.epena)
{ {

View File

@ -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_MIN_CHANNEL_PULSE_US 750 // microseconds
#define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // 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); static void PIOS_PPM_Supervisor(uint32_t ppm_id);
enum pios_ppm_dev_magic { 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; return -1;
} }
TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init;
/* Configure the channels to be in capture/compare mode */ /* Configure the channels to be in capture/compare mode */
for (uint8_t i = 0; i < cfg->num_channels; i++) { for (uint8_t i = 0; i < cfg->num_channels; i++) {
const struct pios_tim_channel * chan = &cfg->channels[i]; const struct pios_tim_channel * chan = &cfg->channels[i];
/* Configure timer for input capture */ /* Configure timer for input capture */
TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init;
TIM_ICInitStructure.TIM_Channel = chan->timer_chan; TIM_ICInitStructure.TIM_Channel = chan->timer_chan;
TIM_ICInit(chan->timer, &TIM_ICInitStructure); 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)) { if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) {
PIOS_DEBUG_Assert(0); PIOS_DEBUG_Assert(0);
} }

View File

@ -257,6 +257,18 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id)
if (xSemaphoreTake(spi_dev->busy, 0xffff) != pdTRUE) if (xSemaphoreTake(spi_dev->busy, 0xffff) != pdTRUE)
return -1; 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 #endif
return 0; return 0;
} }
@ -264,24 +276,34 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id)
/** /**
* Claim the SPI bus semaphore from an ISR. Has no timeout. * Claim the SPI bus semaphore from an ISR. Has no timeout.
* \param[in] spi SPI number (0 or 1) * \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 0 if no error
* \return -1 if timeout before claiming semaphore * \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) #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); bool valid = PIOS_SPI_validate(spi_dev);
PIOS_Assert(valid) PIOS_Assert(valid)
if (xSemaphoreTakeFromISR(spi_dev->busy, NULL) != pdTRUE){ if (xSemaphoreTakeFromISR(spi_dev->busy, &higherPriorityTaskWoken) != pdTRUE){
return -1; return -1;
} }
#endif if (woken) {
return 0; *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 * Release the SPI bus semaphore. Calling the SPI functions does not require this
@ -297,6 +319,11 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id)
PIOS_Assert(valid) PIOS_Assert(valid)
xSemaphoreGive(spi_dev->busy); 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 #endif
return 0; return 0;
} }
@ -304,20 +331,32 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id)
/** /**
* Release the SPI bus semaphore from ISR. Calling the SPI functions does not require this * Release the SPI bus semaphore from ISR. Calling the SPI functions does not require this
* \param[in] spi SPI number (0 or 1) * \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 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) #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); bool valid = PIOS_SPI_validate(spi_dev);
PIOS_Assert(valid) PIOS_Assert(valid)
xSemaphoreGiveFromISR(spi_dev->busy, NULL); xSemaphoreGiveFromISR(spi_dev->busy, &higherPriorityTaskWoken);
#endif if (woken) {
return 0; *woken = *woken || (higherPriorityTaskWoken == pdTRUE);
} }
return 0;
#else
if (woken) {
*woken = false;
}
return PIOS_SPI_ReleaseBus(spi_id);
#endif
}
/** /**
* Controls the RC (Register Clock alias Chip Select) pin of a SPI port * Controls the RC (Register Clock alias Chip Select) pin of a SPI port

View File

@ -162,7 +162,7 @@ bool PIOS_USB_CheckAvailable(__attribute__((unused)) uint32_t id)
if(!PIOS_USB_validate(usb_dev)) if(!PIOS_USB_validate(usb_dev))
return false; 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;
return usb_found != 0 && transfer_possible ? 1 : 0; return usb_found != 0 && transfer_possible ? 1 : 0;
} }

View File

@ -1431,7 +1431,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg_cc = {
.GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_OD, .GPIO_Mode = GPIO_Mode_AF_OD,
}, },
} },
.vsense_active_low = false
}; };
static const struct pios_usb_cfg pios_usb_main_cfg_cc3d = { 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_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_OD, .GPIO_Mode = GPIO_Mode_AF_OD,
}, },
} },
.vsense_active_low = false
}; };
#include "pios_usb_board_data_priv.h" #include "pios_usb_board_data_priv.h"

View File

@ -582,8 +582,6 @@ const struct pios_ppm_cfg pios_ppm_main_cfg = {
#if defined(PIOS_INCLUDE_PPM_OUT) #if defined(PIOS_INCLUDE_PPM_OUT)
#include <pios_ppm_out_priv.h> #include <pios_ppm_out_priv.h>
uint32_t pios_ppm_id;
static const struct pios_tim_channel pios_tim_ppmout[] = { static const struct pios_tim_channel pios_tim_ppmout[] = {
{ {
.timer = TIM2, .timer = TIM2,
@ -640,7 +638,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg = {
.GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_OD, .GPIO_Mode = GPIO_Mode_AF_OD,
}, },
} },
.vsense_active_low = false
}; };
#include "pios_usb_board_data_priv.h" #include "pios_usb_board_data_priv.h"

View File

@ -218,10 +218,9 @@ void PIOS_Board_Init(void) {
/* Initalize the RFM22B radio COM device. */ /* Initalize the RFM22B radio COM device. */
#if defined(PIOS_INCLUDE_RFM22B) #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_board_info * bdinfo = &pios_board_info_blob;
const struct pios_rfm22b_cfg *pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); 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, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) { if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) {
PIOS_Assert(0); PIOS_Assert(0);
} }

View File

@ -502,7 +502,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg = {
.GPIO_Mode = GPIO_Mode_IN, .GPIO_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_OD, .GPIO_OType = GPIO_OType_OD,
}, },
} },
.vsense_active_low = false
}; };
#include "pios_usb_board_data_priv.h" #include "pios_usb_board_data_priv.h"

View File

@ -343,10 +343,10 @@ PIOS_FLASHFS_Logfs_Init(&fs_id, &flashfs_internal_cfg, &pios_internal_flash_driv
PIOS_Assert(0); PIOS_Assert(0);
} }
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); uint8_t *gps_rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN);
PIOS_Assert(rx_buffer); PIOS_Assert(gps_rx_buffer);
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, 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)) { NULL, 0)) {
PIOS_Assert(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); PIOS_DEBUG_Assert(0);
} }
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_RX_BUF_LEN); uint8_t *aux_rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_RX_BUF_LEN);
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_TX_BUF_LEN); uint8_t *aux_tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_TX_BUF_LEN);
PIOS_Assert(rx_buffer); PIOS_Assert(aux_rx_buffer);
PIOS_Assert(tx_buffer); PIOS_Assert(aux_tx_buffer);
if (PIOS_COM_Init(&pios_com_aux_id, &pios_usart_com_driver, pios_usart_aux_id, if (PIOS_COM_Init(&pios_com_aux_id, &pios_usart_com_driver, pios_usart_aux_id,
rx_buffer, PIOS_COM_AUX_RX_BUF_LEN, aux_rx_buffer, PIOS_COM_AUX_RX_BUF_LEN,
tx_buffer, PIOS_COM_AUX_TX_BUF_LEN)) { aux_tx_buffer, PIOS_COM_AUX_TX_BUF_LEN)) {
PIOS_DEBUG_Assert(0); PIOS_DEBUG_Assert(0);
} }
} }
@ -383,13 +383,13 @@ PIOS_FLASHFS_Logfs_Init(&fs_id, &flashfs_internal_cfg, &pios_internal_flash_driv
PIOS_Assert(0); PIOS_Assert(0);
} }
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); uint8_t *telem_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); uint8_t *telem_tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN);
PIOS_Assert(rx_buffer); PIOS_Assert(telem_rx_buffer);
PIOS_Assert(tx_buffer); PIOS_Assert(telem_tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id, 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, telem_rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { telem_tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) {
PIOS_Assert(0); PIOS_Assert(0);
} }
} }

View File

@ -1837,7 +1837,8 @@ static const struct pios_usb_cfg pios_usb_main_rm1_cfg = {
.GPIO_Mode = GPIO_Mode_IN, .GPIO_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_OD, .GPIO_OType = GPIO_OType_OD,
}, },
} },
.vsense_active_low = false
}; };
static const struct pios_usb_cfg pios_usb_main_rm2_cfg = { 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_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_OD, .GPIO_OType = GPIO_OType_OD,
}, },
} },
.vsense_active_low = false
}; };
const struct pios_usb_cfg * PIOS_BOARD_HW_DEFS_GetUsbCfg (uint32_t board_revision) const struct pios_usb_cfg * PIOS_BOARD_HW_DEFS_GetUsbCfg (uint32_t board_revision)

View File

@ -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, 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) ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind)
{ {
uint32_t pios_usart_dsm_id; 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; 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_usart_dsm_id, *proto, *bind)) {
PIOS_Assert(0); 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; 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 */ /* Set up the receiver port. Later this should be optional */
uint32_t pios_pwm_id; 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; uint32_t pios_pwm_rcvr_id;
if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_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; 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; 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; uint32_t pios_ppm_rcvr_id;
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_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; break;
case HWSETTINGS_RADIOPORT_TELEMETRY: case HWSETTINGS_RADIOPORT_TELEMETRY:
{ {
extern const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision); const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev);
const struct pios_board_info * bdinfo = &pios_board_info_blob; if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) {
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)) {
PIOS_Assert(0); PIOS_Assert(0);
} }

View File

@ -2003,7 +2003,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg = {
.GPIO_Mode = GPIO_Mode_IN, .GPIO_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_OD, .GPIO_OType = GPIO_OType_OD,
}, },
} },
.vsense_active_low = false
}; };
#include "pios_usb_board_data_priv.h" #include "pios_usb_board_data_priv.h"

View File

@ -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, 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) ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind)
{ {
uint32_t pios_usart_dsm_id; 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; 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_usart_dsm_id, *proto, *bind)) {
PIOS_Assert(0); PIOS_Assert(0);
} }

View File

@ -68,11 +68,11 @@ struct PeriodicObjectListStruct {
typedef struct PeriodicObjectListStruct PeriodicObjectList; typedef struct PeriodicObjectListStruct PeriodicObjectList;
// Private variables // Private variables
static PeriodicObjectList* objList; static PeriodicObjectList* mObjList;
static xQueueHandle queue; static xQueueHandle mQueue;
static xTaskHandle eventTaskHandle; static xTaskHandle mEventTaskHandle;
static xSemaphoreHandle mutex; static xSemaphoreHandle mMutex;
static EventStats stats; static EventStats mStats;
// Private functions // Private functions
static int32_t processPeriodicUpdates(); static int32_t processPeriodicUpdates();
@ -89,19 +89,19 @@ static uint16_t randomizePeriod(uint16_t periodMs);
int32_t EventDispatcherInitialize() int32_t EventDispatcherInitialize()
{ {
// Initialize variables // Initialize variables
objList = NULL; mObjList = NULL;
memset(&stats, 0, sizeof(EventStats)); memset(&mStats, 0, sizeof(EventStats));
// Create mutex // Create mMutex
mutex = xSemaphoreCreateRecursiveMutex(); mMutex = xSemaphoreCreateRecursiveMutex();
if (mutex == NULL) if (mMutex == NULL)
return -1; return -1;
// Create event queue // Create event queue
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(EventCallbackInfo)); mQueue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(EventCallbackInfo));
// Create task // 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 // Done
return 0; return 0;
@ -113,9 +113,9 @@ int32_t EventDispatcherInitialize()
*/ */
void EventGetStats(EventStats* statsOut) void EventGetStats(EventStats* statsOut)
{ {
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); xSemaphoreTakeRecursive(mMutex, portMAX_DELAY);
memcpy(statsOut, &stats, sizeof(EventStats)); memcpy(statsOut, &mStats, sizeof(EventStats));
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mMutex);
} }
/** /**
@ -123,9 +123,9 @@ void EventGetStats(EventStats* statsOut)
*/ */
void EventClearStats() void EventClearStats()
{ {
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); xSemaphoreTakeRecursive(mMutex, portMAX_DELAY);
memset(&stats, 0, sizeof(EventStats)); memset(&mStats, 0, sizeof(EventStats));
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mMutex);
} }
/** /**
@ -143,7 +143,7 @@ int32_t EventCallbackDispatch(UAVObjEvent* ev, UAVObjEventCallback cb)
evInfo.cb = cb; evInfo.cb = cb;
evInfo.queue = 0; evInfo.queue = 0;
// Push to queue // 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
} }
/** /**
@ -206,24 +206,24 @@ static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQue
{ {
PeriodicObjectList *objEntry; PeriodicObjectList *objEntry;
// Get lock // Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); xSemaphoreTakeRecursive(mMutex, portMAX_DELAY);
// Check that the object is not already connected // Check that the object is not already connected
LL_FOREACH(objList, objEntry) LL_FOREACH(mObjList, objEntry) {
{
if (objEntry->evInfo.cb == cb && if (objEntry->evInfo.cb == cb &&
objEntry->evInfo.queue == queue && objEntry->evInfo.queue == queue &&
objEntry->evInfo.ev.obj == ev->obj && objEntry->evInfo.ev.obj == ev->obj &&
objEntry->evInfo.ev.instId == ev->instId && objEntry->evInfo.ev.instId == ev->instId &&
objEntry->evInfo.ev.event == ev->event) objEntry->evInfo.ev.event == ev->event) {
{
// Already registered, do nothing // Already registered, do nothing
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mMutex);
return -1; return -1;
} }
} }
// Create handle // Create handle
objEntry = (PeriodicObjectList*)pvPortMalloc(sizeof(PeriodicObjectList)); objEntry = (PeriodicObjectList*)pvPortMalloc(sizeof(PeriodicObjectList));
if (objEntry == NULL) return -1; if (objEntry == NULL) {
return -1;
}
objEntry->evInfo.ev.obj = ev->obj; objEntry->evInfo.ev.obj = ev->obj;
objEntry->evInfo.ev.instId = ev->instId; objEntry->evInfo.ev.instId = ev->instId;
objEntry->evInfo.ev.event = ev->event; objEntry->evInfo.ev.event = ev->event;
@ -232,9 +232,9 @@ static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQue
objEntry->updatePeriodMs = periodMs; objEntry->updatePeriodMs = periodMs;
objEntry->timeToNextUpdateMs = randomizePeriod(periodMs); // avoid bunching of updates objEntry->timeToNextUpdateMs = randomizePeriod(periodMs); // avoid bunching of updates
// Add to list // Add to list
LL_APPEND(objList, objEntry); LL_APPEND(mObjList, objEntry);
// Release lock // Release lock
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mMutex);
return 0; return 0;
} }
@ -250,26 +250,24 @@ static int32_t eventPeriodicUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, xQue
{ {
PeriodicObjectList* objEntry; PeriodicObjectList* objEntry;
// Get lock // Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); xSemaphoreTakeRecursive(mMutex, portMAX_DELAY);
// Find object // Find object
LL_FOREACH(objList, objEntry) LL_FOREACH(mObjList, objEntry) {
{
if (objEntry->evInfo.cb == cb && if (objEntry->evInfo.cb == cb &&
objEntry->evInfo.queue == queue && objEntry->evInfo.queue == queue &&
objEntry->evInfo.ev.obj == ev->obj && objEntry->evInfo.ev.obj == ev->obj &&
objEntry->evInfo.ev.instId == ev->instId && objEntry->evInfo.ev.instId == ev->instId &&
objEntry->evInfo.ev.event == ev->event) objEntry->evInfo.ev.event == ev->event) {
{
// Object found, update period // Object found, update period
objEntry->updatePeriodMs = periodMs; objEntry->updatePeriodMs = periodMs;
objEntry->timeToNextUpdateMs = randomizePeriod(periodMs); // avoid bunching of updates objEntry->timeToNextUpdateMs = randomizePeriod(periodMs); // avoid bunching of updates
// Release lock // Release lock
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mMutex);
return 0; return 0;
} }
} }
// If this point is reached the object was not found // If this point is reached the object was not found
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mMutex);
return -1; return -1;
} }
@ -283,7 +281,7 @@ static void eventTask()
EventCallbackInfo evInfo; EventCallbackInfo evInfo;
/* Must do this in task context to ensure that TaskMonitor has already finished its init */ /* 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 // Initialize time
timeToNextUpdateMs = xTaskGetTickCount()*portTICK_RATE_MS; timeToNextUpdateMs = xTaskGetTickCount()*portTICK_RATE_MS;
@ -295,7 +293,7 @@ static void eventTask()
delayMs = timeToNextUpdateMs - (xTaskGetTickCount() * portTICK_RATE_MS); delayMs = timeToNextUpdateMs - (xTaskGetTickCount() * portTICK_RATE_MS);
// Wait for queue message // 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 // Invoke callback, if one
if ( evInfo.cb != 0) if ( evInfo.cb != 0)
@ -324,49 +322,43 @@ static int32_t processPeriodicUpdates()
int32_t offset; int32_t offset;
// Get lock // Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); xSemaphoreTakeRecursive(mMutex, portMAX_DELAY);
// Iterate through each object and update its timer, if zero then transmit object. // Iterate through each object and update its timer, if zero then transmit object.
// Also calculate smallest delay to next update. // Also calculate smallest delay to next update.
timeToNextUpdate = xTaskGetTickCount()*portTICK_RATE_MS + MAX_UPDATE_PERIOD_MS; 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 object is configured for periodic updates
if (objEntry->updatePeriodMs > 0) if (objEntry->updatePeriodMs > 0) {
{
// Check if time for the next update // Check if time for the next update
timeNow = xTaskGetTickCount()*portTICK_RATE_MS; timeNow = xTaskGetTickCount()*portTICK_RATE_MS;
if (objEntry->timeToNextUpdateMs <= timeNow) if (objEntry->timeToNextUpdateMs <= timeNow) {
{
// Reset timer // Reset timer
offset = (timeNow - objEntry->timeToNextUpdateMs) % objEntry->updatePeriodMs; offset = (timeNow - objEntry->timeToNextUpdateMs) % objEntry->updatePeriodMs;
objEntry->timeToNextUpdateMs = timeNow + objEntry->updatePeriodMs - offset; objEntry->timeToNextUpdateMs = timeNow + objEntry->updatePeriodMs - offset;
// Invoke callback, if one // 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 objEntry->evInfo.cb(&objEntry->evInfo.ev); // the function is expected to copy the event information
} }
// Push event to queue, if one // Push event to queue, if one
if ( objEntry->evInfo.queue != 0) if (objEntry->evInfo.queue != 0) {
{ if (xQueueSend(objEntry->evInfo.queue, &objEntry->evInfo.ev, 0) != pdTRUE ) { // do not block if queue is full
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);
if (objEntry->evInfo.ev.obj != NULL) }
stats.lastErrorID = UAVObjGetID(objEntry->evInfo.ev.obj); ++mStats.eventErrors;
++stats.eventErrors;
} }
} }
} }
// Update minimum delay // Update minimum delay
if (objEntry->timeToNextUpdateMs < timeToNextUpdate) if (objEntry->timeToNextUpdateMs < timeToNextUpdate) {
{
timeToNextUpdate = objEntry->timeToNextUpdateMs; timeToNextUpdate = objEntry->timeToNextUpdateMs;
} }
} }
} }
// Done // Done
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mMutex);
return timeToNextUpdate; return timeToNextUpdate;
} }

View File

@ -23,13 +23,27 @@ QSlider::add-page:horizontal {
border-radius: 4px; border-radius: 4px;
} }
QSlider::add-page:horizontal:disabled {
background: #eee;
border: 1px solid #999;
width: 1px;
border-radius: 4px;
}
QSlider::sub-page:horizontal { QSlider::sub-page:horizontal {
background: rgb(249, 117, 76); background: rgb(78, 147, 246);
border: 1px solid #777; border: 1px solid #777;
height: 1px; height: 1px;
border-radius: 4px; border-radius: 4px;
} }
QSlider::sub-page:horizontal:disabled {
background: #ccc;
border: 1px solid #999;
width: 1px;
border-radius: 4px;
}
QSlider::handle:horizontal { QSlider::handle:horizontal {
background: rgb(196, 196, 196); background: rgb(196, 196, 196);
width: 18px; width: 18px;
@ -56,13 +70,27 @@ QSlider::sub-page:vertical {
border-radius: 4px; border-radius: 4px;
} }
QSlider::sub-page:vertical:disabled {
background: #eee;
border: 1px solid #999;
width: 1px;
border-radius: 4px;
}
QSlider::add-page:vertical { QSlider::add-page:vertical {
background: rgb(249, 117, 76); background: rgb(78, 147, 246);
border: 1px solid #777; border: 1px solid #777;
width: 1px; width: 1px;
border-radius: 4px; border-radius: 4px;
} }
QSlider::add-page:vertical:disabled {
background: #ccc;
border: 1px solid #999;
width: 1px;
border-radius: 4px;
}
QSlider::handle:vertical { QSlider::handle:vertical {
background: rgb(196, 196, 196); background: rgb(196, 196, 196);
width: 18px; width: 18px;

View File

@ -1,18 +1 @@
/* Windows styles */ /* 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;
}

View File

@ -91,6 +91,13 @@ void MyTabbedStackWidget::removeTab(int index)
delete item; 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 int MyTabbedStackWidget::currentIndex() const
{ {
return m_listWidget->currentRow(); return m_listWidget->currentRow();

View File

@ -47,6 +47,8 @@ public:
void removeTab(int index); void removeTab(int index);
void setIconSize(int size) { m_listWidget->setIconSize(QSize(size, size)); } void setIconSize(int size) { m_listWidget->setIconSize(QSize(size, size)); }
void setWidgetsEnabled(bool enabled);
int currentIndex() const; int currentIndex() const;
void insertCornerWidget(int index, QWidget *widget); void insertCornerWidget(int index, QWidget *widget);

View File

@ -308,7 +308,9 @@ void ConfigCcpmWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->SwashLvlPositionSlider); parent.addWidget(m_aircraft->SwashLvlPositionSlider);
parent.addWidget(m_aircraft->SwashLvlPositionSpinBox); parent.addWidget(m_aircraft->SwashLvlPositionSpinBox);
parent.addWidget(m_aircraft->ThrottleCurve->getCurveWidget()); 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); parent.addWidget(m_aircraft->ccpmAdvancedSettingsTable);
} }

View File

@ -68,7 +68,6 @@ ConfigCustomWidget::ConfigCustomWidget(QWidget *parent) :
for (int i = 1; i < (int) VehicleConfig::CHANNEL_NUMELEM; i++) { for (int i = 1; i < (int) VehicleConfig::CHANNEL_NUMELEM; i++) {
m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd); m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd);
} }
} }
ConfigCustomWidget::~ConfigCustomWidget() ConfigCustomWidget::~ConfigCustomWidget()
@ -84,7 +83,9 @@ void ConfigCustomWidget::setupUI(QString frameType)
void ConfigCustomWidget::registerWidgets(ConfigTaskWidget &parent) { void ConfigCustomWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->customMixerTable); parent.addWidget(m_aircraft->customMixerTable);
parent.addWidget(m_aircraft->customThrottle1Curve->getCurveWidget()); parent.addWidget(m_aircraft->customThrottle1Curve->getCurveWidget());
parent.addWidget(m_aircraft->customThrottle1Curve);
parent.addWidget(m_aircraft->customThrottle2Curve->getCurveWidget()); parent.addWidget(m_aircraft->customThrottle2Curve->getCurveWidget());
parent.addWidget(m_aircraft->customThrottle2Curve);
} }
void ConfigCustomWidget::resetActuators(GUIConfigDataUnion *configData) void ConfigCustomWidget::resetActuators(GUIConfigDataUnion *configData)

View File

@ -87,11 +87,9 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) :
m_aircraft->fixedWingType->addItems(fixedWingTypes); m_aircraft->fixedWingType->addItems(fixedWingTypes);
// Set default model to "Elevator aileron rudder" // 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))); 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() ConfigFixedWingWidget::~ConfigFixedWingWidget()
@ -109,64 +107,61 @@ void ConfigFixedWingWidget::setupUI(QString frameType)
if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") { if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") {
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder")); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder"));
m_aircraft->fwRudder1ChannelBox->setEnabled(true); m_aircraft->fwRudder1ChannelBox->setEnabled(true);
m_aircraft->fwRudder1Label->setEnabled(true);
m_aircraft->fwRudder2ChannelBox->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true);
m_aircraft->fwRudder2Label->setEnabled(true);
m_aircraft->fwElevator1ChannelBox->setEnabled(true); m_aircraft->fwElevator1ChannelBox->setEnabled(true);
m_aircraft->fwElevator1Label->setEnabled(true);
m_aircraft->fwElevator2ChannelBox->setEnabled(true); m_aircraft->fwElevator2ChannelBox->setEnabled(true);
m_aircraft->fwElevator2Label->setEnabled(true);
m_aircraft->fwAileron1ChannelBox->setEnabled(true); m_aircraft->fwAileron1ChannelBox->setEnabled(true);
m_aircraft->fwAileron1Label->setEnabled(true);
m_aircraft->fwAileron2ChannelBox->setEnabled(true); m_aircraft->fwAileron2ChannelBox->setEnabled(true);
m_aircraft->fwAileron2Label->setEnabled(true);
m_aircraft->fwAileron1Label->setText("Aileron 1"); m_aircraft->fwAileron1Label->setText("Aileron 1");
m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->fwAileron2Label->setText("Aileron 2");
m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator1Label->setText("Elevator 1");
m_aircraft->fwElevator2Label->setText("Elevator 2"); 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") { } else if (frameType == "FixedWingElevon" || frameType == "Elevon") {
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon"));
m_aircraft->fwAileron1Label->setText("Elevon 1"); m_aircraft->fwAileron1Label->setText("Elevon 1");
m_aircraft->fwAileron2Label->setText("Elevon 2"); m_aircraft->fwAileron2Label->setText("Elevon 2");
m_aircraft->fwElevator1ChannelBox->setEnabled(false); m_aircraft->fwElevator1ChannelBox->setEnabled(false);
m_aircraft->fwElevator1Label->setEnabled(false);
m_aircraft->fwElevator2ChannelBox->setEnabled(false); m_aircraft->fwElevator2ChannelBox->setEnabled(false);
m_aircraft->fwElevator2Label->setEnabled(false);
m_aircraft->fwRudder1ChannelBox->setEnabled(true); m_aircraft->fwRudder1ChannelBox->setEnabled(true);
m_aircraft->fwRudder1Label->setEnabled(true);
m_aircraft->fwRudder2ChannelBox->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true);
m_aircraft->fwRudder2Label->setEnabled(true);
m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator1Label->setText("Elevator 1");
m_aircraft->fwElevator2Label->setText("Elevator 2"); m_aircraft->fwElevator2Label->setText("Elevator 2");
m_aircraft->elevonMixBox->setHidden(false);
m_aircraft->elevonLabel1->setText("Roll"); m_aircraft->elevonLabel1->setText("Roll");
m_aircraft->elevonLabel2->setText("Pitch"); m_aircraft->elevonLabel2->setText("Pitch");
m_aircraft->elevonSlider1->setEnabled(true);
m_aircraft->elevonSlider2->setEnabled(true);
} else if (frameType == "FixedWingVtail" || frameType == "Vtail") { } else if (frameType == "FixedWingVtail" || frameType == "Vtail") {
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail"));
m_aircraft->fwRudder1ChannelBox->setEnabled(false); m_aircraft->fwRudder1ChannelBox->setEnabled(false);
m_aircraft->fwRudder1Label->setEnabled(false);
m_aircraft->fwRudder2ChannelBox->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->fwElevator1Label->setText("Vtail 1");
m_aircraft->fwElevator1ChannelBox->setEnabled(true);
m_aircraft->fwElevator2Label->setText("Vtail 2"); m_aircraft->fwElevator2Label->setText("Vtail 2");
m_aircraft->elevonMixBox->setHidden(false);
m_aircraft->fwElevator2ChannelBox->setEnabled(true); m_aircraft->fwElevator2ChannelBox->setEnabled(true);
m_aircraft->fwElevator2Label->setEnabled(true);
m_aircraft->fwAileron1Label->setText("Aileron 1"); m_aircraft->fwAileron1Label->setText("Aileron 1");
m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->fwAileron2Label->setText("Aileron 2");
m_aircraft->elevonLabel1->setText("Rudder"); m_aircraft->elevonLabel1->setText("Rudder");
m_aircraft->elevonLabel2->setText("Pitch"); m_aircraft->elevonLabel2->setText("Pitch");
m_aircraft->elevonSlider1->setEnabled(true);
m_aircraft->elevonSlider2->setEnabled(true);
} }
} }
void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) { void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->fixedWingThrottle->getCurveWidget()); parent.addWidget(m_aircraft->fixedWingThrottle->getCurveWidget());
parent.addWidget(m_aircraft->fixedWingThrottle);
parent.addWidget(m_aircraft->fixedWingType); parent.addWidget(m_aircraft->fixedWingType);
parent.addWidget(m_aircraft->fwEngineChannelBox); parent.addWidget(m_aircraft->fwEngineChannelBox);
@ -508,6 +503,14 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType)
return true; 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. This function displays text and color formatting in order to help the user understand what channels have not yet been configured.
*/ */

View File

@ -64,6 +64,9 @@ private:
bool setupFrameElevon(QString airframeType); bool setupFrameElevon(QString airframeType);
bool setupFrameVtail(QString airframeType); bool setupFrameVtail(QString airframeType);
protected:
void enableControls(bool enable);
private slots: private slots:
virtual void setupUI(QString airframeType); virtual void setupUI(QString airframeType);
virtual bool throwConfigError(QString airframeType); virtual bool throwConfigError(QString airframeType);

View File

@ -79,11 +79,9 @@ ConfigGroundVehicleWidget::ConfigGroundVehicleWidget(QWidget *parent) :
m_aircraft->groundVehicleType->addItems(groundVehicleTypes); m_aircraft->groundVehicleType->addItems(groundVehicleTypes);
// Set default model to "Turnable (car)" // 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))); 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() ConfigGroundVehicleWidget::~ConfigGroundVehicleWidget()
@ -96,42 +94,32 @@ ConfigGroundVehicleWidget::~ConfigGroundVehicleWidget()
*/ */
void ConfigGroundVehicleWidget::setupUI(QString frameType) void ConfigGroundVehicleWidget::setupUI(QString frameType)
{ {
m_aircraft->differentialSteeringMixBox->setHidden(true);
//STILL NEEDS WORK
// Setup the UI // Setup the UI
m_aircraft->gvEngineChannelBox->setEnabled(false); m_aircraft->gvEngineChannelBox->setEnabled(false);
m_aircraft->gvEngineLabel->setEnabled(false);
m_aircraft->gvAileron1ChannelBox->setEnabled(false); m_aircraft->gvAileron1ChannelBox->setEnabled(false);
m_aircraft->gvAileron1Label->setEnabled(false);
m_aircraft->gvAileron2ChannelBox->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)") { if (frameType == "GroundVehicleDifferential" || frameType == "Differential (tank)") {
// Tank // Tank
setComboCurrentIndex(m_aircraft->groundVehicleType, setComboCurrentIndex(m_aircraft->groundVehicleType,
m_aircraft->groundVehicleType->findText("Differential (tank)")); m_aircraft->groundVehicleType->findText("Differential (tank)"));
m_aircraft->gvMotor1ChannelBox->setEnabled(true); m_aircraft->gvMotor1ChannelBox->setEnabled(true);
m_aircraft->gvMotor1Label->setEnabled(true);
m_aircraft->gvMotor2ChannelBox->setEnabled(true); m_aircraft->gvMotor2ChannelBox->setEnabled(true);
m_aircraft->gvMotor2Label->setEnabled(true);
m_aircraft->gvMotor1Label->setText("Left motor"); m_aircraft->gvMotor1Label->setText("Left motor");
m_aircraft->gvMotor2Label->setText("Right motor"); m_aircraft->gvMotor2Label->setText("Right motor");
m_aircraft->gvSteering1ChannelBox->setEnabled(false); m_aircraft->gvSteering1ChannelBox->setEnabled(false);
m_aircraft->gvSteering1Label->setEnabled(false);
m_aircraft->gvSteering2ChannelBox->setEnabled(false); m_aircraft->gvSteering2ChannelBox->setEnabled(false);
m_aircraft->gvSteering2Label->setEnabled(false);
m_aircraft->gvSteering2Label->setText("Rear steering"); 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->gvThrottleCurve1GroupBox->setTitle("Left throttle curve");
m_aircraft->gvThrottleCurve2GroupBox->setTitle("Right throttle curve"); m_aircraft->gvThrottleCurve2GroupBox->setTitle("Right throttle curve");
@ -140,24 +128,16 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType)
// Motorcycle // Motorcycle
setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Motorcycle")); setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Motorcycle"));
m_aircraft->gvMotor1ChannelBox->setEnabled(false); m_aircraft->gvMotor1ChannelBox->setEnabled(false);
m_aircraft->gvMotor1Label->setEnabled(false);
m_aircraft->gvMotor2ChannelBox->setEnabled(true); m_aircraft->gvMotor2ChannelBox->setEnabled(true);
m_aircraft->gvMotor2Label->setEnabled(true);
m_aircraft->gvMotor1Label->setText("Front motor"); m_aircraft->gvMotor1Label->setText("Front motor");
m_aircraft->gvMotor2Label->setText("Rear motor"); m_aircraft->gvMotor2Label->setText("Rear motor");
m_aircraft->gvSteering1ChannelBox->setEnabled(true); m_aircraft->gvSteering1ChannelBox->setEnabled(true);
m_aircraft->gvSteering1Label->setEnabled(true);
m_aircraft->gvSteering2ChannelBox->setEnabled(true); m_aircraft->gvSteering2ChannelBox->setEnabled(true);
m_aircraft->gvSteering2Label->setEnabled(true);
m_aircraft->gvSteering2Label->setText("Balancing"); m_aircraft->gvSteering2Label->setText("Balancing");
m_aircraft->differentialSteeringMixBox->setHidden(true);
m_aircraft->gvThrottleCurve1GroupBox->setTitle("Front throttle curve"); m_aircraft->gvThrottleCurve1GroupBox->setTitle("Front throttle curve");
m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve"); m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve");
} else { } else {
@ -165,31 +145,40 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType)
setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Turnable (car)")); setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Turnable (car)"));
m_aircraft->gvMotor1ChannelBox->setEnabled(true); m_aircraft->gvMotor1ChannelBox->setEnabled(true);
m_aircraft->gvMotor1Label->setEnabled(true);
m_aircraft->gvMotor2ChannelBox->setEnabled(true); m_aircraft->gvMotor2ChannelBox->setEnabled(true);
m_aircraft->gvMotor2Label->setEnabled(true);
m_aircraft->gvMotor1Label->setText("Front motor"); m_aircraft->gvMotor1Label->setText("Front motor");
m_aircraft->gvMotor2Label->setText("Rear motor"); m_aircraft->gvMotor2Label->setText("Rear motor");
m_aircraft->gvSteering1ChannelBox->setEnabled(true); m_aircraft->gvSteering1ChannelBox->setEnabled(true);
m_aircraft->gvSteering1Label->setEnabled(true);
m_aircraft->gvSteering2ChannelBox->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->gvThrottleCurve1GroupBox->setTitle("Front throttle curve");
m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear 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) { void ConfigGroundVehicleWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->groundVehicleThrottle1->getCurveWidget()); parent.addWidget(m_aircraft->groundVehicleThrottle1->getCurveWidget());
parent.addWidget(m_aircraft->groundVehicleThrottle1);
parent.addWidget(m_aircraft->groundVehicleThrottle2->getCurveWidget()); parent.addWidget(m_aircraft->groundVehicleThrottle2->getCurveWidget());
parent.addWidget(m_aircraft->groundVehicleThrottle2);
parent.addWidget(m_aircraft->groundVehicleType); 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) void ConfigGroundVehicleWidget::resetActuators(GUIConfigDataUnion *configData)

View File

@ -54,6 +54,9 @@ public:
virtual void refreshWidgetsValues(QString frameType); virtual void refreshWidgetsValues(QString frameType);
virtual QString updateConfigObjectsFromWidgets(); virtual QString updateConfigObjectsFromWidgets();
protected:
void enableControls(bool enable);
private: private:
Ui_GroundConfigWidget *m_aircraft; Ui_GroundConfigWidget *m_aircraft;

View File

@ -122,6 +122,7 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) :
// Connect the multirotor motor reverse checkbox // Connect the multirotor motor reverse checkbox
connect(m_aircraft->MultirotorRevMixerCheckBox, SIGNAL(clicked(bool)), this, SLOT(reverseMultirotorMotor())); connect(m_aircraft->MultirotorRevMixerCheckBox, SIGNAL(clicked(bool)), this, SLOT(reverseMultirotorMotor()));
updateEnableControls();
} }
ConfigMultiRotorWidget::~ConfigMultiRotorWidget() ConfigMultiRotorWidget::~ConfigMultiRotorWidget()
@ -134,6 +135,81 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
Q_ASSERT(m_aircraft); Q_ASSERT(m_aircraft);
Q_ASSERT(quad); 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 // disable triyaw channel
m_aircraft->triYawChannelBox->setEnabled(false); m_aircraft->triYawChannelBox->setEnabled(false);
@ -148,109 +224,32 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
} }
if (frameType == "Tri" || frameType == "Tricopter Y") { 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); enableComboBoxes(this, CHANNELBOXNAME, 3, true);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
setYawMixLevel(50);
m_aircraft->triYawChannelBox->setEnabled(true); m_aircraft->triYawChannelBox->setEnabled(true);
} else if (frameType == "QuadX" || frameType == "Quad X") { } 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); 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 +") { } 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); enableComboBoxes(this, CHANNELBOXNAME, 4, true);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
setYawMixLevel(50);
} else if (frameType == "Hexa" || frameType == "Hexacopter") { } 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); enableComboBoxes(this, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(33);
setYawMixLevel(33);
} else if (frameType == "HexaX" || frameType == "Hexacopter X") { } 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); enableComboBoxes(this, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(50);
setYawMixLevel(33);
} else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") { } 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); enableComboBoxes(this, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(50);
setYawMixLevel(66);
} else if (frameType == "Octo" || frameType == "Octocopter") { } 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); enableComboBoxes(this, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(33);
setYawMixLevel(25);
} else if (frameType == "OctoV" || frameType == "Octocopter V") { } 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); enableComboBoxes(this, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(25);
m_aircraft->mrPitchMixLevel->setValue(25);
setYawMixLevel(25);
} else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") { } 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); 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") { } 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); 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) { void ConfigMultiRotorWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->multiThrottleCurve->getCurveWidget()); parent.addWidget(m_aircraft->multiThrottleCurve->getCurveWidget());
parent.addWidget(m_aircraft->multiThrottleCurve);
parent.addWidget(m_aircraft->multirotorFrameType); parent.addWidget(m_aircraft->multirotorFrameType);
parent.addWidget(m_aircraft->multiMotorChannelBox1); parent.addWidget(m_aircraft->multiMotorChannelBox1);
parent.addWidget(m_aircraft->multiMotorChannelBox2); parent.addWidget(m_aircraft->multiMotorChannelBox2);
@ -264,6 +263,7 @@ void ConfigMultiRotorWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->mrRollMixLevel); parent.addWidget(m_aircraft->mrRollMixLevel);
parent.addWidget(m_aircraft->mrYawMixLevel); parent.addWidget(m_aircraft->mrYawMixLevel);
parent.addWidget(m_aircraft->triYawChannelBox); parent.addWidget(m_aircraft->triYawChannelBox);
parent.addWidget(m_aircraft->MultirotorRevMixerCheckBox);
} }
void ConfigMultiRotorWidget::resetActuators(GUIConfigDataUnion *configData) void ConfigMultiRotorWidget::resetActuators(GUIConfigDataUnion *configData)
@ -1048,3 +1048,11 @@ void ConfigMultiRotorWidget::resizeEvent(QResizeEvent *event)
Q_UNUSED(event); Q_UNUSED(event);
m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio); m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio);
} }
void ConfigMultiRotorWidget::enableControls(bool enable)
{
ConfigTaskWidget::enableControls(enable);
if(enable) {
setupEnabledControls(m_aircraft->multirotorFrameType->currentText());
}
}

View File

@ -58,6 +58,7 @@ public:
protected: protected:
void showEvent(QShowEvent *event); void showEvent(QShowEvent *event);
void resizeEvent(QResizeEvent *event); void resizeEvent(QResizeEvent *event);
void enableControls(bool enable);
private: private:
Ui_MultiRotorConfigWidget *m_aircraft; Ui_MultiRotorConfigWidget *m_aircraft;
@ -77,6 +78,7 @@ private:
void setYawMixLevel(int); void setYawMixLevel(int);
void updateAirframe(QString multiRotorType); void updateAirframe(QString multiRotorType);
void setupEnabledControls(QString multiRotorType);
private slots: private slots:
virtual void setupUI(QString airframeType); virtual void setupUI(QString airframeType);

View File

@ -43,24 +43,24 @@
ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent)
{ {
m_camerastabilization = new Ui_CameraStabilizationWidget(); ui = new Ui_CameraStabilizationWidget();
m_camerastabilization->setupUi(this); ui->setupUi(this);
addApplySaveButtons(m_camerastabilization->camerastabilizationSaveRAM,m_camerastabilization->camerastabilizationSaveSD); addApplySaveButtons(ui->camerastabilizationSaveRAM,ui->camerastabilizationSaveSD);
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>(); Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode()) if(!settings->useExpertMode())
m_camerastabilization->camerastabilizationSaveRAM->setVisible(false); ui->camerastabilizationSaveRAM->setVisible(false);
// These widgets don't have direct relation to UAVObjects // These widgets don't have direct relation to UAVObjects
// and need special processing // and need special processing
QComboBox *outputs[] = { QComboBox *outputs[] = {
m_camerastabilization->rollChannel, ui->rollChannel,
m_camerastabilization->pitchChannel, ui->pitchChannel,
m_camerastabilization->yawChannel, ui->yawChannel,
}; };
const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]);
@ -78,10 +78,10 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent
autoLoadWidgets(); autoLoadWidgets();
// Add some widgets to track their UI dirty state and handle smartsave // Add some widgets to track their UI dirty state and handle smartsave
addWidget(m_camerastabilization->enableCameraStabilization); addWidget(ui->enableCameraStabilization);
addWidget(m_camerastabilization->rollChannel); addWidget(ui->rollChannel);
addWidget(m_camerastabilization->pitchChannel); addWidget(ui->pitchChannel);
addWidget(m_camerastabilization->yawChannel); addWidget(ui->yawChannel);
// Add some UAVObjects to monitor their changes in addition to autoloaded ones. // 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 // 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))); connect(this, SIGNAL(defaultRequested(int)), this, SLOT(defaultRequestedSlot(int)));
disableMouseWheelEvents(); disableMouseWheelEvents();
updateEnableControls();
} }
ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget() ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget()
@ -120,7 +121,7 @@ void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj)
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
HwSettings::DataFields hwSettingsData = hwSettings->getData(); HwSettings::DataFields hwSettingsData = hwSettings->getData();
m_camerastabilization->enableCameraStabilization->setChecked( ui->enableCameraStabilization->setChecked(
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED); hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED);
// Load mixer outputs which are mapped to camera controls // 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]); const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]);
QComboBox *outputs[] = { QComboBox *outputs[] = {
m_camerastabilization->rollChannel, ui->rollChannel,
m_camerastabilization->pitchChannel, ui->pitchChannel,
m_camerastabilization->yawChannel ui->yawChannel
}; };
const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]);
@ -175,7 +176,7 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets()
// Save state of the module enable checkbox first. // Save state of the module enable checkbox first.
// Do not use setData() member on whole object, if possible, since it triggers // Do not use setData() member on whole object, if possible, since it triggers
// unnessesary UAVObect update. // unnessesary UAVObect update.
quint8 enableModule = m_camerastabilization->enableCameraStabilization->isChecked() ? quint8 enableModule = ui->enableCameraStabilization->isChecked() ?
HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED; HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED;
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_CAMERASTAB, enableModule); hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_CAMERASTAB, enableModule);
@ -202,13 +203,13 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets()
const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]); const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]);
QComboBox *outputs[] = { QComboBox *outputs[] = {
m_camerastabilization->rollChannel, ui->rollChannel,
m_camerastabilization->pitchChannel, ui->pitchChannel,
m_camerastabilization->yawChannel ui->yawChannel
}; };
const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]);
m_camerastabilization->message->setText(""); ui->message->setText("");
bool widgetUpdated; bool widgetUpdated;
do { do {
widgetUpdated = false; widgetUpdated = false;
@ -223,7 +224,7 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets()
// If the mixer channel already mapped to something, it should not be // If the mixer channel already mapped to something, it should not be
// used for camera output, we reset it to none // used for camera output, we reset it to none
outputs[i]->setCurrentIndex(0); 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 // Loop again or we may have inconsistent widget and UAVObject
widgetUpdated = true; 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 // For outputs we set them all to none, so don't use any UAVObject to get defaults
QComboBox *outputs[] = { QComboBox *outputs[] = {
m_camerastabilization->rollChannel, ui->rollChannel,
m_camerastabilization->pitchChannel, ui->pitchChannel,
m_camerastabilization->yawChannel, ui->yawChannel,
}; };
const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]);
@ -280,8 +281,3 @@ void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group)
outputs[i]->setCurrentIndex(0); outputs[i]->setCurrentIndex(0);
} }
} }
/**
@}
@}
*/

View File

@ -43,7 +43,7 @@ public:
~ConfigCameraStabilizationWidget(); ~ConfigCameraStabilizationWidget();
private: private:
Ui_CameraStabilizationWidget *m_camerastabilization; Ui_CameraStabilizationWidget *ui;
void refreshWidgetsValues(UAVObject *obj); void refreshWidgetsValues(UAVObject *obj);
void updateObjectsFromWidgets(); void updateObjectsFromWidgets();

View File

@ -216,15 +216,9 @@ void ConfigCCAttitudeWidget::setAccelFiltering(bool active)
void ConfigCCAttitudeWidget::enableControls(bool enable) void ConfigCCAttitudeWidget::enableControls(bool enable)
{ {
if(ui->zeroBias) {
ui->zeroBias->setEnabled(enable); ui->zeroBias->setEnabled(enable);
}
if(ui->zeroGyroBiasOnArming) {
ui->zeroGyroBiasOnArming->setEnabled(enable); ui->zeroGyroBiasOnArming->setEnabled(enable);
}
if(ui->accelTauSpinbox) {
ui->accelTauSpinbox->setEnabled(enable); ui->accelTauSpinbox->setEnabled(enable);
}
ConfigTaskWidget::enableControls(enable); ConfigTaskWidget::enableControls(enable);
} }

View File

@ -49,8 +49,6 @@
#include <QtGui/QVBoxLayout> #include <QtGui/QVBoxLayout>
#include <QtGui/QPushButton> #include <QtGui/QPushButton>
ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
{ {
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
@ -94,7 +92,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new DefaultAttitudeWidget(this); qwd = new DefaultAttitudeWidget(this);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS")); ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off);
@ -106,7 +104,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigCameraStabilizationWidget(this); qwd = new ConfigCameraStabilizationWidget(this);
ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Camera Stab")); ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Gimbal"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off);
@ -164,15 +162,17 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event)
QWidget::resizeEvent(event); QWidget::resizeEvent(event);
} }
void ConfigGadgetWidget::onAutopilotDisconnect() { void ConfigGadgetWidget::onAutopilotDisconnect()
{
int selectedIndex = ftw->currentIndex(); int selectedIndex = ftw->currentIndex();
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_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new DefaultAttitudeWidget(this); QWidget *qwd = new DefaultAttitudeWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors); ftw->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS")); ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
@ -186,8 +186,8 @@ void ConfigGadgetWidget::onAutopilotDisconnect() {
emit autopilotDisconnected(); emit autopilotDisconnected();
} }
void ConfigGadgetWidget::onAutopilotConnect() { void ConfigGadgetWidget::onAutopilotConnect()
{
qDebug() << "ConfigGadgetWidget onAutopilotConnect"; qDebug() << "ConfigGadgetWidget onAutopilotConnect";
// First of all, check what Board type we are talking to, and // First of all, check what Board type we are talking to, and
// if necessary, remove/add tabs in the config gadget: // if necessary, remove/add tabs in the config gadget:
@ -204,7 +204,7 @@ void ConfigGadgetWidget::onAutopilotConnect() {
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigCCAttitudeWidget(this); QWidget *qwd = new ConfigCCAttitudeWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors); ftw->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("CopterControl")); ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
@ -212,7 +212,6 @@ void ConfigGadgetWidget::onAutopilotConnect() {
qwd = new ConfigCCHWWidget(this); qwd = new ConfigCCHWWidget(this);
ftw->removeTab(ConfigGadgetWidget::hardware); ftw->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
} else if ((board & 0xff00) == 0x0900) { } else if ((board & 0xff00) == 0x0900) {
// Revolution family // Revolution family
@ -221,7 +220,7 @@ void ConfigGadgetWidget::onAutopilotConnect() {
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigRevoWidget(this); QWidget *qwd = new ConfigRevoWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors); ftw->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Revolution")); ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
@ -229,13 +228,13 @@ void ConfigGadgetWidget::onAutopilotConnect() {
qwd = new ConfigRevoHWWidget(this); qwd = new ConfigRevoHWWidget(this);
ftw->removeTab(ConfigGadgetWidget::hardware); ftw->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
} else { } else {
// Unknown board // Unknown board
qDebug() << "Unknown board " << board; qDebug() << "Unknown board " << board;
} }
ftw->setCurrentIndex(selectedIndex); ftw->setCurrentIndex(selectedIndex);
} }
emit autopilotConnected(); emit autopilotConnected();
} }
@ -247,8 +246,7 @@ void ConfigGadgetWidget::tabAboutToChange(int i, bool * proceed)
if (!wid) { if (!wid) {
return; return;
} }
if(wid->isDirty()) if (wid->isDirty()) {
{
int ans = QMessageBox::warning(this, tr("Unsaved changes"), tr("The tab you are leaving has unsaved changes," int ans = QMessageBox::warning(this, tr("Unsaved changes"), tr("The tab you are leaving has unsaved changes,"
"if you proceed they will be lost." "if you proceed they will be lost."
"Do you still want to proceed?"), QMessageBox::Yes, QMessageBox::No); "Do you still want to proceed?"), QMessageBox::Yes, QMessageBox::No);
@ -267,8 +265,7 @@ void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *)
{ {
// Restart the disconnection timer. // Restart the disconnection timer.
oplinkTimeout->start(5000); oplinkTimeout->start(5000);
if (!oplinkConnected) if (!oplinkConnected) {
{
qDebug() << "ConfigGadgetWidget onOPLinkConnect"; qDebug() << "ConfigGadgetWidget onOPLinkConnect";
QIcon *icon = new QIcon(); QIcon *icon = new QIcon();
@ -281,7 +278,8 @@ void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *)
} }
} }
void ConfigGadgetWidget::onOPLinkDisconnect() { void ConfigGadgetWidget::onOPLinkDisconnect()
{
qDebug() << "ConfigGadgetWidget onOPLinkDisconnect"; qDebug() << "ConfigGadgetWidget onOPLinkDisconnect";
oplinkTimeout->stop(); oplinkTimeout->stop();
ftw->removeTab(ConfigGadgetWidget::oplink); ftw->removeTab(ConfigGadgetWidget::oplink);

View File

@ -63,17 +63,17 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager()); manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager());
flightStatusObj = FlightStatus::GetInstance(getObjectManager()); flightStatusObj = FlightStatus::GetInstance(getObjectManager());
receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager()); receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager());
m_config = new Ui_InputWidget(); ui = new Ui_InputWidget();
m_config->setupUi(this); ui->setupUi(this);
addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); addApplySaveButtons(ui->saveRCInputToRAM,ui->saveRCInputToSD);
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>(); Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode()) 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 //Generate the rows of buttons in the input channel form GUI
unsigned int index=0; unsigned int index=0;
@ -82,13 +82,16 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
{ {
Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM); Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM);
inputChannelForm * inpForm=new inputChannelForm(this,index==0); 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); inpForm->setName(name);
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inpForm->ui->channelGroup,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inpForm->ui->channelGroup,index);
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inpForm->ui->channelNumber,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inpForm->ui->channelNumber,index);
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inpForm->ui->channelMin,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inpForm->ui->channelMin,index);
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inpForm->ui->channelNeutral,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inpForm->ui->channelNeutral,index);
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inpForm->ui->channelMax,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 // Input filter response time fields supported for some channels only
switch (index) { switch (index) {
@ -114,51 +117,53 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
++index; ++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(ui->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard()));
connect(m_config->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int))); connect(ui->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int)));
connect(m_config->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool))); connect(ui->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool)));
connect(m_config->wzNext,SIGNAL(clicked()),this,SLOT(wzNext())); connect(ui->wzNext,SIGNAL(clicked()),this,SLOT(wzNext()));
connect(m_config->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel())); connect(ui->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel()));
connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack())); connect(ui->wzBack,SIGNAL(clicked()),this,SLOT(wzBack()));
m_config->stackedWidget->setCurrentIndex(0); ui->stackedWidget->setCurrentIndex(0);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos1, 0, 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos1, 0, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos2, 1, 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos2, 1, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos3, 2, 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos3, 2, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos4, 3, 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos4, 3, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos5, 4, 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos5, 4, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos6, 5, 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos6, 5, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", m_config->fmsPosNum); addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", ui->fmsPosNum);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Roll, "Roll", 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Roll, "Roll", 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Roll, "Roll", 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Pitch, "Pitch", 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Pitch, "Pitch", 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Pitch, "Pitch", 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Yaw, "Yaw", 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Yaw, "Yaw", 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Yaw, "Yaw", 1, true); addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl); addUAVObjectToWidgetRelation("ManualControlSettings","Arming",ui->armControl);
addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000); addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",ui->armTimeout,0,1000);
connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider())); connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider()));
connect( ManualControlSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(updatePositionSlider())); connect( ManualControlSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(updatePositionSlider()));
enableControls(false);
addWidget(ui->configurationWizard);
addWidget(ui->runCalibration);
populateWidgets(); populateWidgets();
refreshWidgetsValues(); refreshWidgetsValues();
// Connect the help button // 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)); ui->graphicsView->setScene(new QGraphicsScene(this));
m_config->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate); ui->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
m_renderer = new QSvgRenderer(); m_renderer = new QSvgRenderer();
QGraphicsScene *l_scene = m_config->graphicsView->scene(); QGraphicsScene *l_scene = ui->graphicsView->scene();
m_config->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); 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()) 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. 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_txAccess2Orig.translate(orig.x(),orig.y());
m_txAccess2->setTransform(m_txAccess2Orig,true); 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); animate=new QTimer(this);
connect(animate,SIGNAL(timeout()),this,SLOT(moveTxControls())); connect(animate,SIGNAL(timeout()),this,SLOT(moveTxControls()));
@ -293,7 +298,10 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
ManualControlSettings::CHANNELGROUPS_ACCESSORY0 << ManualControlSettings::CHANNELGROUPS_ACCESSORY0 <<
ManualControlSettings::CHANNELGROUPS_ACCESSORY1 << ManualControlSettings::CHANNELGROUPS_ACCESSORY1 <<
ManualControlSettings::CHANNELGROUPS_ACCESSORY2; ManualControlSettings::CHANNELGROUPS_ACCESSORY2;
updateEnableControls();
} }
void ConfigInputWidget::resetTxControls() 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) void ConfigInputWidget::resizeEvent(QResizeEvent *event)
{ {
QWidget::resizeEvent(event); QWidget::resizeEvent(event);
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio );
} }
void ConfigInputWidget::openHelp() void ConfigInputWidget::openHelp()
@ -335,8 +352,8 @@ void ConfigInputWidget::goToWizard()
msgBox.exec(); msgBox.exec();
// Set correct tab visible before starting wizard. // Set correct tab visible before starting wizard.
if(m_config->tabWidget->currentIndex() != 0) { if(ui->tabWidget->currentIndex() != 0) {
m_config->tabWidget->setCurrentIndex(0); ui->tabWidget->setCurrentIndex(0);
} }
// Stash current manual settings data in case the wizard is // Stash current manual settings data in case the wizard is
@ -351,27 +368,27 @@ void ConfigInputWidget::goToWizard()
// start the wizard // start the wizard
wizardSetUpStep(wizardWelcome); wizardSetUpStep(wizardWelcome);
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio); ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio);
} }
void ConfigInputWidget::disableWizardButton(int value) void ConfigInputWidget::disableWizardButton(int value)
{ {
if(value!=0) if(value!=0)
m_config->groupBox_3->setVisible(false); ui->groupBox_3->setVisible(false);
else else
m_config->groupBox_3->setVisible(true); ui->groupBox_3->setVisible(true);
} }
void ConfigInputWidget::wzCancel() void ConfigInputWidget::wzCancel()
{ {
dimOtherControls(false); dimOtherControls(false);
manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata()); manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata());
m_config->stackedWidget->setCurrentIndex(0); ui->stackedWidget->setCurrentIndex(0);
if(wizardStep != wizardNone) if(wizardStep != wizardNone)
wizardTearDownStep(wizardStep); wizardTearDownStep(wizardStep);
wizardStep=wizardNone; wizardStep=wizardNone;
m_config->stackedWidget->setCurrentIndex(0); ui->stackedWidget->setCurrentIndex(0);
// Load settings back from beginning of wizard // Load settings back from beginning of wizard
manualSettingsObj->setData(previousManualSettingsData); manualSettingsObj->setData(previousManualSettingsData);
@ -433,8 +450,8 @@ void ConfigInputWidget::wzNext()
} }
manualSettingsObj->setData(manualSettingsData); manualSettingsObj->setData(manualSettingsData);
// move to Arming Settings tab // move to Arming Settings tab
m_config->stackedWidget->setCurrentIndex(0); ui->stackedWidget->setCurrentIndex(0);
m_config->tabWidget->setCurrentIndex(2); ui->tabWidget->setCurrentIndex(2);
break; break;
default: default:
Q_ASSERT(0); Q_ASSERT(0);
@ -481,7 +498,7 @@ void ConfigInputWidget::wzBack()
void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
{ {
m_config->wzText2->clear(); ui->wzText2->clear();
switch(step) { switch(step) {
case wizardWelcome: case wizardWelcome:
@ -491,22 +508,22 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
delete wd; delete wd;
} }
extraWidgets.clear(); extraWidgets.clear();
m_config->graphicsView->setVisible(false); ui->graphicsView->setVisible(false);
setTxMovement(nothing); 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" "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" "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")); "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); ui->stackedWidget->setCurrentIndex(1);
m_config->wzBack->setEnabled(false); ui->wzBack->setEnabled(false);
break; break;
case wizardChooseType: case wizardChooseType:
{ {
m_config->graphicsView->setVisible(true); ui->graphicsView->setVisible(true);
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio); ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio);
setTxMovement(nothing); setTxMovement(nothing);
m_config->wzText->setText(tr("Please choose your transmitter type:")); ui->wzText->setText(tr("Please choose your transmitter type:"));
m_config->wzBack->setEnabled(true); ui->wzBack->setEnabled(true);
QRadioButton * typeAcro=new QRadioButton(tr("Acro: normal transmitter for fixed-wing or quad"),this); 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); QRadioButton * typeHeli=new QRadioButton(tr("Helicopter: has collective pitch and throttle input"),this);
if (transmitterType == heli) { if (transmitterType == heli) {
@ -515,20 +532,20 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
else { else {
typeAcro->setChecked(true); 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.clear();
extraWidgets.append(typeAcro); extraWidgets.append(typeAcro);
extraWidgets.append(typeHeli); extraWidgets.append(typeHeli);
m_config->radioButtonsLayout->layout()->addWidget(typeAcro); ui->radioButtonsLayout->layout()->addWidget(typeAcro);
m_config->radioButtonsLayout->layout()->addWidget(typeHeli); ui->radioButtonsLayout->layout()->addWidget(typeHeli);
} }
break; break;
case wizardChooseMode: case wizardChooseMode:
{ {
m_config->wzBack->setEnabled(true); ui->wzBack->setEnabled(true);
extraWidgets.clear(); 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) { for (int i = 0; i <= mode4; ++i) {
QString label; QString label;
txMode mode = static_cast<txMode>(i); txMode mode = static_cast<txMode>(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; case mode4: label = tr("Mode 4: Throttle and Ailerons on the left, Elevator and Rudder on the right"); break;
default: Q_ASSERT(0); 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); QRadioButton * modeButton = new QRadioButton(label, this);
if (transmitterMode == mode) { if (transmitterMode == mode) {
modeButton->setChecked(true); modeButton->setChecked(true);
} }
extraWidgets.append(modeButton); extraWidgets.append(modeButton);
m_config->radioButtonsLayout->layout()->addWidget(modeButton); ui->radioButtonsLayout->layout()->addWidget(modeButton);
} }
} }
break; break;
@ -565,11 +582,11 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
nextChannel(); nextChannel();
manualSettingsData=manualSettingsObj->getData(); manualSettingsData=manualSettingsObj->getData();
connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
m_config->wzNext->setEnabled(false); ui->wzNext->setEnabled(false);
break; break;
case wizardIdentifyCenter: case wizardIdentifyCenter:
setTxMovement(centerAll); 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."))); "If your FlightMode switch has only two positions, leave it in either position.")));
break; break;
case wizardIdentifyLimits: case wizardIdentifyLimits:
@ -578,7 +595,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1); accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1);
accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2); accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2);
setTxMovement(nothing); 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(); fastMdata();
manualSettingsData=manualSettingsObj->getData(); manualSettingsData=manualSettingsObj->getData();
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i) for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
@ -612,13 +629,13 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
QCheckBox * cb=new QCheckBox(name,this); QCheckBox * cb=new QCheckBox(name,this);
// Make sure checked status matches current one // Make sure checked status matches current one
cb->setChecked(manualSettingsData.ChannelMax[index] < manualSettingsData.ChannelMin[index]); cb->setChecked(manualSettingsData.ChannelMax[index] < manualSettingsData.ChannelMin[index]);
dynamic_cast<QGridLayout*>(m_config->checkBoxesLayout->layout())->addWidget(cb, extraWidgets.size()/4, extraWidgets.size()%4); dynamic_cast<QGridLayout*>(ui->checkBoxesLayout->layout())->addWidget(cb, extraWidgets.size()/4, extraWidgets.size()%4);
extraWidgets.append(cb); extraWidgets.append(cb);
connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls())); connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
} }
} }
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); 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(); fastMdata();
break; break;
case wizardFinish: case wizardFinish:
@ -626,7 +643,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
connect(accessoryDesiredObj0, 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 " "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."))); "tab where you can set your desired arming sequence and save the configuration.")));
fastMdata(); fastMdata();
@ -666,7 +683,7 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
break; break;
case wizardIdentifySticks: case wizardIdentifySticks:
disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
m_config->wzNext->setEnabled(true); ui->wzNext->setEnabled(true);
setTxMovement(nothing); setTxMovement(nothing);
break; break;
case wizardIdentifyCenter: case wizardIdentifyCenter:
@ -742,21 +759,21 @@ void ConfigInputWidget::restoreMdata()
void ConfigInputWidget::setChannel(int newChan) void ConfigInputWidget::setChannel(int newChan)
{ {
if(newChan == ManualControlSettings::CHANNELGROUPS_COLLECTIVE) 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) 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)) 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 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))); "Move the %1 stick.")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan)));
if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory") || if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory") ||
manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) { manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) {
m_config->wzNext->setEnabled(true); ui->wzNext->setEnabled(true);
m_config->wzText->setText(m_config->wzText->text() + tr(" Alternatively, click Next to skip this channel.")); ui->wzText->setText(ui->wzText->text() + tr(" Alternatively, click Next to skip this channel."));
} else } else
m_config->wzNext->setEnabled(false); ui->wzNext->setEnabled(false);
setMoveFromCommand(newChan); setMoveFromCommand(newChan);
@ -1249,15 +1266,6 @@ void ConfigInputWidget::dimOtherControls(bool value)
m_txFlightMode->setOpacity(opac); 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() void ConfigInputWidget::invertControls()
{ {
manualSettingsData=manualSettingsObj->getData(); manualSettingsData=manualSettingsObj->getData();
@ -1318,7 +1326,7 @@ void ConfigInputWidget::moveFMSlider()
uint8_t pos = ((int16_t)(valueScaled * 256) + 256) * manualSettingsDataPriv.FlightModeNumber >> 9; uint8_t pos = ((int16_t)(valueScaled * 256) + 256) * manualSettingsDataPriv.FlightModeNumber >> 9;
if (pos >= manualSettingsDataPriv.FlightModeNumber) if (pos >= manualSettingsDataPriv.FlightModeNumber)
pos = manualSettingsDataPriv.FlightModeNumber - 1; pos = manualSettingsDataPriv.FlightModeNumber - 1;
m_config->fmsSlider->setValue(pos); ui->fmsSlider->setValue(pos);
} }
void ConfigInputWidget::updatePositionSlider() void ConfigInputWidget::updatePositionSlider()
@ -1328,22 +1336,22 @@ void ConfigInputWidget::updatePositionSlider()
switch(manualSettingsDataPriv.FlightModeNumber) { switch(manualSettingsDataPriv.FlightModeNumber) {
default: default:
case 6: case 6:
m_config->fmsModePos6->setEnabled(true); ui->fmsModePos6->setEnabled(true);
// pass through // pass through
case 5: case 5:
m_config->fmsModePos5->setEnabled(true); ui->fmsModePos5->setEnabled(true);
// pass through // pass through
case 4: case 4:
m_config->fmsModePos4->setEnabled(true); ui->fmsModePos4->setEnabled(true);
// pass through // pass through
case 3: case 3:
m_config->fmsModePos3->setEnabled(true); ui->fmsModePos3->setEnabled(true);
// pass through // pass through
case 2: case 2:
m_config->fmsModePos2->setEnabled(true); ui->fmsModePos2->setEnabled(true);
// pass through // pass through
case 1: case 1:
m_config->fmsModePos1->setEnabled(true); ui->fmsModePos1->setEnabled(true);
// pass through // pass through
case 0: case 0:
break; break;
@ -1351,22 +1359,22 @@ void ConfigInputWidget::updatePositionSlider()
switch(manualSettingsDataPriv.FlightModeNumber) { switch(manualSettingsDataPriv.FlightModeNumber) {
case 0: case 0:
m_config->fmsModePos1->setEnabled(false); ui->fmsModePos1->setEnabled(false);
// pass through // pass through
case 1: case 1:
m_config->fmsModePos2->setEnabled(false); ui->fmsModePos2->setEnabled(false);
// pass through // pass through
case 2: case 2:
m_config->fmsModePos3->setEnabled(false); ui->fmsModePos3->setEnabled(false);
// pass through // pass through
case 3: case 3:
m_config->fmsModePos4->setEnabled(false); ui->fmsModePos4->setEnabled(false);
// pass through // pass through
case 4: case 4:
m_config->fmsModePos5->setEnabled(false); ui->fmsModePos5->setEnabled(false);
// pass through // pass through
case 5: case 5:
m_config->fmsModePos6->setEnabled(false); ui->fmsModePos6->setEnabled(false);
// pass through // pass through
case 6: case 6:
default: default:
@ -1395,7 +1403,7 @@ void ConfigInputWidget::updateCalibration()
void ConfigInputWidget::simpleCalibration(bool enable) void ConfigInputWidget::simpleCalibration(bool enable)
{ {
if (enable) { if (enable) {
m_config->configurationWizard->setEnabled(false); ui->configurationWizard->setEnabled(false);
QMessageBox msgBox; QMessageBox msgBox;
msgBox.setText(tr("Arming Settings are now set to 'Always Disarmed' for your safety.")); 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())); connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration()));
} else { } else {
m_config->configurationWizard->setEnabled(true); ui->configurationWizard->setEnabled(true);
manualCommandData = manualCommandObj->getData(); manualCommandData = manualCommandObj->getData();
manualSettingsData = manualSettingsObj->getData(); manualSettingsData = manualSettingsObj->getData();

View File

@ -61,6 +61,7 @@ public:
enum txMovementType{vertical,horizontal,jump,mix}; enum txMovementType{vertical,horizontal,jump,mix};
enum txType {acro, heli}; enum txType {acro, heli};
void startInputWizard() { goToWizard(); } void startInputWizard() { goToWizard(); }
void enableControls(bool enable);
private: private:
bool growing; bool growing;
@ -68,7 +69,7 @@ private:
txMovements currentMovement; txMovements currentMovement;
int movePos; int movePos;
void setTxMovement(txMovements movement); void setTxMovement(txMovements movement);
Ui_InputWidget *m_config; Ui_InputWidget *ui;
wizardSteps wizardStep; wizardSteps wizardStep;
QList<QPointer<QWidget> > extraWidgets; QList<QPointer<QWidget> > extraWidgets;
txMode transmitterMode; txMode transmitterMode;
@ -166,7 +167,6 @@ private slots:
protected: protected:
void resizeEvent(QResizeEvent *event); void resizeEvent(QResizeEvent *event);
virtual void enableControls(bool enable);
}; };
#endif #endif

View File

@ -51,46 +51,51 @@
ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false) ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false)
{ {
m_config = new Ui_OutputWidget(); ui = new Ui_OutputWidget();
m_config->setupUi(this); ui->setupUi(this);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>(); Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode()) { if(!settings->useExpertMode()) {
m_config->saveRCOutputToRAM->setVisible(false); ui->saveRCOutputToRAM->setVisible(false);
} }
UAVSettingsImportExportFactory *importexportplugin = pm->getObject<UAVSettingsImportExportFactory>(); UAVSettingsImportExportFactory *importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
connect(importexportplugin, SIGNAL(importAboutToBegin()), this, SLOT(stopTests())); 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. connect(ui->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool)));
// 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)));
// Configure the task widget // Configure the task widget
// Connect the help button // 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 // Track the ActuatorSettings object
addUAVObject("ActuatorSettings"); 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 // Associate the buttons with their UAVO fields
addWidget(m_config->cb_outputRate6); addWidget(ui->cb_outputRate6);
addWidget(m_config->cb_outputRate5); addWidget(ui->cb_outputRate5);
addWidget(m_config->cb_outputRate4); addWidget(ui->cb_outputRate4);
addWidget(m_config->cb_outputRate3); addWidget(ui->cb_outputRate3);
addWidget(m_config->cb_outputRate2); addWidget(ui->cb_outputRate2);
addWidget(m_config->cb_outputRate1); addWidget(ui->cb_outputRate1);
addWidget(m_config->spinningArmed); addWidget(ui->spinningArmed);
disconnect(this, SLOT(refreshWidgetsValues(UAVObject*))); disconnect(this, SLOT(refreshWidgetsValues(UAVObject*)));
@ -102,15 +107,16 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
connect(obj,SIGNAL(objectUpdated(UAVObject*)), this, SLOT(disableIfNotMe(UAVObject*))); connect(obj,SIGNAL(objectUpdated(UAVObject*)), this, SLOT(disableIfNotMe(UAVObject*)));
refreshWidgetsValues(); refreshWidgetsValues();
updateEnableControls();
} }
void ConfigOutputWidget::enableControls(bool enable) void ConfigOutputWidget::enableControls(bool enable)
{ {
ConfigTaskWidget::enableControls(enable); ConfigTaskWidget::enableControls(enable);
if(!enable) { if(!enable) {
m_config->channelOutTest->setChecked(false); ui->channelOutTest->setChecked(false);
} }
m_config->channelOutTest->setEnabled(enable); ui->channelOutTest->setEnabled(enable);
} }
ConfigOutputWidget::~ConfigOutputWidget() ConfigOutputWidget::~ConfigOutputWidget()
@ -136,7 +142,7 @@ void ConfigOutputWidget::runChannelTests(bool state)
// Unfortunately must cache this since callback will reoccur // Unfortunately must cache this since callback will reoccur
accInitialData = ActuatorCommand::GetInstance(getObjectManager())->getMetadata(); accInitialData = ActuatorCommand::GetInstance(getObjectManager())->getMetadata();
m_config->channelOutTest->setChecked(false); ui->channelOutTest->setChecked(false);
return; return;
} }
@ -149,7 +155,7 @@ void ConfigOutputWidget::runChannelTests(bool state)
if(retval != QMessageBox::Yes) { if(retval != QMessageBox::Yes) {
state = false; state = false;
qDebug() << "Cancelled"; qDebug() << "Cancelled";
m_config->channelOutTest->setChecked(false); ui->channelOutTest->setChecked(false);
return; return;
} }
} }
@ -209,7 +215,7 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str)
*/ */
void ConfigOutputWidget::sendChannelTest(int index, int value) void ConfigOutputWidget::sendChannelTest(int index, int value)
{ {
if (!m_config->channelOutTest->isChecked()) { if (!ui->channelOutTest->isChecked()) {
return; return;
} }
@ -260,47 +266,47 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj)
} }
// Get the SpinWhileArmed setting // 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 // Setup output rates for all banks
if(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])) == -1) { if(ui->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])) == -1) {
m_config->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])); ui->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]));
} }
if(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])) == -1) { if(ui->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])) == -1) {
m_config->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])); ui->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]));
} }
if(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]) )== -1) { if(ui->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]) )== -1) {
m_config->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])); ui->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]));
} }
if(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])) == -1) { if(ui->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])) == -1) {
m_config->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])); ui->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]));
} }
if(m_config->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])) == -1) { if(ui->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])) == -1) {
m_config->cb_outputRate5->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])); ui->cb_outputRate5->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[4]));
} }
if(m_config->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])) == -1) { if(ui->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])) == -1) {
m_config->cb_outputRate6->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])); ui->cb_outputRate6->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[5]));
} }
m_config->cb_outputRate1->setCurrentIndex(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))); ui->cb_outputRate1->setCurrentIndex(ui->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])));
m_config->cb_outputRate2->setCurrentIndex(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))); ui->cb_outputRate2->setCurrentIndex(ui->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])));
m_config->cb_outputRate3->setCurrentIndex(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]))); ui->cb_outputRate3->setCurrentIndex(ui->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])));
m_config->cb_outputRate4->setCurrentIndex(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]))); ui->cb_outputRate4->setCurrentIndex(ui->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])));
m_config->cb_outputRate5->setCurrentIndex(m_config->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4]))); ui->cb_outputRate5->setCurrentIndex(ui->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_outputRate6->setCurrentIndex(ui->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])));
// Reset to all disabled // Reset to all disabled
m_config->chBank1->setText("-"); ui->chBank1->setText("-");
m_config->chBank2->setText("-"); ui->chBank2->setText("-");
m_config->chBank3->setText("-"); ui->chBank3->setText("-");
m_config->chBank4->setText("-"); ui->chBank4->setText("-");
m_config->chBank5->setText("-"); ui->chBank5->setText("-");
m_config->chBank6->setText("-"); ui->chBank6->setText("-");
m_config->cb_outputRate1->setEnabled(false); ui->cb_outputRate1->setEnabled(false);
m_config->cb_outputRate2->setEnabled(false); ui->cb_outputRate2->setEnabled(false);
m_config->cb_outputRate3->setEnabled(false); ui->cb_outputRate3->setEnabled(false);
m_config->cb_outputRate4->setEnabled(false); ui->cb_outputRate4->setEnabled(false);
m_config->cb_outputRate5->setEnabled(false); ui->cb_outputRate5->setEnabled(false);
m_config->cb_outputRate6->setEnabled(false); ui->cb_outputRate6->setEnabled(false);
// Get connected board model // Get connected board model
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); 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 // Setup labels and combos for banks according to board type
if ((board & 0xff00) == 0x0400) { if ((board & 0xff00) == 0x0400) {
// Coptercontrol family of boards 4 timer banks // Coptercontrol family of boards 4 timer banks
m_config->chBank1->setText("1-3"); ui->chBank1->setText("1-3");
m_config->chBank2->setText("4"); ui->chBank2->setText("4");
m_config->chBank3->setText("5,7-8"); ui->chBank3->setText("5,7-8");
m_config->chBank4->setText("6,9-10"); ui->chBank4->setText("6,9-10");
m_config->cb_outputRate1->setEnabled(true); ui->cb_outputRate1->setEnabled(true);
m_config->cb_outputRate2->setEnabled(true); ui->cb_outputRate2->setEnabled(true);
m_config->cb_outputRate3->setEnabled(true); ui->cb_outputRate3->setEnabled(true);
m_config->cb_outputRate4->setEnabled(true); ui->cb_outputRate4->setEnabled(true);
} }
else if((board & 0xff00) == 0x0900) { else if((board & 0xff00) == 0x0900) {
// Revolution family of boards 6 timer banks // Revolution family of boards 6 timer banks
m_config->chBank1->setText("1-2"); ui->chBank1->setText("1-2");
m_config->chBank2->setText("3"); ui->chBank2->setText("3");
m_config->chBank3->setText("4"); ui->chBank3->setText("4");
m_config->chBank4->setText("5-6"); ui->chBank4->setText("5-6");
m_config->chBank5->setText("7-8"); ui->chBank5->setText("7-8");
m_config->chBank6->setText("9-10"); ui->chBank6->setText("9-10");
m_config->cb_outputRate1->setEnabled(true); ui->cb_outputRate1->setEnabled(true);
m_config->cb_outputRate2->setEnabled(true); ui->cb_outputRate2->setEnabled(true);
m_config->cb_outputRate3->setEnabled(true); ui->cb_outputRate3->setEnabled(true);
m_config->cb_outputRate4->setEnabled(true); ui->cb_outputRate4->setEnabled(true);
m_config->cb_outputRate5->setEnabled(true); ui->cb_outputRate5->setEnabled(true);
m_config->cb_outputRate6->setEnabled(true); ui->cb_outputRate6->setEnabled(true);
} }
} }
@ -371,14 +377,14 @@ void ConfigOutputWidget::updateObjectsFromWidgets()
} }
// Set update rates // Set update rates
actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt(); actuatorSettingsData.ChannelUpdateFreq[0] = ui->cb_outputRate1->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt(); actuatorSettingsData.ChannelUpdateFreq[1] = ui->cb_outputRate2->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt(); actuatorSettingsData.ChannelUpdateFreq[2] = ui->cb_outputRate3->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt(); actuatorSettingsData.ChannelUpdateFreq[3] = ui->cb_outputRate4->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[4] = m_config->cb_outputRate5->currentText().toUInt(); actuatorSettingsData.ChannelUpdateFreq[4] = ui->cb_outputRate5->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[5] = m_config->cb_outputRate6->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_TRUE :
ActuatorSettings::MOTORSSPINWHILEARMED_FALSE; ActuatorSettings::MOTORSSPINWHILEARMED_FALSE;
@ -394,7 +400,7 @@ void ConfigOutputWidget::openHelp()
void ConfigOutputWidget::stopTests() void ConfigOutputWidget::stopTests()
{ {
m_config->channelOutTest->setChecked(false); ui->channelOutTest->setChecked(false);
} }
void ConfigOutputWidget::disableIfNotMe(UAVObject* obj) void ConfigOutputWidget::disableIfNotMe(UAVObject* obj)

View File

@ -50,7 +50,7 @@ public:
private: private:
Ui_OutputWidget *m_config; Ui_OutputWidget *ui;
QList<QSlider> sliders; QList<QSlider> sliders;

View File

@ -20,6 +20,9 @@
<number>0</number> <number>0</number>
</property> </property>
<widget class="QWidget" name="tab"> <widget class="QWidget" name="tab">
<property name="autoFillBackground">
<bool>true</bool>
</property>
<attribute name="title"> <attribute name="title">
<string>HW settings</string> <string>HW settings</string>
</attribute> </attribute>
@ -119,7 +122,7 @@
<number>12</number> <number>12</number>
</property> </property>
<item row="2" column="2"> <item row="2" column="2">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0"> <layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
<item row="7" column="0"> <item row="7" column="0">
<widget class="QLabel" name="label_8"> <widget class="QLabel" name="label_8">
<property name="sizePolicy"> <property name="sizePolicy">

View File

@ -61,8 +61,7 @@ const double ConfigRevoWidget::maxVarValue = 0.1;
// ***************** // *****************
class Thread : public QThread class Thread : public QThread {
{
public: public:
static void usleep(unsigned long usecs) static void usleep(unsigned long usecs)
{ {
@ -74,9 +73,10 @@ public:
ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
ConfigTaskWidget(parent), ConfigTaskWidget(parent),
collectingData(false),
m_ui(new Ui_RevoSensorsWidget()), m_ui(new Ui_RevoSensorsWidget()),
position(-1) collectingData(false),
position(-1),
isBoardRotationStored(false)
{ {
m_ui->setupUi(this); m_ui->setupUi(this);
@ -214,6 +214,8 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
// will be dealing with some null pointers // will be dealing with some null pointers
addUAVObject("RevoCalibration"); addUAVObject("RevoCalibration");
addUAVObject("EKFConfiguration"); addUAVObject("EKFConfiguration");
addUAVObject("HomeLocation");
addUAVObject("AttitudeSettings");
autoLoadWidgets(); autoLoadWidgets();
// Connect the signals // Connect the signals
@ -222,10 +224,17 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData()));
connect(m_ui->noiseMeasurementStart, SIGNAL(clicked()), this, SLOT(doStartNoiseMeasurement())); 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("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(); populateWidgets();
refreshWidgetsValues(); refreshWidgetsValues();
m_ui->tabWidget->setCurrentIndex(0);
} }
ConfigRevoWidget::~ConfigRevoWidget() ConfigRevoWidget::~ConfigRevoWidget()
@ -256,6 +265,10 @@ void ConfigRevoWidget::resizeEvent(QResizeEvent *event)
*/ */
void ConfigRevoWidget::doStartAccelGyroBiasCalibration() void ConfigRevoWidget::doStartAccelGyroBiasCalibration()
{ {
// Store and reset board rotation before calibration starts
isBoardRotationStored = false;
storeAndClearBoardRotation();
m_ui->accelBiasStart->setEnabled(false); m_ui->accelBiasStart->setEnabled(false);
m_ui->accelBiasProgress->setValue(0); m_ui->accelBiasProgress->setValue(0);
@ -312,6 +325,7 @@ void ConfigRevoWidget::doStartAccelGyroBiasCalibration()
void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj)
{ {
QMutexLocker lock(&sensorsUpdateLock); QMutexLocker lock(&sensorsUpdateLock);
Q_UNUSED(lock); Q_UNUSED(lock);
switch (obj->getObjID()) { switch (obj->getObjID()) {
@ -349,7 +363,6 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj)
if (accel_accum_x.size() >= NOISE_SAMPLES && if (accel_accum_x.size() >= NOISE_SAMPLES &&
gyro_accum_y.size() >= NOISE_SAMPLES && gyro_accum_y.size() >= NOISE_SAMPLES &&
collectingData == true) { collectingData == true) {
collectingData = false; collectingData = false;
Accels *accels = Accels::GetInstance(getObjectManager()); Accels *accels = Accels::GetInstance(getObjectManager());
@ -385,9 +398,11 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj)
accels->setMetadata(initialAccelsMdata); accels->setMetadata(initialAccelsMdata);
gyros->setMetadata(initialGyrosMdata); 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)
@ -397,25 +412,20 @@ int LinearEquationsSolving(int nDim, double* pfMatr, double* pfVect, double* pfS
int i, j, k, m; int i, j, k, m;
for(k=0; k<(nDim-1); k++) // base row of matrix for (k = 0; k < (nDim - 1); k++) { // base row of matrix
{
// search of line with max element // search of line with max element
fMaxElem = fabs(pfMatr[k * nDim + k]); fMaxElem = fabs(pfMatr[k * nDim + k]);
m = k; m = k;
for(i=k+1; i<nDim; i++) for (i = k + 1; i < nDim; i++) {
{ if (fMaxElem < fabs(pfMatr[i * nDim + k])) {
if(fMaxElem < fabs(pfMatr[i*nDim + k]) )
{
fMaxElem = pfMatr[i * nDim + k]; fMaxElem = pfMatr[i * nDim + k];
m = i; m = i;
} }
} }
// permutation of base line (index k) and max element line(index m) // permutation of base line (index k) and max element line(index m)
if(m != k) if (m != k) {
{ for (i = k; i < nDim; i++) {
for(i=k; i<nDim; i++)
{
fAcc = pfMatr[k * nDim + i]; fAcc = pfMatr[k * nDim + i];
pfMatr[k * nDim + i] = pfMatr[m * nDim + i]; pfMatr[k * nDim + i] = pfMatr[m * nDim + i];
pfMatr[m * nDim + i] = fAcc; pfMatr[m * nDim + i] = fAcc;
@ -425,25 +435,22 @@ int LinearEquationsSolving(int nDim, double* pfMatr, double* pfVect, double* pfS
pfVect[m] = fAcc; pfVect[m] = fAcc;
} }
if( pfMatr[k*nDim + k] == 0.) return 0; // needs improvement !!! if (pfMatr[k * nDim + k] == 0.) {
return 0; // needs improvement !!!
}
// triangulation of matrix with coefficients // triangulation of matrix with coefficients
for(j=(k+1); j<nDim; j++) // current row of matrix for (j = (k + 1); j < nDim; j++) { // current row of matrix
{
fAcc = -pfMatr[j * nDim + k] / pfMatr[k * nDim + k]; fAcc = -pfMatr[j * nDim + k] / pfMatr[k * nDim + k];
for(i=k; i<nDim; i++) for (i = k; i < nDim; i++) {
{
pfMatr[j * nDim + i] = pfMatr[j * nDim + i] + fAcc * pfMatr[k * nDim + i]; pfMatr[j * nDim + i] = pfMatr[j * nDim + i] + fAcc * pfMatr[k * nDim + i];
} }
pfVect[j] = pfVect[j] + fAcc * pfVect[k]; // free member recalculation pfVect[j] = pfVect[j] + fAcc * pfVect[k]; // free member recalculation
} }
} }
for(k=(nDim-1); k>=0; k--) for (k = (nDim - 1); k >= 0; k--) {
{
pfSolution[k] = pfVect[k]; pfSolution[k] = pfVect[k];
for(i=(k+1); i<nDim; i++) for (i = (k + 1); i < nDim; i++) {
{
pfSolution[k] -= (pfMatr[k * nDim + i] * pfSolution[i]); pfSolution[k] -= (pfMatr[k * nDim + i] * pfSolution[i]);
} }
pfSolution[k] = pfSolution[k] / pfMatr[k * nDim + k]; pfSolution[k] = pfSolution[k] / pfMatr[k * nDim + k];
@ -475,7 +482,9 @@ int SixPointInConstFieldCal( double ConstMag, double x[6], double y[6], double z
} }
// solve for c0=bx/Sx, c1=Sy^2/Sx^2; c2=Sy*by/Sx^2, c3=Sz^2/Sx^2, c4=Sz*bz/Sx^2 // solve for c0=bx/Sx, c1=Sy^2/Sx^2; c2=Sy*by/Sx^2, c3=Sz^2/Sx^2, c4=Sz*bz/Sx^2
if ( !LinearEquationsSolving( 5, (double *)A, f, c) ) return 0; if (!LinearEquationsSolving(5, (double *)A, f, c)) {
return 0;
}
// use one magnitude equation and c's to find Sx - doesn't matter which - all give the same answer // use one magnitude equation and c's to find Sx - doesn't matter which - all give the same answer
xp = x[0]; yp = y[0]; zp = z[0]; xp = x[0]; yp = y[0]; zp = z[0];
@ -501,16 +510,20 @@ int SixPointInConstFieldCal( double ConstMag, double x[6], double y[6], double z
*/ */
void ConfigRevoWidget::doStartSixPointCalibration() void ConfigRevoWidget::doStartSixPointCalibration()
{ {
// Store and reset board rotation before calibration starts
isBoardRotationStored = false;
storeAndClearBoardRotation();
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
Q_ASSERT(revoCalibration); Q_ASSERT(revoCalibration);
Q_ASSERT(homeLocation); Q_ASSERT(homeLocation);
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
HomeLocation::DataFields homeLocationData = homeLocation->getData(); HomeLocation::DataFields homeLocationData = homeLocation->getData();
// check if Homelocation is set // check if Homelocation is set
if(!homeLocationData.Set) if (!homeLocationData.Set) {
{
QMessageBox msgBox; QMessageBox msgBox;
msgBox.setInformativeText(tr("<p>HomeLocation not SET.</p><p>Please set your HomeLocation and try again. Aborting calibration!</p>")); msgBox.setInformativeText(tr("<p>HomeLocation not SET.</p><p>Please set your HomeLocation and try again. Aborting calibration!</p>"));
msgBox.setStandardButtons(QMessageBox::Ok); msgBox.setStandardButtons(QMessageBox::Ok);
@ -597,6 +610,7 @@ void ConfigRevoWidget::doStartSixPointCalibration()
void ConfigRevoWidget::savePositionData() void ConfigRevoWidget::savePositionData()
{ {
QMutexLocker lock(&sensorsUpdateLock); QMutexLocker lock(&sensorsUpdateLock);
m_ui->sixPointsSave->setEnabled(false); m_ui->sixPointsSave->setEnabled(false);
accel_accum_x.clear(); accel_accum_x.clear();
@ -709,6 +723,9 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj)
accels->setMetadata(initialAccelsMdata); accels->setMetadata(initialAccelsMdata);
#endif #endif
mag->setMetadata(initialMagMdata); mag->setMetadata(initialMagMdata);
// Recall saved board rotation
recallBoardRotation();
} }
} }
} }
@ -723,6 +740,7 @@ void ConfigRevoWidget::computeScaleBias()
double Be_length; double Be_length;
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
Q_ASSERT(revoCalibration); Q_ASSERT(revoCalibration);
Q_ASSERT(homeLocation); Q_ASSERT(homeLocation);
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
@ -791,7 +809,7 @@ void ConfigRevoWidget::computeScaleBias()
revoCalibrationData = revoCalibration->getData(); revoCalibrationData = revoCalibration->getData();
m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat.");
} }
#else #else // ifdef SIX_POINT_CAL_ACCEL
bool good_calibration = true; bool good_calibration = true;
good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] ==
revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X];
@ -812,11 +830,47 @@ void ConfigRevoWidget::computeScaleBias()
revoCalibrationData = revoCalibration->getData(); revoCalibrationData = revoCalibration->getData();
m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat.");
} }
#endif #endif // ifdef SIX_POINT_CAL_ACCEL
position = -1; // set to run again 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 Rotate the paper plane
*/ */
@ -825,7 +879,6 @@ void ConfigRevoWidget::displayPlane(QString elementID)
paperplane->setElementId(elementID); paperplane->setElementId(elementID);
m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect()); m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect());
m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio); m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio);
} }
/*********** Noise measurement functions **************/ /*********** Noise measurement functions **************/
@ -835,6 +888,11 @@ void ConfigRevoWidget::displayPlane(QString elementID)
void ConfigRevoWidget::doStartNoiseMeasurement() void ConfigRevoWidget::doStartNoiseMeasurement()
{ {
QMutexLocker lock(&sensorsUpdateLock); QMutexLocker lock(&sensorsUpdateLock);
// Store and reset board rotation before calibration starts
isBoardRotationStored = false;
storeAndClearBoardRotation();
Q_UNUSED(lock); Q_UNUSED(lock);
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
@ -845,8 +903,7 @@ void ConfigRevoWidget::doStartNoiseMeasurement()
HomeLocation::DataFields homeLocationData = homeLocation->getData(); HomeLocation::DataFields homeLocationData = homeLocation->getData();
// check if Homelocation is set // check if Homelocation is set
if(!homeLocationData.Set) if (!homeLocationData.Set) {
{
QMessageBox msgBox; QMessageBox msgBox;
msgBox.setInformativeText(tr("<p>HomeLocation not SET.</p><p>Please set your HomeLocation and try again. Aborting calibration!</p>")); msgBox.setInformativeText(tr("<p>HomeLocation not SET.</p><p>Please set your HomeLocation and try again. Aborting calibration!</p>"));
msgBox.setStandardButtons(QMessageBox::Ok); msgBox.setStandardButtons(QMessageBox::Ok);
@ -907,6 +964,7 @@ void ConfigRevoWidget::doStartNoiseMeasurement()
void ConfigRevoWidget::doGetNoiseSample(UAVObject *obj) void ConfigRevoWidget::doGetNoiseSample(UAVObject *obj)
{ {
QMutexLocker lock(&sensorsUpdateLock); QMutexLocker lock(&sensorsUpdateLock);
Q_UNUSED(lock); Q_UNUSED(lock);
Q_ASSERT(obj); Q_ASSERT(obj);
@ -982,6 +1040,9 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj)
revoCalData.R[EKFConfiguration::R_MAGZ] = listVar(mag_accum_z); revoCalData.R[EKFConfiguration::R_MAGZ] = listVar(mag_accum_z);
ekfConfiguration->setData(revoCalData); ekfConfiguration->setData(revoCalData);
} }
// Recall saved board rotation
recallBoardRotation();
} }
} }
@ -992,44 +1053,55 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj)
void ConfigRevoWidget::drawVariancesGraph() void ConfigRevoWidget::drawVariancesGraph()
{ {
EKFConfiguration *ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager()); EKFConfiguration *ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager());
Q_ASSERT(ekfConfiguration); Q_ASSERT(ekfConfiguration);
if(!ekfConfiguration) if (!ekfConfiguration) {
return; return;
}
EKFConfiguration::DataFields ekfConfigurationData = ekfConfiguration->getData(); EKFConfiguration::DataFields ekfConfigurationData = ekfConfiguration->getData();
// The expected range is from 1E-6 to 1E-1 // The expected range is from 1E-6 to 1E-1
double steps = 6; // 6 bars on the graph double steps = 6; // 6 bars on the graph
float accel_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELX])); float accel_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELX]));
if(accel_x) if (accel_x) {
accel_x->setTransform(QTransform::fromScale(1, accel_x_var), false); accel_x->setTransform(QTransform::fromScale(1, accel_x_var), false);
}
float accel_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELY])); float accel_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELY]));
if(accel_y) if (accel_y) {
accel_y->setTransform(QTransform::fromScale(1, accel_y_var), false); accel_y->setTransform(QTransform::fromScale(1, accel_y_var), false);
}
float accel_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELZ])); float accel_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELZ]));
if(accel_z) if (accel_z) {
accel_z->setTransform(QTransform::fromScale(1, accel_z_var), false); accel_z->setTransform(QTransform::fromScale(1, accel_z_var), false);
}
float gyro_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROX])); float gyro_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROX]));
if(gyro_x) if (gyro_x) {
gyro_x->setTransform(QTransform::fromScale(1, gyro_x_var), false); gyro_x->setTransform(QTransform::fromScale(1, gyro_x_var), false);
}
float gyro_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROY])); float gyro_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROY]));
if(gyro_y) if (gyro_y) {
gyro_y->setTransform(QTransform::fromScale(1, gyro_y_var), false); gyro_y->setTransform(QTransform::fromScale(1, gyro_y_var), false);
}
float gyro_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROZ])); float gyro_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROZ]));
if(gyro_z) if (gyro_z) {
gyro_z->setTransform(QTransform::fromScale(1, gyro_z_var), false); gyro_z->setTransform(QTransform::fromScale(1, gyro_z_var), false);
}
// Scale by 1e-3 because mag vars are much higher. // 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])); float mag_x_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGX]));
if(mag_x) if (mag_x) {
mag_x->setTransform(QTransform::fromScale(1, mag_x_var), false); 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])); float mag_y_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGY]));
if(mag_y) if (mag_y) {
mag_y->setTransform(QTransform::fromScale(1, mag_y_var), false); 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])); float mag_z_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGZ]));
if(mag_z) if (mag_z) {
mag_z->setTransform(QTransform::fromScale(1, mag_z_var), false); mag_z->setTransform(QTransform::fromScale(1, mag_z_var), false);
} }
}
/** /**
* Called by the ConfigTaskWidget parent when RevoCalibration is updated * Called by the ConfigTaskWidget parent when RevoCalibration is updated
@ -1044,12 +1116,31 @@ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object)
m_ui->noiseMeasurementStart->setEnabled(true); m_ui->noiseMeasurementStart->setEnabled(true);
m_ui->sixPointsStart->setEnabled(true); m_ui->sixPointsStart->setEnabled(true);
m_ui->accelBiasStart->setEnabled(true); m_ui->accelBiasStart->setEnabled(true);
m_ui->startDriftCalib->setEnabled(true);
m_ui->calibInstructions->setText(QString("Press \"Start\" above to calibrate.")); 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);
}

View File

@ -43,8 +43,7 @@
class Ui_Widget; class Ui_Widget;
class ConfigRevoWidget: public ConfigTaskWidget class ConfigRevoWidget : public ConfigTaskWidget {
{
Q_OBJECT Q_OBJECT
public: public:
@ -101,6 +100,13 @@ private:
static const int NOISE_SAMPLES = 100; static const int NOISE_SAMPLES = 100;
// Board rotation store/recall
qint16 storedBoardRotation[3];
bool isBoardRotationStored;
void storeAndClearBoardRotation();
void recallBoardRotation();
private slots: private slots:
// ! Overriden method from the configTaskWidget to update UI // ! Overriden method from the configTaskWidget to update UI
virtual void refreshWidgetsValues(UAVObject *object = NULL); virtual void refreshWidgetsValues(UAVObject *object = NULL);
@ -118,10 +124,12 @@ private slots:
void doStartNoiseMeasurement(); void doStartNoiseMeasurement();
void doGetNoiseSample(UAVObject *); void doGetNoiseSample(UAVObject *);
// Slot for clearing home location
void clearHomeLocation();
protected: protected:
void showEvent(QShowEvent *event); void showEvent(QShowEvent *event);
void resizeEvent(QResizeEvent *event); void resizeEvent(QResizeEvent *event);
}; };
#endif // ConfigRevoWidget_H #endif // ConfigRevoWidget_H

View File

@ -1,7 +1,7 @@
/** /**
****************************************************************************** ******************************************************************************
* *
* @file configstabilizationwidget.h * @file configstabilizationwidget.cpp
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins * @addtogroup GCSPlugins GCS Plugins
* @{ * @{
@ -36,132 +36,161 @@
#include <QUrl> #include <QUrl>
#include <QList> #include <QList>
#include <extensionsystem/pluginmanager.h> #include <extensionsystem/pluginmanager.h>
#include <coreplugin/generalsettings.h> #include <coreplugin/generalsettings.h>
ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent)
{ {
m_stabilization = new Ui_StabilizationWidget(); ui = new Ui_StabilizationWidget();
m_stabilization->setupUi(this); ui->setupUi(this);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>(); Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_stabilization->saveStabilizationToRAM_6->setVisible(false);
if (!settings->useExpertMode()) {
ui->saveStabilizationToRAM_6->setVisible(false);
}
autoLoadWidgets(); autoLoadWidgets();
realtimeUpdates = new QTimer(this); realtimeUpdates = new QTimer(this);
connect(m_stabilization->realTimeUpdates_6,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int)));
connect(realtimeUpdates, SIGNAL(timeout()), this, SLOT(apply())); connect(realtimeUpdates, SIGNAL(timeout()), this, SLOT(apply()));
connect(m_stabilization->checkBox_7,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); connect(ui->realTimeUpdates_6, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool)));
connect(m_stabilization->checkBox_2,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); addWidget(ui->realTimeUpdates_6);
connect(m_stabilization->checkBox_8,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); connect(ui->realTimeUpdates_8, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool)));
connect(m_stabilization->checkBox_3,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); 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 *))); connect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *)));
// Link by default
ui->checkBox_7->setChecked(true);
ui->checkBox_8->setChecked(true);
disableMouseWheelEvents(); disableMouseWheelEvents();
updateEnableControls();
} }
ConfigStabilizationWidget::~ConfigStabilizationWidget() ConfigStabilizationWidget::~ConfigStabilizationWidget()
{ {
// Do nothing // Do nothing
} }
void ConfigStabilizationWidget::realtimeUpdatesSlot(int value)
void ConfigStabilizationWidget::refreshWidgetsValues(UAVObject *o)
{ {
m_stabilization->realTimeUpdates_6->setCheckState((Qt::CheckState)value); ConfigTaskWidget::refreshWidgetsValues(o);
if(value==Qt::Checked && !realtimeUpdates->isActive())
realtimeUpdates->start(300); ui->basicResponsivenessGroupBox->setChecked(ui->rateRollKp_3->value() == ui->ratePitchKp_4->value() &&
else if(value==Qt::Unchecked) ui->rateRollKi_3->value() == ui->ratePitchKi_4->value());
realtimeUpdates->stop();
} }
void ConfigStabilizationWidget::linkCheckBoxes(int value) void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value)
{ {
if(sender()== m_stabilization->checkBox_7) ui->realTimeUpdates_6->setChecked(value);
m_stabilization->checkBox_3->setCheckState((Qt::CheckState)value); ui->realTimeUpdates_8->setChecked(value);
else if(sender()== m_stabilization->checkBox_3) ui->realTimeUpdates_12->setChecked(value);
m_stabilization->checkBox_7->setCheckState((Qt::CheckState)value);
else if(sender()== m_stabilization->checkBox_8) if (value && !realtimeUpdates->isActive()) {
m_stabilization->checkBox_2->setCheckState((Qt::CheckState)value); realtimeUpdates->start(AUTOMATIC_UPDATE_RATE);
else if(sender()== m_stabilization->checkBox_2) qDebug() << "Instant Update timer started.";
m_stabilization->checkBox_8->setCheckState((Qt::CheckState)value); } else if (!value && realtimeUpdates->isActive()) {
realtimeUpdates->stop();
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) void ConfigStabilizationWidget::processLinkedWidgets(QWidget *widget)
{ {
if(m_stabilization->checkBox_7->checkState()==Qt::Checked) if (ui->checkBox_7->isChecked()) {
{ if (widget == ui->RateRollKp_2) {
if(widget== m_stabilization->RateRollKp_2) ui->RatePitchKp->setValue(ui->RateRollKp_2->value());
{ } else if (widget == ui->RateRollKi_2) {
m_stabilization->RatePitchKp->setValue(m_stabilization->RateRollKp_2->value()); ui->RatePitchKi->setValue(ui->RateRollKi_2->value());
} } else if (widget == ui->RateRollILimit_2) {
else if(widget== m_stabilization->RateRollKi_2) ui->RatePitchILimit->setValue(ui->RateRollILimit_2->value());
{ } else if (widget == ui->RatePitchKp) {
m_stabilization->RatePitchKi->setValue(m_stabilization->RateRollKi_2->value()); ui->RateRollKp_2->setValue(ui->RatePitchKp->value());
} } else if (widget == ui->RatePitchKi) {
else if(widget== m_stabilization->RateRollILimit_2) ui->RateRollKi_2->setValue(ui->RatePitchKi->value());
{ } else if (widget == ui->RatePitchILimit) {
m_stabilization->RatePitchILimit->setValue(m_stabilization->RateRollILimit_2->value()); ui->RateRollILimit_2->setValue(ui->RatePitchILimit->value());
} } else if (widget == ui->RollRateKd) {
else if(widget== m_stabilization->RatePitchKp) ui->PitchRateKd->setValue(ui->RollRateKd->value());
{ } else if (widget == ui->PitchRateKd) {
m_stabilization->RateRollKp_2->setValue(m_stabilization->RatePitchKp->value()); ui->RollRateKd->setValue(ui->PitchRateKd->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());
}
} }
} }
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());
}
}
}

View File

@ -46,11 +46,18 @@ public:
~ConfigStabilizationWidget(); ~ConfigStabilizationWidget();
private: private:
Ui_StabilizationWidget *m_stabilization; Ui_StabilizationWidget *ui;
QTimer * realtimeUpdates; QTimer * realtimeUpdates;
// Milliseconds between automatic 'Instant Updates'
static const int AUTOMATIC_UPDATE_RATE = 500;
protected slots:
void refreshWidgetsValues(UAVObject *o = NULL);
private slots: private slots:
void realtimeUpdatesSlot(int); void realtimeUpdatesSlot(bool value);
void linkCheckBoxes(int value); void linkCheckBoxes(bool value);
void processLinkedWidgets(QWidget*); void processLinkedWidgets(QWidget*);
}; };

View File

@ -108,9 +108,3 @@ void ConfigTxPIDWidget::saveSettings()
UAVObject *obj = HwSettings::GetInstance(getObjectManager()); UAVObject *obj = HwSettings::GetInstance(getObjectManager());
saveObjectToSD(obj); saveObjectToSD(obj);
} }
/**
@}
@}
*/

View File

@ -138,8 +138,6 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
// Connect the help pushbutton // Connect the help pushbutton
connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
enableControls(false);
refreshWidgetsValues(); refreshWidgetsValues();
// register widgets for dirty state management // register widgets for dirty state management
@ -150,8 +148,12 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
addWidget(m_aircraft->accelTime); addWidget(m_aircraft->accelTime);
addWidget(m_aircraft->decelTime); addWidget(m_aircraft->decelTime);
addWidget(m_aircraft->maxAccelSlider); addWidget(m_aircraft->maxAccelSlider);
addWidget(m_aircraft->ffTestBox1);
addWidget(m_aircraft->ffTestBox2);
addWidget(m_aircraft->ffTestBox3);
disableMouseWheelEvents(); disableMouseWheelEvents();
updateEnableControls();
} }
/** /**

View File

@ -29,11 +29,11 @@
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt; <string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt; &lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; } p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt; &lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-weight:600;&quot;&gt;Attitude / INS calibration&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;Attitude Calibration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;/p&gt; &lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;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.&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string> &lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property> </property>
</widget> </widget>
</item> </item>

View File

@ -25,15 +25,18 @@
<layout class="QVBoxLayout" name="verticalLayout_2"> <layout class="QVBoxLayout" name="verticalLayout_2">
<item> <item>
<widget class="QTextBrowser" name="textBrowser"> <widget class="QTextBrowser" name="textBrowser">
<property name="enabled">
<bool>true</bool>
</property>
<property name="html"> <property name="html">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt; <string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt; &lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; } p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&gt; &lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;Hardware Configuration&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;Hardware Configuration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;/p&gt; &lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;This panel will be updated to provide the relevant controls to let you configure your hardware once telemetry is connected and running.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;This panel will be updated to provide the relevant controls to let you configure your hardware once telemetry is connected and running.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string> &lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property> </property>
</widget> </widget>
</item> </item>

Binary file not shown.

Before

Width:  |  Height:  |  Size: 178 KiB

After

Width:  |  Height:  |  Size: 183 KiB

View File

@ -11,8 +11,7 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) :
ui->setupUi(this); ui->setupUi(this);
// The first time through the loop, keep the legend. All other times, delete it. // The first time through the loop, keep the legend. All other times, delete it.
if(!showlegend) if (!showlegend) {
{
layout()->removeWidget(ui->legend0); layout()->removeWidget(ui->legend0);
layout()->removeWidget(ui->legend1); layout()->removeWidget(ui->legend1);
layout()->removeWidget(ui->legend2); layout()->removeWidget(ui->legend2);
@ -27,7 +26,6 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) :
delete ui->legend4; delete ui->legend4;
delete ui->legend5; delete ui->legend5;
delete ui->legend6; delete ui->legend6;
} }
connect(ui->channelMin, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated())); connect(ui->channelMin, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated()));
@ -55,15 +53,16 @@ void inputChannelForm::setName(QString &name)
ui->channelName->setText(name); ui->channelName->setText(name);
QFontMetrics metrics(ui->channelName->font()); QFontMetrics metrics(ui->channelName->font());
int width = metrics.width(name) + 5; int width = metrics.width(name) + 5;
foreach(inputChannelForm * form,parent()->findChildren<inputChannelForm*>()) foreach(inputChannelForm * form, parent()->findChildren<inputChannelForm *>()) {
{ if (form == this) {
if(form==this)
continue; continue;
if(form->ui->channelName->minimumSize().width()<width) }
if (form->ui->channelName->minimumSize().width() < width) {
form->ui->channelName->setMinimumSize(width, 0); form->ui->channelName->setMinimumSize(width, 0);
else } else {
width = form->ui->channelName->minimumSize().width(); width = form->ui->channelName->minimumSize().width();
} }
}
ui->channelName->setMinimumSize(width, 0); ui->channelName->setMinimumSize(width, 0);
} }
@ -73,6 +72,7 @@ void inputChannelForm::setName(QString &name)
void inputChannelForm::minMaxUpdated() void inputChannelForm::minMaxUpdated()
{ {
bool reverse = ui->channelMin->value() > ui->channelMax->value(); bool reverse = ui->channelMin->value() > ui->channelMax->value();
if (reverse) { if (reverse) {
ui->channelNeutral->setMinimum(ui->channelMax->value()); ui->channelNeutral->setMinimum(ui->channelMax->value());
ui->channelNeutral->setMaximum(ui->channelMin->value()); ui->channelNeutral->setMaximum(ui->channelMin->value());
@ -129,8 +129,9 @@ void inputChannelForm::groupUpdated()
Q_ASSERT(0); Q_ASSERT(0);
} }
for (int i = 0; i < count; i++) for (int i = 0; i < count; i++) {
ui->channelNumberDropdown->addItem(QString(tr("Chan %1").arg(i + 1))); ui->channelNumberDropdown->addItem(QString(tr("Chan %1").arg(i + 1)));
}
ui->channelNumber->setMaximum(count); ui->channelNumber->setMaximum(count);
ui->channelNumber->setMinimum(0); ui->channelNumber->setMinimum(0);

View File

@ -43,10 +43,6 @@ MixerCurve::MixerCurve(QWidget *parent) :
m_mixerUI->SettingsGroup->hide(); 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 // create our spin delegate
m_spinDelegate = new DoubleSpinDelegate(); m_spinDelegate = new DoubleSpinDelegate();
@ -54,27 +50,19 @@ MixerCurve::MixerCurve(QWidget *parent) :
// set the default mixer type // set the default mixer type
setMixerType(MixerCurve::MIXERCURVE_THROTTLE); setMixerType(MixerCurve::MIXERCURVE_THROTTLE);
// setup and turn off advanced mode
CommandActivated();
// paint the ui // paint the ui
UpdateCurveUI(); UpdateCurveUI();
// wire up our signals // wire up our signals
connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(CurveTypeChanged())); connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(CurveTypeChanged()));
connect(m_mixerUI->ResetCurve, SIGNAL(clicked()), this, SLOT(ResetCurve())); 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_mixerUI->GenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve()));
connect(m_curve, SIGNAL(curveUpdated()), this, SLOT(UpdateSettingsTable())); 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->CurveMin, SIGNAL(valueChanged(double)), this, SLOT(CurveMinChanged(double)));
connect(m_mixerUI->CurveMax, SIGNAL(valueChanged(double)), this, SLOT(CurveMaxChanged(double))); connect(m_mixerUI->CurveMax, SIGNAL(valueChanged(double)), this, SLOT(CurveMaxChanged(double)));
connect(m_mixerUI->CurveStep, SIGNAL(valueChanged(double)), this, SLOT(GenerateCurve())); connect(m_mixerUI->CurveStep, SIGNAL(valueChanged(double)), this, SLOT(GenerateCurve()));
} }
MixerCurve::~MixerCurve() MixerCurve::~MixerCurve()
@ -103,7 +91,6 @@ void MixerCurve::setMixerType(MixerCurveType curveType)
{ {
m_mixerUI->SettingsGroup->setTitle("Pitch Curve"); m_mixerUI->SettingsGroup->setTitle("Pitch Curve");
m_curve->setRange(-1.0, 1.0); m_curve->setRange(-1.0, 1.0);
m_curve->setPositiveColor("#0000aa", "#0000aa");
m_mixerUI->CurveMin->setMinimum(-1.0); m_mixerUI->CurveMin->setMinimum(-1.0);
m_mixerUI->CurveMax->setMinimum(-1.0); m_mixerUI->CurveMax->setMinimum(-1.0);
break; break;
@ -126,15 +113,11 @@ void MixerCurve::ResetCurve()
initLinearCurve(MixerCurveWidget::NODE_NUMELEM, getCurveMax(), getCurveMin()); initLinearCurve(MixerCurveWidget::NODE_NUMELEM, getCurveMax(), getCurveMin());
m_curve->activateCommand("Linear");
UpdateSettingsTable(); UpdateSettingsTable();
} }
void MixerCurve::PopupCurve() void MixerCurve::PopupCurve()
{ {
if (!m_curve->isCommandActive("Popup")) {
m_mixerUI->SettingsGroup->show(); m_mixerUI->SettingsGroup->show();
m_mixerUI->PopupCurve->hide(); m_mixerUI->PopupCurve->hide();
@ -143,20 +126,13 @@ void MixerCurve::PopupCurve()
m_mixerUI->SettingsGroup->hide(); m_mixerUI->SettingsGroup->hide();
m_mixerUI->PopupCurve->show(); m_mixerUI->PopupCurve->show();
m_curve->showCommands(false);
}
} }
void MixerCurve::UpdateCurveUI() void MixerCurve::UpdateCurveUI()
{ {
// get the user settings // get the user settings
QString curveType = m_mixerUI->CurveType->currentText(); 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->setMinimum(0.0);
m_mixerUI->CurveStep->setMaximum(100.0); m_mixerUI->CurveStep->setMaximum(100.0);
@ -170,8 +146,7 @@ void MixerCurve::UpdateCurveUI()
m_mixerUI->stepLabel->setVisible(false); m_mixerUI->stepLabel->setVisible(false);
m_mixerUI->CurveStep->setVisible(false); m_mixerUI->CurveStep->setVisible(false);
if ( curveType.compare("Flat")==0) if (curveType.compare("Flat") == 0) {
{
m_mixerUI->minLabel->setVisible(false); m_mixerUI->minLabel->setVisible(false);
m_mixerUI->CurveMin->setVisible(false); m_mixerUI->CurveMin->setVisible(false);
m_mixerUI->stepLabel->setVisible(true); m_mixerUI->stepLabel->setVisible(true);
@ -181,13 +156,11 @@ void MixerCurve::UpdateCurveUI()
m_mixerUI->CurveStep->setSingleStep(0.01); m_mixerUI->CurveStep->setSingleStep(0.01);
m_mixerUI->CurveStep->setValue(m_mixerUI->CurveMax->value() / 2); 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->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true); m_mixerUI->CurveMax->setVisible(true);
} }
if ( curveType.compare("Step")==0) if (curveType.compare("Step") == 0) {
{
m_mixerUI->maxLabel->setVisible(true); m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true); m_mixerUI->CurveMax->setVisible(true);
m_mixerUI->stepLabel->setText("Step at"); m_mixerUI->stepLabel->setText("Step at");
@ -196,8 +169,7 @@ void MixerCurve::UpdateCurveUI()
m_mixerUI->CurveStep->setMinimum(1.0); m_mixerUI->CurveStep->setMinimum(1.0);
} }
if ( curveType.compare("Exp")==0) if (curveType.compare("Exp") == 0) {
{
m_mixerUI->maxLabel->setVisible(true); m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true); m_mixerUI->CurveMax->setVisible(true);
m_mixerUI->stepLabel->setText("Power"); m_mixerUI->stepLabel->setText("Power");
@ -206,8 +178,7 @@ void MixerCurve::UpdateCurveUI()
m_mixerUI->CurveStep->setMinimum(1.0); m_mixerUI->CurveStep->setMinimum(1.0);
} }
if ( curveType.compare("Log")==0) if (curveType.compare("Log") == 0) {
{
m_mixerUI->maxLabel->setVisible(true); m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true); m_mixerUI->CurveMax->setVisible(true);
m_mixerUI->stepLabel->setText("Power"); m_mixerUI->stepLabel->setText("Power");
@ -229,43 +200,32 @@ void MixerCurve::GenerateCurve()
double value2 = getCurveMax(); double value2 = getCurveMax();
double value3 = getCurveStep(); double value3 = getCurveStep();
m_curve->setCommandText("StepValue", QString("%0").arg(value3));
QString CurveType = m_mixerUI->CurveType->currentText(); QString CurveType = m_mixerUI->CurveType->currentText();
QList<double> points; QList<double> points;
for (int i=0; i<MixerCurveWidget::NODE_NUMELEM; i++) for (int i = 0; i < MixerCurveWidget::NODE_NUMELEM; i++) {
{
scale = ((double)i / (double)(MixerCurveWidget::NODE_NUMELEM - 1)); scale = ((double)i / (double)(MixerCurveWidget::NODE_NUMELEM - 1));
if ( CurveType.compare("Flat")==0) if (CurveType.compare("Flat") == 0) {
{
points.append(value3); points.append(value3);
} }
if ( CurveType.compare("Linear")==0) if (CurveType.compare("Linear") == 0) {
{
newValue = value1 + (scale * (value2 - value1)); newValue = value1 + (scale * (value2 - value1));
points.append(newValue); points.append(newValue);
} }
if ( CurveType.compare("Step")==0) if (CurveType.compare("Step") == 0) {
{ if (scale * 100 < value3) {
if (scale*100<value3)
{
points.append(value1); points.append(value1);
} } else {
else
{
points.append(value2); points.append(value2);
} }
} }
if ( CurveType.compare("Exp")==0) if (CurveType.compare("Exp") == 0) {
{
newValue = value1 + (((exp(scale * (value3 / 10)) - 1)) / (exp((value3 / 10)) - 1) * (value2 - value1)); newValue = value1 + (((exp(scale * (value3 / 10)) - 1)) / (exp((value3 / 10)) - 1) * (value2 - value1));
points.append(newValue); points.append(newValue);
} }
if ( CurveType.compare("Log")==0) if (CurveType.compare("Log") == 0) {
{
newValue = value1 + (((log(scale * (value3 * 2) + 1)) / (log(1 + (value3 * 2)))) * (value2 - value1)); newValue = value1 + (((log(scale * (value3 * 2) + 1)) / (log(1 + (value3 * 2)))) * (value2 - value1));
points.append(newValue); points.append(newValue);
} }
@ -282,10 +242,12 @@ void MixerCurve::initCurve (const QList<double>* points)
m_curve->setCurve(points); m_curve->setCurve(points);
UpdateSettingsTable(); UpdateSettingsTable();
} }
QList<double> MixerCurve::getCurve() QList<double> MixerCurve::getCurve()
{ {
return m_curve->getCurve(); return m_curve->getCurve();
} }
void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue) void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue)
{ {
setMin(minValue); setMin(minValue);
@ -293,42 +255,49 @@ void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue
m_curve->initLinearCurve(numPoints, maxValue, minValue); m_curve->initLinearCurve(numPoints, maxValue, minValue);
if (m_spinDelegate) if (m_spinDelegate) {
m_spinDelegate->setRange(minValue, maxValue); m_spinDelegate->setRange(minValue, maxValue);
} }
}
void MixerCurve::setCurve(const QList<double> *points) void MixerCurve::setCurve(const QList<double> *points)
{ {
m_curve->setCurve(points); m_curve->setCurve(points);
UpdateSettingsTable(); UpdateSettingsTable();
} }
void MixerCurve::setMin(double value) void MixerCurve::setMin(double value)
{ {
// m_curve->setMin(value); // m_curve->setMin(value);
m_mixerUI->CurveMin->setMinimum(value); m_mixerUI->CurveMin->setMinimum(value);
} }
double MixerCurve::getMin() double MixerCurve::getMin()
{ {
return m_curve->getMin(); return m_curve->getMin();
} }
void MixerCurve::setMax(double value) void MixerCurve::setMax(double value)
{ {
// m_curve->setMax(value); // m_curve->setMax(value);
m_mixerUI->CurveMax->setMaximum(value); m_mixerUI->CurveMax->setMaximum(value);
} }
double MixerCurve::getMax() double MixerCurve::getMax()
{ {
return m_curve->getMax(); return m_curve->getMax();
} }
double MixerCurve::setRange(double min, double max) double MixerCurve::setRange(double min, double max)
{ {
return m_curve->setRange(min, max); return m_curve->setRange(min, max);
} }
double MixerCurve::getCurveMin() double MixerCurve::getCurveMin()
{ {
return m_mixerUI->CurveMin->value(); return m_mixerUI->CurveMin->value();
} }
double MixerCurve::getCurveMax() double MixerCurve::getCurveMax()
{ {
return m_mixerUI->CurveMax->value(); return m_mixerUI->CurveMax->value();
@ -344,25 +313,25 @@ void MixerCurve::UpdateSettingsTable()
QList<double> points = m_curve->getCurve(); QList<double> points = m_curve->getCurve();
int ptCnt = points.count(); int ptCnt = points.count();
for (int i=0; i<ptCnt; i++) for (int i = 0; i < ptCnt; i++) {
{
QTableWidgetItem *item = m_settings->item(i, 0); QTableWidgetItem *item = m_settings->item(i, 0);
if (item) if (item) {
item->setText(QString().sprintf("%.2f", points.at((ptCnt - 1) - i))); item->setText(QString().sprintf("%.2f", points.at((ptCnt - 1) - i)));
} }
} }
}
void MixerCurve::SettingsTableChanged() void MixerCurve::SettingsTableChanged()
{ {
QList<double> points; QList<double> points;
for (int i=0; i < m_settings->rowCount(); i++) for (int i = 0; i < m_settings->rowCount(); i++) {
{
QTableWidgetItem *item = m_settings->item(i, 0); QTableWidgetItem *item = m_settings->item(i, 0);
if (item) if (item) {
points.push_front(item->text().toDouble()); points.push_front(item->text().toDouble());
} }
}
m_mixerUI->CurveMin->setValue(points.first()); m_mixerUI->CurveMin->setValue(points.first());
m_mixerUI->CurveMax->setValue(points.last()); m_mixerUI->CurveMax->setValue(points.last());
@ -370,59 +339,6 @@ void MixerCurve::SettingsTableChanged()
m_curve->setCurve(&points); 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() void MixerCurve::CurveTypeChanged()
{ {
// setup the ui for this curvetype // setup the ui for this curvetype
@ -455,8 +371,9 @@ void MixerCurve::showEvent(QShowEvent *event)
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(); int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount();
for (int i=0; i<m_settings->rowCount(); i++) for (int i = 0; i < m_settings->rowCount(); i++) {
m_settings->setRowHeight(i, h); m_settings->setRowHeight(i, h);
}
m_curve->showEvent(event); m_curve->showEvent(event);
} }
@ -467,8 +384,9 @@ void MixerCurve::resizeEvent(QResizeEvent* event)
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(); int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount();
for (int i=0; i<m_settings->rowCount(); i++) for (int i = 0; i < m_settings->rowCount(); i++) {
m_settings->setRowHeight(i, h); m_settings->setRowHeight(i, h);
}
m_curve->resizeEvent(event); m_curve->resizeEvent(event);
} }

View File

@ -84,7 +84,6 @@ public slots:
void UpdateSettingsTable(); void UpdateSettingsTable();
private slots: private slots:
void CommandActivated(MixerNode* node = 0);
void SettingsTableChanged(); void SettingsTableChanged();
void CurveTypeChanged(); void CurveTypeChanged();
void CurveMinChanged(double value); void CurveMinChanged(double value);

View File

@ -38,7 +38,7 @@ class OutputChannelForm : public ConfigTaskWidget
public: public:
explicit OutputChannelForm(const int index, QWidget *parent = NULL, const bool showLegend = false); explicit OutputChannelForm(const int index, QWidget *parent = NULL, const bool showLegend = false);
~OutputChannelForm(); ~OutputChannelForm();
friend class ConfigOnputWidget; friend class ConfigOutputWidget;
void setAssignment(const QString &assignment); void setAssignment(const QString &assignment);
int index() const; int index() const;
@ -57,10 +57,10 @@ signals:
void channelChanged(int index, int value); void channelChanged(int index, int value);
private: private:
Ui::outputChannelForm ui;
/// Channel index /// Channel index
int m_index; int m_index;
bool m_inChannelTest; bool m_inChannelTest;
Ui::outputChannelForm ui;
private slots: private slots:
void linkToggled(bool state); void linkToggled(bool state);

View File

@ -6,8 +6,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>720</width> <width>643</width>
<height>567</height> <height>531</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
@ -16,10 +16,16 @@
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QVBoxLayout" name="verticalLayout">
<item> <item>
<widget class="QTabWidget" name="tabWidget"> <widget class="QTabWidget" name="tabWidget">
<property name="autoFillBackground">
<bool>true</bool>
</property>
<property name="currentIndex"> <property name="currentIndex">
<number>0</number> <number>0</number>
</property> </property>
<widget class="QWidget" name="tab_2"> <widget class="QWidget" name="tab_2">
<property name="autoFillBackground">
<bool>true</bool>
</property>
<attribute name="title"> <attribute name="title">
<string>Calibration</string> <string>Calibration</string>
</attribute> </attribute>
@ -46,8 +52,8 @@
<widget class="QLabel" name="label_3"> <widget class="QLabel" name="label_3">
<property name="font"> <property name="font">
<font> <font>
<weight>75</weight> <weight>50</weight>
<bold>true</bold> <bold>false</bold>
</font> </font>
</property> </property>
<property name="text"> <property name="text">
@ -132,8 +138,8 @@
<widget class="QLabel" name="label"> <widget class="QLabel" name="label">
<property name="font"> <property name="font">
<font> <font>
<weight>75</weight> <weight>50</weight>
<bold>true</bold> <bold>false</bold>
</font> </font>
</property> </property>
<property name="text"> <property name="text">
@ -235,8 +241,8 @@ Hint: run this with engines at cruising speed.</string>
<widget class="QLabel" name="label_5"> <widget class="QLabel" name="label_5">
<property name="font"> <property name="font">
<font> <font>
<weight>75</weight> <weight>50</weight>
<bold>true</bold> <bold>false</bold>
</font> </font>
</property> </property>
<property name="text"> <property name="text">
@ -288,173 +294,6 @@ Hint: run this with engines at cruising speed.</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item>
<widget class="QFrame" name="frame_4">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_8">
<property name="margin">
<number>3</number>
</property>
<item>
<layout class="QVBoxLayout" name="gyroDriftLayout">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_11">
<item>
<widget class="QLabel" name="label_6">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>#4 Gyro temperature drift calibration</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>Temp:</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="gyroMinTemp">
<property name="font">
<font>
<pointsize>9</pointsize>
</font>
</property>
<property name="text">
<string>Min</string>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="gyroTempSlider">
<property name="toolTip">
<string>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...</string>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="tickPosition">
<enum>QSlider::TicksBelow</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="gyroMaxTemp">
<property name="font">
<font>
<pointsize>9</pointsize>
</font>
</property>
<property name="text">
<string>Max</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_7">
<item>
<widget class="QLabel" name="label_14">
<property name="text">
<string>Current drift:</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_10">
<item>
<widget class="QLabel" name="label_17">
<property name="text">
<string>Saved drift:</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<item>
<widget class="QPushButton" name="startDriftCalib">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Start gathering data for temperature drift calibration.
Avoid sudden moves once you have started gathering!</string>
</property>
<property name="text">
<string>Start</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="gyroMeasureDrift">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>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...</string>
</property>
<property name="text">
<string>Measure</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="updateDrift">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Updates the XYZ drift values into the AHRS (saves to SD)</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout> </layout>
</item> </item>
<item> <item>
@ -473,54 +312,301 @@ p, li { white-space: pre-wrap; }
&lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt; &lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt;
&lt;tr&gt; &lt;tr&gt;
&lt;td style=&quot;border: none;&quot;&gt; &lt;td style=&quot;border: none;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;Help&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;Help&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;Step #1 and #2 are really necessary. Steps #3 and #4 will help you achieve the best possible results.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Step #1 and #2 are really necessary. Step #3 will help you achieve the best possible results.&lt;/span&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt; &lt;p align=&quot;center&quot; style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;#1: Multi-Point calibration:&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;#1: Multi-Point calibration:&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;This calibration will compute the scale for all sensors on the INS. Press &amp;quot;Start&amp;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).&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;This calibration will compute the scale for all sensors on the INS. Press &amp;quot;Start&amp;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).&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt; &lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;#2: Sensor noise calibration:&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;#2: Sensor noise calibration:&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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 &amp;quot;Start&amp;quot;.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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 &amp;quot;Start&amp;quot;.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt; &lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;#3: Accelerometer bias calibration:&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;#3: Accelerometer bias calibration:&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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.&lt;/span&gt;&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;#4 Gyro temp drift calibration:&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property> </property>
</widget> </widget>
</item> </item>
</layout> </layout>
</widget> </widget>
<widget class="QWidget" name="tab"> <widget class="QWidget" name="tab">
<property name="autoFillBackground">
<bool>true</bool>
</property>
<attribute name="title"> <attribute name="title">
<string>Settings</string> <string>Settings</string>
</attribute> </attribute>
<layout class="QVBoxLayout" name="verticalLayout_6"> <layout class="QVBoxLayout" name="verticalLayout_6">
<item> <item>
<layout class="QHBoxLayout" name="ahrsSettingsLayout"> <layout class="QHBoxLayout" name="ahrsSettingsLayout">
<item> <property name="margin">
<widget class="QLabel" name="label_2"> <number>6</number>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property> </property>
<property name="text">
<string>Attitude Algorithm:</string>
</property>
</widget>
</item>
<item> <item>
<widget class="QGroupBox" name="groupBox_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Attitude Estimation Algorithm</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="0" alignment="Qt::AlignTop">
<widget class="QComboBox" name="FusionAlgorithm"> <widget class="QComboBox" name="FusionAlgorithm">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip"> <property name="toolTip">
<string>Selects the sensor integration algorithm to be used by the Revolution board.</string> <string>Selects the sensor integration algorithm to be used by the Revolution board.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="0">
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item> <item>
<spacer name="horizontalSpacer_2"> <widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Home Location</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum>
</property>
<item row="2" column="3">
<widget class="QLabel" name="label_10">
<property name="text">
<string>Gravity acceleration:</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Latitude:</string>
</property>
</widget>
</item>
<item row="2" column="5">
<widget class="QLineEdit" name="geBox">
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:HomeLocation</string>
<string>fieldname:g_e</string>
</stringlist>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="lattitudeBox">
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:HomeLocation</string>
<string>fieldname:Latitude</string>
</stringlist>
</property>
</widget>
</item>
<item row="1" column="5">
<widget class="QLineEdit" name="beBox">
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_8">
<property name="text">
<string>Altitude:</string>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QLineEdit" name="altitudeBox">
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:HomeLocation</string>
<string>fieldname:Altitude</string>
</stringlist>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="label_9">
<property name="text">
<string>Magnetic field vector:</string>
</property>
</widget>
</item>
<item row="0" column="0" colspan="6">
<widget class="QLabel" name="label_11">
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This information must be set to enable calibration the Revolution controllers sensors. &lt;br/&gt;Set home location using context menu in the map widget.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="longitudeBox">
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:HomeLocation</string>
<string>fieldname:Longitude</string>
</stringlist>
</property>
</widget>
</item>
<item row="3" column="5">
<widget class="QCheckBox" name="isSetCheckBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="text">
<string>Is Set</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:HomeLocation</string>
<string>fieldname:Set</string>
</stringlist>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_4">
<property name="text">
<string>Longitude:</string>
</property>
</widget>
</item>
<item row="5" column="5" alignment="Qt::AlignRight">
<widget class="QPushButton" name="hlClearButton">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="4" column="5">
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QGroupBox" name="groupBox_3">
<property name="title">
<string>Rotate virtual attitude relative to board</string>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="0,1,0,1,0,1,0">
<item row="0" column="1">
<widget class="QLabel" name="label_12">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QSpinBox" name="rollRotation">
<property name="minimum">
<number>-180</number>
</property>
<property name="maximum">
<number>180</number>
</property>
</widget>
</item>
<item row="1" column="4">
<spacer name="horizontalSpacer_9">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
</property> </property>
@ -532,71 +618,114 @@ p, li { white-space: pre-wrap; }
</property> </property>
</spacer> </spacer>
</item> </item>
<item> <item row="1" column="5">
<widget class="QLabel" name="label_4"> <widget class="QSpinBox" name="yawRotation">
<property name="font"> <property name="minimum">
<font> <number>-180</number>
<weight>75</weight>
<bold>true</bold>
</font>
</property> </property>
<property name="text"> <property name="maximum">
<string>Home Location:</string> <number>180</number>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="5">
<widget class="QRadioButton" name="homeLocationSet"> <widget class="QLabel" name="label_13">
<property name="enabled"> <property name="styleSheet">
<bool>false</bool> <string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property> color: rgb(255, 255, 255);
<property name="toolTip"> border-radius: 5;
<string>Saves the Home Location. This is only enabled font: bold 12px;
if the Home Location is set, i.e. if the GPS fix is margin:1px;</string>
successful.
Disabled if there is no GPS fix.</string>
</property> </property>
<property name="text"> <property name="text">
<string>Set</string> <string>Yaw</string>
</property> </property>
<property name="checked"> <property name="alignment">
<bool>true</bool> <set>Qt::AlignCenter</set>
</property> </property>
<attribute name="buttonGroup">
<string notr="true">buttonGroup</string>
</attribute>
</widget> </widget>
</item> </item>
<item> <item row="1" column="2">
<widget class="QRadioButton" name="homeLocationClear"> <spacer name="horizontalSpacer_8">
<property name="enabled"> <property name="orientation">
<bool>true</bool> <enum>Qt::Horizontal</enum>
</property> </property>
<property name="toolTip"> <property name="sizeHint" stdset="0">
<string>Clears the HomeLocation: only makes sense if you save <size>
to SD. This will force the INS to use the next GPS fix as the <width>40</width>
new home location unless it is in indoor mode.</string> <height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_15">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property> </property>
<property name="text"> <property name="text">
<string>Clear</string> <string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property> </property>
<attribute name="buttonGroup">
<string notr="true">buttonGroup</string>
</attribute>
</widget> </widget>
</item> </item>
<item row="1" column="3">
<widget class="QSpinBox" name="pitchRotation">
<property name="minimum">
<number>-90</number>
</property>
<property name="maximum">
<number>90</number>
</property>
</widget>
</item>
<item row="1" column="0">
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="6">
<spacer name="horizontalSpacer_10">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</widget>
</item> </item>
<item> <item>
<spacer name="verticalSpacer"> <spacer name="verticalSpacer">
<property name="orientation"> <property name="orientation">
<enum>Qt::Vertical</enum> <enum>Qt::Vertical</enum>
</property> </property>
<property name="sizeType">
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>20</width> <width>20</width>
<height>40</height> <height>100</height>
</size> </size>
</property> </property>
</spacer> </spacer>
@ -716,7 +845,4 @@ specific calibration button on top of the screen.</string>
<include location="../coreplugin/core.qrc"/> <include location="../coreplugin/core.qrc"/>
</resources> </resources>
<connections/> <connections/>
<buttongroups>
<buttongroup name="buttonGroup"/>
</buttongroups>
</ui> </ui>

File diff suppressed because it is too large Load Diff

View File

@ -39,8 +39,6 @@
****************************************************************************/ ****************************************************************************/
import QtQuick 1.1 import QtQuick 1.1
import QtWebKit 1.0
// This is a tabbed pane element. Add a nested Rectangle to add a tab. // This is a tabbed pane element. Add a nested Rectangle to add a tab.
TabWidget { TabWidget {

View File

@ -36,35 +36,30 @@ ScopeGadget::ScopeGadget(QString classId, ScopeGadgetWidget *widget, QWidget *pa
IUAVGadget(classId, parent), IUAVGadget(classId, parent),
m_widget(widget), m_widget(widget),
configLoaded(false) configLoaded(false)
{ {}
}
void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration *config) void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration *config)
{ {
ScopeGadgetConfiguration *sgConfig = qobject_cast<ScopeGadgetConfiguration *>(config); ScopeGadgetConfiguration *sgConfig = qobject_cast<ScopeGadgetConfiguration *>(config);
ScopeGadgetWidget *widget = qobject_cast<ScopeGadgetWidget *>(m_widget); ScopeGadgetWidget *widget = qobject_cast<ScopeGadgetWidget *>(m_widget);
widget->setXWindowSize(sgConfig->dataSize()); widget->setXWindowSize(sgConfig->dataSize());
widget->setRefreshInterval(sgConfig->refreshInterval()); widget->setRefreshInterval(sgConfig->refreshInterval());
if(sgConfig->plotType() == SequentialPlot ) if (sgConfig->plotType() == SequentialPlot) {
widget->setupSequentialPlot(); widget->setupSequentialPlot();
else if(sgConfig->plotType() == ChronoPlot) } else if (sgConfig->plotType() == ChronoPlot) {
widget->setupChronoPlot(); widget->setupChronoPlot();
// else if(sgConfig->plotType() == UAVObjectPlot) }
// widget->setupUAVObjectPlot();
foreach(PlotCurveConfiguration * plotCurveConfig, sgConfig->plotCurveConfigs()) { foreach(PlotCurveConfiguration * plotCurveConfig, sgConfig->plotCurveConfigs()) {
QString uavObject = plotCurveConfig->uavObject; QString uavObject = plotCurveConfig->uavObject;
QString uavField = plotCurveConfig->uavField; QString uavField = plotCurveConfig->uavField;
int scale = plotCurveConfig->yScalePower; int scale = plotCurveConfig->yScalePower;
int mean = plotCurveConfig->yMeanSamples; int mean = plotCurveConfig->yMeanSamples;
QString mathFunction = plotCurveConfig->mathFunction; QString mathFunction = plotCurveConfig->mathFunction;
QRgb color = plotCurveConfig->color; QRgb color = plotCurveConfig->color;
bool antialiased = plotCurveConfig->drawAntialiased;
widget->addCurvePlot( widget->addCurvePlot(
uavObject, uavObject,
uavField, uavField,
@ -72,11 +67,11 @@ void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config)
mean, mean,
mathFunction, mathFunction,
QPen(QBrush(QColor(color), Qt::SolidPattern), QPen(QBrush(QColor(color), Qt::SolidPattern),
// (qreal)2,
(qreal)1, (qreal)1,
Qt::SolidLine, Qt::SolidLine,
Qt::SquareCap, Qt::SquareCap,
Qt::BevelJoin) Qt::BevelJoin),
antialiased
); );
} }
@ -87,7 +82,6 @@ void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config)
widget->csvLoggingStop(); widget->csvLoggingStop();
widget->csvLoggingSetName(sgConfig->name()); widget->csvLoggingSetName(sgConfig->name());
widget->csvLoggingStart(); widget->csvLoggingStart();
} }
/** /**

View File

@ -38,64 +38,52 @@ ScopeGadgetConfiguration::ScopeGadgetConfiguration(QString classId, QSettings* q
int plotCurveCount = 0; int plotCurveCount = 0;
//if a saved configuration exists load it // If a saved configuration exists load it
if (qSettings != 0) { if (qSettings != 0) {
currentStreamVersion = qSettings->value("configurationStreamVersion").toUInt(); currentStreamVersion = qSettings->value("configurationStreamVersion").toUInt();
if(currentStreamVersion != m_configurationStreamVersion) if (currentStreamVersion != m_configurationStreamVersion) {
return; return;
}
m_plotType = qSettings->value("plotType").toInt(); m_plotType = qSettings->value("plotType").toInt();
m_dataSize = qSettings->value("dataSize").toInt(); m_dataSize = qSettings->value("dataSize").toInt();
m_refreshInterval = qSettings->value("refreshInterval").toInt(); m_refreshInterval = qSettings->value("refreshInterval").toInt();
plotCurveCount = qSettings->value("plotCurveCount").toInt(); plotCurveCount = qSettings->value("plotCurveCount").toInt();
for(int plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) for (int plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) {
{
QString uavObject;
QString uavField;
QRgb color;
qSettings->beginGroup(QString("plotCurve") + QString().number(plotDatasLoadIndex)); qSettings->beginGroup(QString("plotCurve") + QString().number(plotDatasLoadIndex));
PlotCurveConfiguration *plotCurveConf = new PlotCurveConfiguration(); PlotCurveConfiguration *plotCurveConf = new PlotCurveConfiguration();
uavObject = qSettings->value("uavObject").toString(); plotCurveConf->uavObject = qSettings->value("uavObject").toString();
plotCurveConf->uavObject = uavObject; plotCurveConf->uavField = qSettings->value("uavField").toString();
uavField = qSettings->value("uavField").toString(); plotCurveConf->color = qSettings->value("color").value<QRgb>();
plotCurveConf->uavField = uavField;
color = qSettings->value("color").value<QRgb>();
plotCurveConf->color = color;
plotCurveConf->yScalePower = qSettings->value("yScalePower").toInt(); plotCurveConf->yScalePower = qSettings->value("yScalePower").toInt();
plotCurveConf->mathFunction = qSettings->value("mathFunction").toString(); plotCurveConf->mathFunction = qSettings->value("mathFunction").toString();
plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples").toInt(); plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples", 1).toInt();
plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples", 1).toInt();
if (!plotCurveConf->yMeanSamples) plotCurveConf->yMeanSamples = 1; // fallback for backward compatibility with earlier versions //IS THIS STILL NECESSARY? plotCurveConf->drawAntialiased = qSettings->value("drawAntialiased", true).toBool();
plotCurveConf->yMinimum = qSettings->value("yMinimum").toDouble(); plotCurveConf->yMinimum = qSettings->value("yMinimum").toDouble();
plotCurveConf->yMaximum = qSettings->value("yMaximum").toDouble(); plotCurveConf->yMaximum = qSettings->value("yMaximum").toDouble();
m_plotCurveConfigs.append(plotCurveConf);
m_PlotCurveConfigs.append(plotCurveConf);
qSettings->endGroup(); qSettings->endGroup();
} }
m_LoggingEnabled = qSettings->value("LoggingEnabled").toBool(); m_loggingEnabled = qSettings->value("LoggingEnabled").toBool();
m_LoggingNewFileOnConnect = qSettings->value("LoggingNewFileOnConnect").toBool(); m_loggingNewFileOnConnect = qSettings->value("LoggingNewFileOnConnect").toBool();
m_LoggingPath = qSettings->value("LoggingPath").toString(); m_loggingPath = qSettings->value("LoggingPath").toString();
} }
} }
void ScopeGadgetConfiguration::clearPlotData() void ScopeGadgetConfiguration::clearPlotData()
{ {
PlotCurveConfiguration* poltCurveConfig; PlotCurveConfiguration *plotCurveConfig;
while(m_PlotCurveConfigs.size() > 0) while (m_plotCurveConfigs.size() > 0) {
{ plotCurveConfig = m_plotCurveConfigs.first();
poltCurveConfig = m_PlotCurveConfigs.first(); m_plotCurveConfigs.pop_front();
m_PlotCurveConfigs.pop_front(); delete plotCurveConfig;
delete poltCurveConfig;
} }
} }
@ -109,16 +97,16 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone()
int plotDatasLoadIndex = 0; int plotDatasLoadIndex = 0;
ScopeGadgetConfiguration *m = new ScopeGadgetConfiguration(this->classId()); ScopeGadgetConfiguration *m = new ScopeGadgetConfiguration(this->classId());
m->setPlotType(m_plotType); m->setPlotType(m_plotType);
m->setDataSize(m_dataSize); m->setDataSize(m_dataSize);
m->setMathFunctionType(m_mathFunctionType); m->setMathFunctionType(m_mathFunctionType);
m->setRefreashInterval(m_refreshInterval); m->setRefreashInterval(m_refreshInterval);
plotCurveCount = m_PlotCurveConfigs.size(); plotCurveCount = m_plotCurveConfigs.size();
for(plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) for (plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) {
{ PlotCurveConfiguration *currentPlotCurveConf = m_plotCurveConfigs.at(plotDatasLoadIndex);
PlotCurveConfiguration* currentPlotCurveConf = m_PlotCurveConfigs.at(plotDatasLoadIndex);
PlotCurveConfiguration *newPlotCurveConf = new PlotCurveConfiguration(); PlotCurveConfiguration *newPlotCurveConf = new PlotCurveConfiguration();
newPlotCurveConf->uavObject = currentPlotCurveConf->uavObject; newPlotCurveConf->uavObject = currentPlotCurveConf->uavObject;
@ -127,18 +115,16 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone()
newPlotCurveConf->yScalePower = currentPlotCurveConf->yScalePower; newPlotCurveConf->yScalePower = currentPlotCurveConf->yScalePower;
newPlotCurveConf->yMeanSamples = currentPlotCurveConf->yMeanSamples; newPlotCurveConf->yMeanSamples = currentPlotCurveConf->yMeanSamples;
newPlotCurveConf->mathFunction = currentPlotCurveConf->mathFunction; newPlotCurveConf->mathFunction = currentPlotCurveConf->mathFunction;
newPlotCurveConf->drawAntialiased = currentPlotCurveConf->drawAntialiased;
newPlotCurveConf->yMinimum = currentPlotCurveConf->yMinimum; newPlotCurveConf->yMinimum = currentPlotCurveConf->yMinimum;
newPlotCurveConf->yMaximum = currentPlotCurveConf->yMaximum; newPlotCurveConf->yMaximum = currentPlotCurveConf->yMaximum;
m->addPlotCurveConfig(newPlotCurveConf); m->addPlotCurveConfig(newPlotCurveConf);
} }
m->setLoggingEnabled(m_LoggingEnabled); m->setLoggingEnabled(m_loggingEnabled);
m->setLoggingNewFileOnConnect(m_LoggingNewFileOnConnect); m->setLoggingNewFileOnConnect(m_loggingNewFileOnConnect);
m->setLoggingPath(m_LoggingPath); m->setLoggingPath(m_loggingPath);
return m; return m;
} }
@ -148,9 +134,9 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone()
* Saves a configuration. //REDEFINES saveConfig CHILD BEHAVIOR? * Saves a configuration. //REDEFINES saveConfig CHILD BEHAVIOR?
* *
*/ */
void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const { void ScopeGadgetConfiguration::saveConfig(QSettings *qSettings) const
{
int plotCurveCount = m_PlotCurveConfigs.size(); int plotCurveCount = m_plotCurveConfigs.size();
int plotDatasLoadIndex = 0; int plotDatasLoadIndex = 0;
qSettings->setValue("configurationStreamVersion", m_configurationStreamVersion); qSettings->setValue("configurationStreamVersion", m_configurationStreamVersion);
@ -159,11 +145,10 @@ void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const {
qSettings->setValue("refreshInterval", m_refreshInterval); qSettings->setValue("refreshInterval", m_refreshInterval);
qSettings->setValue("plotCurveCount", plotCurveCount); qSettings->setValue("plotCurveCount", plotCurveCount);
for(plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) for (plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) {
{
qSettings->beginGroup(QString("plotCurve") + QString().number(plotDatasLoadIndex)); qSettings->beginGroup(QString("plotCurve") + QString().number(plotDatasLoadIndex));
PlotCurveConfiguration* plotCurveConf = m_PlotCurveConfigs.at(plotDatasLoadIndex); PlotCurveConfiguration *plotCurveConf = m_plotCurveConfigs.at(plotDatasLoadIndex);
qSettings->setValue("uavObject", plotCurveConf->uavObject); qSettings->setValue("uavObject", plotCurveConf->uavObject);
qSettings->setValue("uavField", plotCurveConf->uavField); qSettings->setValue("uavField", plotCurveConf->uavField);
qSettings->setValue("color", plotCurveConf->color); qSettings->setValue("color", plotCurveConf->color);
@ -172,22 +157,21 @@ void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const {
qSettings->setValue("yMeanSamples", plotCurveConf->yMeanSamples); qSettings->setValue("yMeanSamples", plotCurveConf->yMeanSamples);
qSettings->setValue("yMinimum", plotCurveConf->yMinimum); qSettings->setValue("yMinimum", plotCurveConf->yMinimum);
qSettings->setValue("yMaximum", plotCurveConf->yMaximum); qSettings->setValue("yMaximum", plotCurveConf->yMaximum);
qSettings->setValue("drawAntialiased", plotCurveConf->drawAntialiased);
qSettings->endGroup(); qSettings->endGroup();
} }
qSettings->setValue("LoggingEnabled", m_LoggingEnabled); qSettings->setValue("LoggingEnabled", m_loggingEnabled);
qSettings->setValue("LoggingNewFileOnConnect", m_LoggingNewFileOnConnect); qSettings->setValue("LoggingNewFileOnConnect", m_loggingNewFileOnConnect);
qSettings->setValue("LoggingPath", m_LoggingPath); qSettings->setValue("LoggingPath", m_loggingPath);
} }
void ScopeGadgetConfiguration::replacePlotCurveConfig(QList<PlotCurveConfiguration *> newPlotCurveConfigs) void ScopeGadgetConfiguration::replacePlotCurveConfig(QList<PlotCurveConfiguration *> newPlotCurveConfigs)
{ {
clearPlotData(); clearPlotData();
m_PlotCurveConfigs.append(newPlotCurveConfigs); m_plotCurveConfigs.append(newPlotCurveConfigs);
} }
ScopeGadgetConfiguration::~ScopeGadgetConfiguration() ScopeGadgetConfiguration::~ScopeGadgetConfiguration()

View File

@ -35,8 +35,7 @@
using namespace Core; using namespace Core;
struct PlotCurveConfiguration struct PlotCurveConfiguration {
{
QString uavObject; QString uavObject;
QString uavField; QString uavField;
int yScalePower; // This is the power to which each value must be raised int yScalePower; // This is the power to which each value must be raised
@ -45,10 +44,10 @@ struct PlotCurveConfiguration
QString mathFunction; QString mathFunction;
double yMinimum; double yMinimum;
double yMaximum; double yMaximum;
bool drawAntialiased;
}; };
class ScopeGadgetConfiguration : public IUAVGadgetConfiguration class ScopeGadgetConfiguration : public IUAVGadgetConfiguration {
{
Q_OBJECT Q_OBJECT
public: public:
explicit ScopeGadgetConfiguration(QString classId, QSettings *qSettings = 0, QObject *parent = 0); explicit ScopeGadgetConfiguration(QString classId, QSettings *qSettings = 0, QObject *parent = 0);
@ -56,45 +55,97 @@ public:
~ScopeGadgetConfiguration(); ~ScopeGadgetConfiguration();
// configuration setter functions // configuration setter functions
void setPlotType(int value){m_plotType = value;} void setPlotType(int value)
void setMathFunctionType(int value){m_mathFunctionType = value;} {
void setDataSize(int value){m_dataSize = value;} m_plotType = value;
void setRefreashInterval(int value){m_refreshInterval = value;} }
void addPlotCurveConfig(PlotCurveConfiguration* value){m_PlotCurveConfigs.append(value);} void setMathFunctionType(int value)
void replacePlotCurveConfig(QList<PlotCurveConfiguration*> m_PlotCurveConfigs); {
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<PlotCurveConfiguration *> m_plotCurveConfigs);
//configurations getter functions // Configurations getter functions
int plotType(){return m_plotType;} int plotType()
int mathFunctionType(){return m_mathFunctionType;} {
int dataSize(){return m_dataSize;} return m_plotType;
int refreshInterval(){return m_refreshInterval;} }
QList<PlotCurveConfiguration*> plotCurveConfigs(){return m_PlotCurveConfigs;} int mathFunctionType()
{
return m_mathFunctionType;
}
int dataSize()
{
return m_dataSize;
}
int refreshInterval()
{
return m_refreshInterval;
}
QList<PlotCurveConfiguration *> 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(); IUAVGadgetConfiguration *clone();
bool getLoggingEnabled(){return m_LoggingEnabled;}; bool getLoggingEnabled()
bool getLoggingNewFileOnConnect(){return m_LoggingNewFileOnConnect;}; {
QString getLoggingPath(){return m_LoggingPath;}; return m_loggingEnabled;
void setLoggingEnabled(bool value){m_LoggingEnabled=value;}; }
void setLoggingNewFileOnConnect(bool value){m_LoggingNewFileOnConnect=value;}; bool getLoggingNewFileOnConnect()
void setLoggingPath(QString value){m_LoggingPath=value;}; {
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: 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. // 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 static const uint m_configurationStreamVersion = 1000;
int m_dataSize; //The size of the data buffer to render in the curve plot // The type of the plot
int m_refreshInterval; //The interval to replot the curve widget. The data buffer is refresh as the data comes in. int m_plotType;
int m_mathFunctionType; //The type of math function to be used in the scope analysis // The size of the data buffer to render in the curve plot
QList<PlotCurveConfiguration*> m_PlotCurveConfigs; 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<PlotCurveConfiguration *> m_plotCurveConfigs;
void clearPlotData(); void clearPlotData();
bool m_LoggingEnabled; bool m_loggingEnabled;
bool m_LoggingNewFileOnConnect; bool m_loggingNewFileOnConnect;
QString m_LoggingPath; QString m_loggingPath;
}; };
#endif // SCOPEGADGETCONFIGURATION_H #endif // SCOPEGADGETCONFIGURATION_H

View File

@ -73,8 +73,9 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent)
options_page->mathFunctionComboBox->addItem("Boxcar average"); options_page->mathFunctionComboBox->addItem("Boxcar average");
options_page->mathFunctionComboBox->addItem("Standard deviation"); 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()); on_cmbUAVObjects_currentIndexChanged(options_page->cmbUAVObjects->currentText());
}
options_page->cmbScale->addItem("10^-9", -9); options_page->cmbScale->addItem("10^-9", -9);
options_page->cmbScale->addItem("10^-6", -6); options_page->cmbScale->addItem("10^-6", -6);
@ -102,19 +103,20 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent)
// add the configured curves // add the configured curves
foreach(PlotCurveConfiguration * plotData, m_config->plotCurveConfigs()) { foreach(PlotCurveConfiguration * plotData, m_config->plotCurveConfigs()) {
QString uavObject = plotData->uavObject; QString uavObject = plotData->uavObject;
QString uavField = plotData->uavField; QString uavField = plotData->uavField;
int scale = plotData->yScalePower; int scale = plotData->yScalePower;
int mean = plotData->yMeanSamples; int mean = plotData->yMeanSamples;
QString mathFunction = plotData->mathFunction; QString mathFunction = plotData->mathFunction;
QVariant varColor = plotData->color; 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); options_page->lstCurves->setCurrentRow(0, QItemSelectionModel::ClearAndSelect);
}
connect(options_page->btnAddCurve, SIGNAL(clicked()), this, SLOT(on_btnAddCurve_clicked())); 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->btnRemoveCurve, SIGNAL(clicked()), this, SLOT(on_btnRemoveCurve_clicked()));
@ -148,36 +150,35 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent)
sp->installEventFilter(this); sp->installEventFilter(this);
} }
return optionsPageWidget; return optionsPageWidget;
} }
bool ScopeGadgetOptionsPage::eventFilter( QObject * obj, QEvent * evt ) { bool ScopeGadgetOptionsPage::eventFilter(QObject *obj, QEvent *evt)
{
// Filter all wheel events, and ignore them // Filter all wheel events, and ignore them
if (evt->type() == QEvent::Wheel && if (evt->type() == QEvent::Wheel &&
(qobject_cast<QAbstractSpinBox *>(obj) || (qobject_cast<QAbstractSpinBox *>(obj) ||
qobject_cast<QComboBox *>(obj) || qobject_cast<QComboBox *>(obj) ||
qobject_cast<QAbstractSlider*>( obj ) )) qobject_cast<QAbstractSlider *>(obj))) {
{
evt->ignore(); evt->ignore();
return true; return true;
} }
return ScopeGadgetOptionsPage::eventFilter(obj, evt); return ScopeGadgetOptionsPage::eventFilter(obj, evt);
} }
void ScopeGadgetOptionsPage::on_mathFunctionComboBox_currentIndexChanged(int currentIndex){ void ScopeGadgetOptionsPage::on_mathFunctionComboBox_currentIndexChanged(int currentIndex)
{
if (currentIndex > 0) { if (currentIndex > 0) {
options_page->spnMeanSamples->setEnabled(true); options_page->spnMeanSamples->setEnabled(true);
} } else {
else{
options_page->spnMeanSamples->setEnabled(false); options_page->spnMeanSamples->setEnabled(false);
} }
} }
void ScopeGadgetOptionsPage::on_btnColor_clicked() void ScopeGadgetOptionsPage::on_btnColor_clicked()
{ {
QColor color = QColorDialog::getColor(QColor(options_page->btnColor->text())); QColor color = QColorDialog::getColor(QColor(options_page->btnColor->text()));
if (color.isValid()) { if (color.isValid()) {
setButtonColor(color); setButtonColor(color);
} }
@ -192,8 +193,9 @@ void ScopeGadgetOptionsPage::setYAxisWidgetFromPlotCurve()
bool parseOK = false; bool parseOK = false;
QListWidgetItem *listItem = options_page->lstCurves->currentItem(); QListWidgetItem *listItem = options_page->lstCurves->currentItem();
if(listItem == 0) if (listItem == 0) {
return; return;
}
// WHAT IS UserRole DOING? // WHAT IS UserRole DOING?
int currentIndex = options_page->cmbUAVObjects->findText(listItem->data(Qt::UserRole + 0).toString()); int currentIndex = options_page->cmbUAVObjects->findText(listItem->data(Qt::UserRole + 0).toString());
@ -211,12 +213,14 @@ void ScopeGadgetOptionsPage::setYAxisWidgetFromPlotCurve()
setButtonColor(QColor((QRgb)rgb)); setButtonColor(QColor((QRgb)rgb));
int mean = listItem->data(Qt::UserRole + 4).toInt(&parseOK); int mean = listItem->data(Qt::UserRole + 4).toInt(&parseOK);
if(!parseOK) mean = 1; if (!parseOK) {
mean = 1;
}
options_page->spnMeanSamples->setValue(mean); 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->mathFunctionComboBox->setCurrentIndex(currentIndex);
options_page->drawAntialiasedCheckBox->setChecked(listItem->data(Qt::UserRole + 6).toBool());
} }
void ScopeGadgetOptionsPage::setButtonColor(const QColor &color) void ScopeGadgetOptionsPage::setButtonColor(const QColor &color)
@ -237,25 +241,24 @@ void ScopeGadgetOptionsPage::on_cmbUAVObjects_currentIndexChanged(QString val)
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>(); UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(objManager->getObject(val)); UAVDataObject *obj = dynamic_cast<UAVDataObject *>(objManager->getObject(val));
if (obj == NULL) if (obj == NULL) {
return; // Rare case: the config contained a UAVObject name which does not exist anymore. return; // Rare case: the config contained a UAVObject name which does not exist anymore.
}
QList<UAVObjectField *> fieldList = obj->getFields(); QList<UAVObjectField *> fieldList = obj->getFields();
foreach(UAVObjectField * field, fieldList) { foreach(UAVObjectField * field, fieldList) {
if(field->getType() == UAVObjectField::STRING || field->getType() == UAVObjectField::ENUM ) if (field->getType() == UAVObjectField::STRING || field->getType() == UAVObjectField::ENUM) {
continue; continue;
}
if(field->getElementNames().count() > 1) if (field->getElementNames().count() > 1) {
{ foreach(QString elemName, field->getElementNames()) {
foreach(QString elemName , field->getElementNames())
{
options_page->cmbUAVField->addItem(field->getName() + "-" + elemName); options_page->cmbUAVField->addItem(field->getName() + "-" + elemName);
} }
} } else {
else
options_page->cmbUAVField->addItem(field->getName()); options_page->cmbUAVField->addItem(field->getName());
} }
} }
}
/** /**
* Called when the user presses apply or OK. * Called when the user presses apply or OK.
@ -281,22 +284,25 @@ void ScopeGadgetOptionsPage::apply()
newPlotCurveConfigs->uavObject = listItem->data(Qt::UserRole + 0).toString(); newPlotCurveConfigs->uavObject = listItem->data(Qt::UserRole + 0).toString();
newPlotCurveConfigs->uavField = listItem->data(Qt::UserRole + 1).toString(); newPlotCurveConfigs->uavField = listItem->data(Qt::UserRole + 1).toString();
newPlotCurveConfigs->yScalePower = listItem->data(Qt::UserRole + 2).toInt(&parseOK); newPlotCurveConfigs->yScalePower = listItem->data(Qt::UserRole + 2).toInt(&parseOK);
if(!parseOK) if (!parseOK) {
newPlotCurveConfigs->yScalePower = 0; newPlotCurveConfigs->yScalePower = 0;
}
QVariant varColor = listItem->data(Qt::UserRole + 3); QVariant varColor = listItem->data(Qt::UserRole + 3);
int rgb = varColor.toInt(&parseOK); int rgb = varColor.toInt(&parseOK);
if(!parseOK) if (!parseOK) {
newPlotCurveConfigs->color = QColor(Qt::black).rgb(); newPlotCurveConfigs->color = QColor(Qt::black).rgb();
else } else {
newPlotCurveConfigs->color = (QRgb)rgb; newPlotCurveConfigs->color = (QRgb)rgb;
}
newPlotCurveConfigs->yMeanSamples = listItem->data(Qt::UserRole + 4).toInt(&parseOK); newPlotCurveConfigs->yMeanSamples = listItem->data(Qt::UserRole + 4).toInt(&parseOK);
if(!parseOK) if (!parseOK) {
newPlotCurveConfigs->yMeanSamples = 1; 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); plotCurveConfigs.append(newPlotCurveConfigs);
} }
@ -307,7 +313,6 @@ void ScopeGadgetOptionsPage::apply()
m_config->setLoggingPath(options_page->LoggingPath->path()); m_config->setLoggingPath(options_page->LoggingPath->path());
m_config->setLoggingNewFileOnConnect(options_page->LoggingConnect->isChecked()); m_config->setLoggingNewFileOnConnect(options_page->LoggingConnect->isChecked());
m_config->setLoggingEnabled(options_page->LoggingEnable->isChecked()); m_config->setLoggingEnabled(options_page->LoggingEnable->isChecked());
} }
/*! /*!
@ -320,8 +325,9 @@ void ScopeGadgetOptionsPage::on_btnAddCurve_clicked()
QString uavField = options_page->cmbUAVField->currentText(); QString uavField = options_page->cmbUAVField->currentText();
int scale = options_page->cmbScale->itemData(options_page->cmbScale->currentIndex()).toInt(&parseOK); int scale = options_page->cmbScale->itemData(options_page->cmbScale->currentIndex()).toInt(&parseOK);
if(!parseOK) if (!parseOK) {
scale = 0; scale = 0;
}
int mean = options_page->spnMeanSamples->value(); int mean = options_page->spnMeanSamples->value();
QString mathFunction = options_page->mathFunctionComboBox->currentText(); QString mathFunction = options_page->mathFunctionComboBox->currentText();
@ -329,41 +335,40 @@ void ScopeGadgetOptionsPage::on_btnAddCurve_clicked()
QVariant varColor = (int)QColor(options_page->btnColor->text()).rgb(); QVariant varColor = (int)QColor(options_page->btnColor->text()).rgb();
bool antialiased = options_page->drawAntialiasedCheckBox->isChecked();
// Find an existing plot curve config based on the uavobject and uav field. If it // Find an existing plot curve config based on the uavobject and uav field. If it
// exists, update it, else add a new one. // exists, update it, else add a new one.
if (options_page->lstCurves->count() && if (options_page->lstCurves->count() &&
options_page->lstCurves->currentItem()->text() == uavObject + "." + uavField) options_page->lstCurves->currentItem()->text() == uavObject + "." + uavField) {
{
QListWidgetItem *listWidgetItem = options_page->lstCurves->currentItem(); QListWidgetItem *listWidgetItem = options_page->lstCurves->currentItem();
setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,mean,mathFunction,varColor); setCurvePlotProperties(listWidgetItem, uavObject, uavField, scale, mean, mathFunction, varColor, antialiased);
}else } else {
{ addPlotCurveConfig(uavObject, uavField, scale, mean, mathFunction, varColor, antialiased);
addPlotCurveConfig(uavObject,uavField,scale,mean,mathFunction,varColor);
options_page->lstCurves->setCurrentRow(options_page->lstCurves->count() - 1); 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 // Add a new curve config to the list
QString listItemDisplayText = uavObject + "." + uavField; QString listItemDisplayText = uavObject + "." + uavField;
options_page->lstCurves->addItem(listItemDisplayText); options_page->lstCurves->addItem(listItemDisplayText);
QListWidgetItem *listWidgetItem = options_page->lstCurves->item(options_page->lstCurves->count() - 1); 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; bool parseOK = false;
// Set the properties of the newly added list item // Set the properties of the newly added list item
QString listItemDisplayText = uavObject + "." + uavField;
QRgb rgbColor = (QRgb)varColor.toInt(&parseOK); QRgb rgbColor = (QRgb)varColor.toInt(&parseOK);
QColor color = QColor(rgbColor); QColor color = QColor(rgbColor);
//listWidgetItem->setText(listItemDisplayText);
listWidgetItem->setTextColor(color); listWidgetItem->setTextColor(color);
// Store some additional data for the plot curve on the list item // Store some additional data for the plot curve on the list item
@ -373,6 +378,7 @@ void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetI
listWidgetItem->setData(Qt::UserRole + 3, varColor); listWidgetItem->setData(Qt::UserRole + 3, varColor);
listWidgetItem->setData(Qt::UserRole + 4, QVariant(mean)); listWidgetItem->setData(Qt::UserRole + 4, QVariant(mean));
listWidgetItem->setData(Qt::UserRole + 5, QVariant(mathFunction)); listWidgetItem->setData(Qt::UserRole + 5, QVariant(mathFunction));
listWidgetItem->setData(Qt::UserRole + 6, QVariant(antialias));
} }
/*! /*!
@ -384,9 +390,7 @@ void ScopeGadgetOptionsPage::on_btnRemoveCurve_clicked()
} }
void ScopeGadgetOptionsPage::finish() 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.
@ -400,10 +404,10 @@ void ScopeGadgetOptionsPage::on_lstCurves_currentRowChanged(int currentRow)
void ScopeGadgetOptionsPage::on_loggingEnable_clicked() void ScopeGadgetOptionsPage::on_loggingEnable_clicked()
{ {
bool en = options_page->LoggingEnable->isChecked(); bool en = options_page->LoggingEnable->isChecked();
options_page->LoggingPath->setEnabled(en); options_page->LoggingPath->setEnabled(en);
options_page->LoggingConnect->setEnabled(en); options_page->LoggingConnect->setEnabled(en);
options_page->LoggingLabel->setEnabled(en); options_page->LoggingLabel->setEnabled(en);
} }
void ScopeGadgetOptionsPage::on_spnRefreshInterval_valueChanged(int) void ScopeGadgetOptionsPage::on_spnRefreshInterval_valueChanged(int)
@ -415,6 +419,7 @@ void ScopeGadgetOptionsPage::validateRefreshInterval()
{ {
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>(); UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
for (int iIndex = 0; iIndex < options_page->lstCurves->count(); iIndex++) { for (int iIndex = 0; iIndex < options_page->lstCurves->count(); iIndex++) {
QListWidgetItem *listItem = options_page->lstCurves->item(iIndex); QListWidgetItem *listItem = options_page->lstCurves->item(iIndex);
@ -426,8 +431,7 @@ void ScopeGadgetOptionsPage::validateRefreshInterval()
continue; 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."); options_page->lblWarnings->setText("The refresh interval is faster than some or all telemetry objects.");
return; return;
} }
@ -435,4 +439,3 @@ void ScopeGadgetOptionsPage::validateRefreshInterval()
options_page->lblWarnings->setText(""); options_page->lblWarnings->setText("");
} }

View File

@ -38,22 +38,19 @@
#include <QDebug> #include <QDebug>
#include <QtGui/QColorDialog> #include <QtGui/QColorDialog>
namespace Core namespace Core {
{
class IUAVGadgetConfiguration; class IUAVGadgetConfiguration;
} }
class ScopeGadgetConfiguration; class ScopeGadgetConfiguration;
namespace Ui namespace Ui {
{
class ScopeGadgetOptionsPage; class ScopeGadgetOptionsPage;
} }
using namespace Core; using namespace Core;
class ScopeGadgetOptionsPage : public IOptionsPage class ScopeGadgetOptionsPage : public IOptionsPage {
{
Q_OBJECT Q_OBJECT
public: public:
explicit ScopeGadgetOptionsPage(ScopeGadgetConfiguration *config, QObject *parent = 0); explicit ScopeGadgetOptionsPage(ScopeGadgetConfiguration *config, QObject *parent = 0);
@ -66,8 +63,9 @@ private:
Ui::ScopeGadgetOptionsPage *options_page; Ui::ScopeGadgetOptionsPage *options_page;
ScopeGadgetConfiguration *m_config; ScopeGadgetConfiguration *m_config;
void addPlotCurveConfig(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); void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, int mean,
QString mathFunction, QVariant varColor, bool antialias);
void setYAxisWidgetFromPlotCurve(); void setYAxisWidgetFromPlotCurve();
void setButtonColor(const QColor &color); void setButtonColor(const QColor &color);
void validateRefreshInterval(); void validateRefreshInterval();
@ -82,7 +80,6 @@ private slots:
void on_btnColor_clicked(); void on_btnColor_clicked();
void on_mathFunctionComboBox_currentIndexChanged(int currentIndex); void on_mathFunctionComboBox_currentIndexChanged(int currentIndex);
void on_loggingEnable_clicked(); void on_loggingEnable_clicked();
}; };
#endif // SCOPEGADGETOPTIONSPAGE_H #endif // SCOPEGADGETOPTIONSPAGE_H

View File

@ -176,38 +176,18 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="9" column="0"> <item row="7" column="0">
<widget class="QLabel" name="label_3"> <widget class="QLabel" name="mathFunctionLabel">
<property name="text"> <property name="text">
<string>Color:</string> <string>Math function:</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="9" column="1"> <item row="7" column="1">
<widget class="QPushButton" name="btnColor"> <widget class="QComboBox" name="mathFunctionComboBox">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
</property> </property>
<property name="text">
<string>Choose</string>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QLabel" name="label_6">
<property name="text">
<string>Y-axis scale factor:</string>
</property>
</widget>
</item>
<item row="10" column="1">
<widget class="QComboBox" name="cmbScale">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="editable">
<bool>false</bool>
</property>
</widget> </widget>
</item> </item>
<item row="8" column="0"> <item row="8" column="0">
@ -248,18 +228,51 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="7" column="0"> <item row="9" column="0">
<widget class="QLabel" name="mathFunctionLabel"> <widget class="QLabel" name="label_3">
<property name="text"> <property name="text">
<string>Math function:</string> <string>Color:</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="7" column="1"> <item row="9" column="1">
<widget class="QComboBox" name="mathFunctionComboBox"> <widget class="QPushButton" name="btnColor">
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
</property> </property>
<property name="text">
<string>Choose</string>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QLabel" name="label_6">
<property name="text">
<string>Y-axis scale factor:</string>
</property>
</widget>
</item>
<item row="10" column="1">
<widget class="QComboBox" name="cmbScale">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="editable">
<bool>false</bool>
</property>
</widget>
</item>
<item row="11" column="1">
<widget class="QCheckBox" name="drawAntialiasedCheckBox">
<property name="toolTip">
<string>Check this to have the curve drawn antialiased.</string>
</property>
<property name="text">
<string>Draw Antialiased</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget> </widget>
</item> </item>
</layout> </layout>
@ -277,7 +290,7 @@
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>20</width> <width>20</width>
<height>100</height> <height>40</height>
</size> </size>
</property> </property>
</spacer> </spacer>
@ -288,8 +301,7 @@
<string>Add a new curve to the scope, or update it if the UAVObject and UAVField is the same.</string> <string>Add a new curve to the scope, or update it if the UAVObject and UAVField is the same.</string>
</property> </property>
<property name="text"> <property name="text">
<string>Add <string>Add / Update</string>
Update</string>
</property> </property>
</widget> </widget>
</item> </item>
@ -299,8 +311,7 @@ Update</string>
<string>Remove the curve from the scope.</string> <string>Remove the curve from the scope.</string>
</property> </property>
<property name="text"> <property name="text">
<string>Remove <string>Remove</string>
</string>
</property> </property>
</widget> </widget>
</item> </item>
@ -310,12 +321,12 @@ Update</string>
<enum>Qt::Vertical</enum> <enum>Qt::Vertical</enum>
</property> </property>
<property name="sizeType"> <property name="sizeType">
<enum>QSizePolicy::Fixed</enum> <enum>QSizePolicy::Expanding</enum>
</property> </property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>20</width> <width>20</width>
<height>15</height> <height>40</height>
</size> </size>
</property> </property>
</spacer> </spacer>
@ -331,8 +342,8 @@ Update</string>
</property> </property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>0</width> <width>20</width>
<height>200</height> <height>40</height>
</size> </size>
</property> </property>
</spacer> </spacer>
@ -347,6 +358,19 @@ Update</string>
</property> </property>
</widget> </widget>
</item> </item>
<item>
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</item> </item>
</layout> </layout>

View File

@ -91,8 +91,7 @@ ScopeGadgetWidget::ScopeGadgetWidget(QWidget *parent) : QwtPlot(parent)
ScopeGadgetWidget::~ScopeGadgetWidget() ScopeGadgetWidget::~ScopeGadgetWidget()
{ {
if (replotTimer) if (replotTimer) {
{
replotTimer->stop(); replotTimer->stop();
delete replotTimer; delete replotTimer;
@ -102,9 +101,9 @@ ScopeGadgetWidget::~ScopeGadgetWidget()
// Get the object to de-monitor // Get the object to de-monitor
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>(); UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
foreach (QString uavObjName, m_connectedUAVObjects) foreach(QString uavObjName, m_connectedUAVObjects) {
{
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(objManager->getObject(uavObjName)); UAVDataObject *obj = dynamic_cast<UAVDataObject *>(objManager->getObject(uavObjName));
disconnect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(uavObjectReceived(UAVObject *))); disconnect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(uavObjectReceived(UAVObject *)));
} }
@ -127,10 +126,11 @@ void ScopeGadgetWidget::mouseDoubleClickEvent(QMouseEvent *e)
{ {
// On double-click, toggle legend // On double-click, toggle legend
mutex.lock(); mutex.lock();
if (legend()) if (legend()) {
deleteLegend(); deleteLegend();
else } else {
addLegend(); addLegend();
}
mutex.unlock(); mutex.unlock();
// On double-click, reset plot zoom // On double-click, reset plot zoom
@ -150,8 +150,8 @@ void ScopeGadgetWidget::wheelEvent(QWheelEvent *e)
{ {
// Change zoom on scroll wheel event // Change zoom on scroll wheel event
QwtInterval yInterval = axisInterval(QwtPlot::yLeft); 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)
{ 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 // 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 // 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. // does *not*. Thus, when zooming with a legend, there will always be a small bias error.
@ -167,8 +167,7 @@ void ScopeGadgetWidget::wheelEvent(QWheelEvent *e)
setAxisScale(QwtPlot::yLeft, setAxisScale(QwtPlot::yLeft,
(yInterval.minValue() - zoomLine) * zoomScale + zoomLine, (yInterval.minValue() - zoomLine) * zoomScale + zoomLine,
(yInterval.maxValue() - zoomLine) * zoomScale + zoomLine); (yInterval.maxValue() - zoomLine) * zoomScale + zoomLine);
} } else {
else{
setAxisScale(QwtPlot::yLeft, setAxisScale(QwtPlot::yLeft,
(yInterval.minValue() - zoomLine) / zoomScale + zoomLine, (yInterval.minValue() - zoomLine) / zoomScale + zoomLine,
(yInterval.maxValue() - zoomLine) / zoomScale + zoomLine); (yInterval.maxValue() - zoomLine) / zoomScale + zoomLine);
@ -178,30 +177,40 @@ void ScopeGadgetWidget::wheelEvent(QWheelEvent *e)
QwtPlot::wheelEvent(e); QwtPlot::wheelEvent(e);
} }
void ScopeGadgetWidget::showEvent(QShowEvent *e)
{
replotNewData();
QwtPlot::showEvent(e);
}
/** /**
* Starts/stops telemetry * Starts/stops telemetry
*/ */
void ScopeGadgetWidget::startPlotting() void ScopeGadgetWidget::startPlotting()
{ {
if (!replotTimer) if (!replotTimer) {
return; return;
}
if (!replotTimer->isActive()) if (!replotTimer->isActive()) {
replotTimer->start(m_refreshInterval); replotTimer->start(m_refreshInterval);
} }
}
void ScopeGadgetWidget::stopPlotting() void ScopeGadgetWidget::stopPlotting()
{ {
if (!replotTimer) if (!replotTimer) {
return; return;
}
replotTimer->stop(); replotTimer->stop();
} }
void ScopeGadgetWidget::deleteLegend() void ScopeGadgetWidget::deleteLegend()
{ {
if (!legend()) if (!legend()) {
return; return;
}
disconnect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, 0); disconnect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, 0);
@ -211,8 +220,9 @@ void ScopeGadgetWidget::deleteLegend()
void ScopeGadgetWidget::addLegend() void ScopeGadgetWidget::addLegend()
{ {
if (legend()) if (legend()) {
return; return;
}
// Show a legend at the top // Show a legend at the top
QwtLegend *legend = new QwtLegend(); QwtLegend *legend = new QwtLegend();
@ -242,9 +252,11 @@ void ScopeGadgetWidget::addLegend()
foreach(QwtPlotItem * item, this->itemList()) { foreach(QwtPlotItem * item, this->itemList()) {
bool on = item->isVisible(); bool on = item->isVisible();
QWidget *w = legend->find(item); QWidget *w = legend->find(item);
if ( w && w->inherits("QwtLegendItem") )
if (w && w->inherits("QwtLegendItem")) {
((QwtLegendItem *)w)->setChecked(!on); ((QwtLegendItem *)w)->setChecked(!on);
} }
}
connect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, SLOT(showCurve(QwtPlotItem *, bool))); connect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, SLOT(showCurve(QwtPlotItem *, bool)));
} }
@ -281,21 +293,22 @@ void ScopeGadgetWidget::preparePlot(PlotType plotType)
// Only start the timer if we are already connected // Only start the timer if we are already connected
Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager();
if (cm->getCurrentConnection() && replotTimer) if (cm->getCurrentConnection() && replotTimer) {
{ if (!replotTimer->isActive()) {
if (!replotTimer->isActive())
replotTimer->start(m_refreshInterval); replotTimer->start(m_refreshInterval);
else } else {
replotTimer->setInterval(m_refreshInterval); replotTimer->setInterval(m_refreshInterval);
} }
} }
}
void ScopeGadgetWidget::showCurve(QwtPlotItem *item, bool on) void ScopeGadgetWidget::showCurve(QwtPlotItem *item, bool on)
{ {
item->setVisible(!on); item->setVisible(!on);
QWidget *w = legend()->find(item); QWidget *w = legend()->find(item);
if ( w && w->inherits("QwtLegendItem") ) if (w && w->inherits("QwtLegendItem")) {
((QwtLegendItem *)w)->setChecked(on); ((QwtLegendItem *)w)->setChecked(on);
}
mutex.lock(); mutex.lock();
replot(); replot();
@ -385,14 +398,15 @@ void ScopeGadgetWidget::setupChronoPlot()
// scaleWidget->setMinBorderDist(0, fmw); // 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); plotData = new SequentialPlotData(uavObject, uavFieldSubField);
else if (m_plotType == ChronoPlot) } else if (m_plotType == ChronoPlot) {
plotData = new ChronoPlotData(uavObject, uavFieldSubField); plotData = new ChronoPlotData(uavObject, uavFieldSubField);
}
// else if (m_plotType == UAVObjectPlot) // else if (m_plotType == UAVObjectPlot)
// plotData = new UAVObjectPlotData(uavObject, uavField); // plotData = new UAVObjectPlotData(uavObject, uavField);
@ -402,15 +416,15 @@ void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField
plotData->mathFunction = mathFunction; plotData->mathFunction = mathFunction;
// If the y-bounds are supplied, set them // If the y-bounds are supplied, set them
if (plotData->yMinimum != plotData->yMaximum) if (plotData->yMinimum != plotData->yMaximum) {
{
setAxisScale(QwtPlot::yLeft, plotData->yMinimum, plotData->yMaximum); setAxisScale(QwtPlot::yLeft, plotData->yMinimum, plotData->yMaximum);
} }
// Create the curve // Create the curve
QString curveName = (plotData->uavObject) + "." + (plotData->uavField); QString curveName = (plotData->uavObject) + "." + (plotData->uavField);
if(plotData->haveSubField) if (plotData->haveSubField) {
curveName = curveName.append("." + plotData->uavSubField); curveName = curveName.append("." + plotData->uavSubField);
}
// Get the uav object // Get the uav object
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
@ -427,16 +441,23 @@ void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField
} }
QString units = field->getUnits(); QString units = field->getUnits();
if(units == 0) if (units == 0) {
units = QString(); units = QString();
}
QString curveNameScaled; QString curveNameScaled;
if(scaleOrderFactor == 0) if (scaleOrderFactor == 0) {
curveNameScaled = curveName + " (" + units + ")"; curveNameScaled = curveName + " (" + units + ")";
else } else {
curveNameScaled = curveName + " (x10^" + QString::number(scaleOrderFactor) + " " + units + ")"; curveNameScaled = curveName + " (x10^" + QString::number(scaleOrderFactor) + " " + units + ")";
}
QwtPlotCurve *plotCurve = new QwtPlotCurve(curveNameScaled); QwtPlotCurve *plotCurve = new QwtPlotCurve(curveNameScaled);
if (antialiased) {
plotCurve->setRenderHint(QwtPlotCurve::RenderAntialiased);
}
plotCurve->setPen(pen); plotCurve->setPen(pen);
plotCurve->setSamples(*plotData->xData, *plotData->yData); plotCurve->setSamples(*plotData->xData, *plotData->yData);
plotCurve->attach(this); plotCurve->attach(this);
@ -475,17 +496,21 @@ void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField
void ScopeGadgetWidget::uavObjectReceived(UAVObject *obj) void ScopeGadgetWidget::uavObjectReceived(UAVObject *obj)
{ {
foreach(PlotData * plotData, m_curvesData.values()) { foreach(PlotData * plotData, m_curvesData.values()) {
if (plotData->append(obj)) m_csvLoggingDataUpdated=1; if (plotData->append(obj)) {
m_csvLoggingDataUpdated = 1;
}
} }
csvLoggingAddData(); csvLoggingAddData();
} }
void ScopeGadgetWidget::replotNewData() 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->removeStaleData();
plotData->curve->setSamples(*plotData->xData, *plotData->yData); plotData->curve->setSamples(*plotData->xData, *plotData->yData);
} }
@ -493,8 +518,9 @@ void ScopeGadgetWidget::replotNewData()
QDateTime NOW = QDateTime::currentDateTime(); QDateTime NOW = QDateTime::currentDateTime();
double toTime = NOW.toTime_t(); double toTime = NOW.toTime_t();
toTime += NOW.time().msec() / 1000.0; toTime += NOW.time().msec() / 1000.0;
if (m_plotType == ChronoPlot) if (m_plotType == ChronoPlot) {
setAxisScale(QwtPlot::xBottom, toTime - m_xWindowSize, toTime); 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;
@ -503,53 +529,6 @@ void ScopeGadgetWidget::replotNewData()
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() void ScopeGadgetWidget::clearCurvePlots()
{ {
foreach(PlotData * plotData, m_curvesData.values()) { foreach(PlotData * plotData, m_curvesData.values()) {
@ -572,41 +551,34 @@ QFile csvLoggingFile;
*/ */
int ScopeGadgetWidget::csvLoggingStart() int ScopeGadgetWidget::csvLoggingStart()
{ {
if (!m_csvLoggingStarted) if (!m_csvLoggingStarted) {
if (m_csvLoggingEnabled) if (m_csvLoggingEnabled) {
if ((!m_csvLoggingNewFileOnConnect)||(m_csvLoggingNewFileOnConnect && m_csvLoggingConnected)) if ((!m_csvLoggingNewFileOnConnect) || (m_csvLoggingNewFileOnConnect && m_csvLoggingConnected)) {
{
QDateTime NOW = QDateTime::currentDateTime(); QDateTime NOW = QDateTime::currentDateTime();
m_csvLoggingStartTime = NOW; m_csvLoggingStartTime = NOW;
m_csvLoggingHeaderSaved = 0; m_csvLoggingHeaderSaved = 0;
m_csvLoggingDataSaved = 0; m_csvLoggingDataSaved = 0;
m_csvLoggingBuffer.clear(); m_csvLoggingBuffer.clear();
QDir PathCheck(m_csvLoggingPath); QDir PathCheck(m_csvLoggingPath);
if (!PathCheck.exists()) if (!PathCheck.exists()) {
{
PathCheck.mkpath("./"); PathCheck.mkpath("./");
} }
if (m_csvLoggingNameSet) 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"))); 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 {
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"))); 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()); QDir FileCheck(m_csvLoggingFile.fileName());
if (FileCheck.exists()) if (FileCheck.exists()) {
{
m_csvLoggingFile.setFileName(""); m_csvLoggingFile.setFileName("");
} } else {
else
{
m_csvLoggingStarted = 1; m_csvLoggingStarted = 1;
csvLoggingInsertHeader(); csvLoggingInsertHeader();
} }
}
}
} }
return 0; return 0;
@ -621,26 +593,30 @@ int ScopeGadgetWidget::csvLoggingStop()
int ScopeGadgetWidget::csvLoggingInsertHeader() int ScopeGadgetWidget::csvLoggingInsertHeader()
{ {
if (!m_csvLoggingStarted) return -1; if (!m_csvLoggingStarted) {
if (m_csvLoggingHeaderSaved) return -2; return -1;
if (m_csvLoggingDataSaved) return -3; }
if (m_csvLoggingHeaderSaved) {
return -2;
}
if (m_csvLoggingDataSaved) {
return -3;
}
m_csvLoggingHeaderSaved = 1; m_csvLoggingHeaderSaved = 1;
if(m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append)== FALSE) if (m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append) == FALSE) {
{
qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Header"; qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Header";
} } else {
else
{
QTextStream ts(&m_csvLoggingFile); QTextStream ts(&m_csvLoggingFile);
ts << "date" << ", " << "Time" << ", " << "Sec since start" << ", " << "Connected" << ", " << "Data changed"; ts << "date" << ", " << "Time" << ", " << "Sec since start" << ", " << "Connected" << ", " << "Data changed";
foreach(PlotData* plotData2, m_curvesData.values()) foreach(PlotData * plotData2, m_curvesData.values()) {
{
ts << ", "; ts << ", ";
ts << plotData2->uavObject; ts << plotData2->uavObject;
ts << "." << plotData2->uavField; ts << "." << plotData2->uavField;
if (plotData2->haveSubField) ts << "." << plotData2->uavSubField; if (plotData2->haveSubField) {
ts << "." << plotData2->uavSubField;
}
} }
ts << endl; ts << endl;
m_csvLoggingFile.close(); m_csvLoggingFile.close();
@ -650,7 +626,9 @@ int ScopeGadgetWidget::csvLoggingInsertHeader()
int ScopeGadgetWidget::csvLoggingAddData() int ScopeGadgetWidget::csvLoggingAddData()
{ {
if (!m_csvLoggingStarted) return -1; if (!m_csvLoggingStarted) {
return -1;
}
m_csvLoggingDataValid = 0; m_csvLoggingDataValid = 0;
QDateTime NOW = QDateTime::currentDateTime(); QDateTime NOW = QDateTime::currentDateTime();
QString tempString; QString tempString;
@ -666,30 +644,21 @@ int ScopeGadgetWidget::csvLoggingAddData()
ss << ", " << m_csvLoggingConnected << ", " << m_csvLoggingDataUpdated; ss << ", " << m_csvLoggingConnected << ", " << m_csvLoggingDataUpdated;
m_csvLoggingDataUpdated = 0; m_csvLoggingDataUpdated = 0;
foreach(PlotData* plotData2, m_curvesData.values()) foreach(PlotData * plotData2, m_curvesData.values()) {
{
ss << ", "; ss << ", ";
if (plotData2->xData->isEmpty ()) if (plotData2->xData->isEmpty()) {
{
ss << ", "; ss << ", ";
if (plotData2->xData->isEmpty ()) if (plotData2->xData->isEmpty()) {} else {
{
}
else
{
ss << QString().sprintf("%3.10g", plotData2->yData->last()); ss << QString().sprintf("%3.10g", plotData2->yData->last());
m_csvLoggingDataValid = 1; m_csvLoggingDataValid = 1;
} }
} } else {
else
{
ss << QString().sprintf("%3.10g", plotData2->yData->last()); ss << QString().sprintf("%3.10g", plotData2->yData->last());
m_csvLoggingDataValid = 1; m_csvLoggingDataValid = 1;
} }
} }
ss << endl; ss << endl;
if (m_csvLoggingDataValid) if (m_csvLoggingDataValid) {
{
QTextStream ts(&m_csvLoggingBuffer); QTextStream ts(&m_csvLoggingBuffer);
ts << tempString; ts << tempString;
} }
@ -699,15 +668,14 @@ int ScopeGadgetWidget::csvLoggingAddData()
int ScopeGadgetWidget::csvLoggingInsertData() int ScopeGadgetWidget::csvLoggingInsertData()
{ {
if (!m_csvLoggingStarted) return -1; if (!m_csvLoggingStarted) {
return -1;
}
m_csvLoggingDataSaved = 1; m_csvLoggingDataSaved = 1;
if(m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append)== FALSE) if (m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append) == FALSE) {
{
qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Data"; qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Data";
} } else {
else
{
QTextStream ts(&m_csvLoggingFile); QTextStream ts(&m_csvLoggingFile);
ts << m_csvLoggingBuffer; ts << m_csvLoggingBuffer;
m_csvLoggingFile.close(); m_csvLoggingFile.close();
@ -726,13 +694,15 @@ void ScopeGadgetWidget::csvLoggingSetName(QString newName)
void ScopeGadgetWidget::csvLoggingConnect() void ScopeGadgetWidget::csvLoggingConnect()
{ {
m_csvLoggingConnected = 1; m_csvLoggingConnected = 1;
if (m_csvLoggingNewFileOnConnect)csvLoggingStart(); if (m_csvLoggingNewFileOnConnect) {
return; csvLoggingStart();
}
} }
void ScopeGadgetWidget::csvLoggingDisconnect() void ScopeGadgetWidget::csvLoggingDisconnect()
{ {
m_csvLoggingHeaderSaved = 0; m_csvLoggingHeaderSaved = 0;
m_csvLoggingConnected = 0; m_csvLoggingConnected = 0;
if (m_csvLoggingNewFileOnConnect)csvLoggingStop(); if (m_csvLoggingNewFileOnConnect) {
return; csvLoggingStop();
}
} }

View File

@ -49,7 +49,6 @@ class TimeScaleDraw : public QwtScaleDraw
{ {
public: public:
TimeScaleDraw() { TimeScaleDraw() {
//baseTime = QDateTime::currentDateTime().toTime_t();
} }
virtual QwtText label(double v) const { virtual QwtText label(double v) const {
uint seconds = (uint)(v); uint seconds = (uint)(v);
@ -58,8 +57,6 @@ public:
upTime.setTime(timePart); upTime.setTime(timePart);
return upTime.toLocalTime().toString("hh:mm:ss"); return upTime.toLocalTime().toString("hh:mm:ss");
} }
private:
// double baseTime;
}; };
class ScopeGadgetWidget : public QwtPlot class ScopeGadgetWidget : public QwtPlot
@ -81,15 +78,15 @@ public:
int refreshInterval(){return m_refreshInterval;} 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 addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, int meanSamples = 1,
//void removeCurvePlot(QString uavObject, QString uavField); QString mathFunction= "None", QPen pen = QPen(Qt::black), bool antialiased = true);
void clearCurvePlots(); void clearCurvePlots();
int csvLoggingStart(); int csvLoggingStart();
int csvLoggingStop(); int csvLoggingStop();
void csvLoggingSetName(QString); void csvLoggingSetName(QString);
void setLoggingEnabled(bool value){m_csvLoggingEnabled=value;}; void setLoggingEnabled(bool value){m_csvLoggingEnabled=value;}
void setLoggingNewFileOnConnect(bool value){m_csvLoggingNewFileOnConnect=value;}; void setLoggingNewFileOnConnect(bool value){m_csvLoggingNewFileOnConnect=value;}
void setLoggingPath(QString value){m_csvLoggingPath=value;}; void setLoggingPath(QString value){m_csvLoggingPath=value;}
protected: protected:
void mousePressEvent(QMouseEvent *e); void mousePressEvent(QMouseEvent *e);
@ -97,6 +94,7 @@ protected:
void mouseDoubleClickEvent(QMouseEvent *e); void mouseDoubleClickEvent(QMouseEvent *e);
void mouseMoveEvent(QMouseEvent *e); void mouseMoveEvent(QMouseEvent *e);
void wheelEvent(QWheelEvent *e); void wheelEvent(QWheelEvent *e);
void showEvent(QShowEvent *e);
private slots: private slots:
void uavObjectReceived(UAVObject*); void uavObjectReceived(UAVObject*);

View File

@ -66,10 +66,11 @@ void ConfigTaskWidget::addUAVObject(QString objectName,QList<int> * reloadGroups
void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList<int> *reloadGroups) void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList<int> *reloadGroups)
{ {
QString objstr; 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 * Add an UAVObject field to widget relation to the management system
@ -82,6 +83,7 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
{ {
UAVObject *obj = NULL; UAVObject *obj = NULL;
UAVObjectField *_field = NULL; UAVObjectField *_field = NULL;
obj = objManager->getObject(QString(object)); obj = objManager->getObject(QString(object));
Q_ASSERT(obj); Q_ASSERT(obj);
_field = obj->getField(QString(field)); _field = obj->getField(QString(field));
@ -93,10 +95,13 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
{ {
QString objstr; QString objstr;
QString fieldstr; QString fieldstr;
if(obj)
if (obj) {
objstr = obj->getName(); objstr = obj->getName();
if(field) }
if (field) {
fieldstr = field->getName(); fieldstr = field->getName();
}
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index); addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index);
} }
/** /**
@ -113,15 +118,16 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID) void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
{ {
UAVObject *obj = objManager->getObject(QString(object), instID); UAVObject *obj = objManager->getObject(QString(object), instID);
Q_ASSERT(obj); Q_ASSERT(obj);
UAVObjectField *_field; UAVObjectField *_field;
int index = 0; int index = 0;
if(!field.isEmpty() && obj) if (!field.isEmpty() && obj) {
{
_field = obj->getField(QString(field)); _field = obj->getField(QString(field));
if(!element.isEmpty()) if (!element.isEmpty()) {
index = _field->getElementNames().indexOf(QString(element)); index = _field->getElementNames().indexOf(QString(element));
} }
}
addUAVObjectToWidgetRelation(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID); addUAVObjectToWidgetRelation(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID);
} }
@ -129,20 +135,26 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
{ {
QString objstr; QString objstr;
QString fieldstr; QString fieldstr;
if(obj)
if (obj) {
objstr = obj->getName(); objstr = obj->getName();
if(field) }
if (field) {
fieldstr = field->getName(); fieldstr = field->getName();
}
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, element, scale, isLimited, defaultReloadGroups, instID); 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<int> *defaultReloadGroups, quint32 instID) void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
{ {
QString objstr; QString objstr;
QString fieldstr; QString fieldstr;
if(obj)
if (obj) {
objstr = obj->getName(); objstr = obj->getName();
if(field) }
if (field) {
fieldstr = field->getName(); fieldstr = field->getName();
}
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index, scale, isLimited, defaultReloadGroups, instID); addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index, scale, isLimited, defaultReloadGroups, instID);
} }
@ -159,21 +171,22 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject * obj,UAVObjectFie
*/ */
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID) void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
{ {
if(addShadowWidget(object,field,widget,index,scale,isLimited,defaultReloadGroups,instID)) if (addShadowWidget(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID)) {
return; return;
}
UAVObject *obj = NULL; UAVObject *obj = NULL;
UAVObjectField *_field = NULL; UAVObjectField *_field = NULL;
if(!object.isEmpty()) if (!object.isEmpty()) {
{
obj = objManager->getObject(QString(object), instID); obj = objManager->getObject(QString(object), instID);
Q_ASSERT(obj); Q_ASSERT(obj);
objectUpdates.insert(obj, true); objectUpdates.insert(obj, true);
connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(objectUpdated(UAVObject *))); connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(objectUpdated(UAVObject *)));
connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection); connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection);
} }
if(!field.isEmpty() && obj) if (!field.isEmpty() && obj) {
_field = obj->getField(QString(field)); _field = obj->getField(QString(field));
}
objectToWidget *ow = new objectToWidget(); objectToWidget *ow = new objectToWidget();
ow->field = _field; ow->field = _field;
ow->object = obj; ow->object = obj;
@ -182,36 +195,27 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
ow->scale = scale; ow->scale = scale;
ow->isLimited = isLimited; ow->isLimited = isLimited;
objOfInterest.append(ow); objOfInterest.append(ow);
if(obj) if (obj) {
{ if (smartsave) {
if(smartsave)
{
smartsave->addObject((UAVDataObject *)obj); smartsave->addObject((UAVDataObject *)obj);
} }
} }
if(widget==NULL) if (widget == NULL) {
{ if (defaultReloadGroups && obj) {
if(defaultReloadGroups && obj) foreach(int i, *defaultReloadGroups) {
{ if (this->defaultReloadGroups.contains(i)) {
foreach(int i,*defaultReloadGroups)
{
if(this->defaultReloadGroups.contains(i))
{
this->defaultReloadGroups.value(i)->append(ow); this->defaultReloadGroups.value(i)->append(ow);
} } else {
else
{
this->defaultReloadGroups.insert(i, new QList<objectToWidget *>()); this->defaultReloadGroups.insert(i, new QList<objectToWidget *>());
this->defaultReloadGroups.value(i)->append(ow); this->defaultReloadGroups.value(i)->append(ow);
} }
} }
} }
} } else {
else
{
connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged()));
if(defaultReloadGroups) if (defaultReloadGroups) {
addWidgetToDefaultReloadGroups(widget, defaultReloadGroups); addWidgetToDefaultReloadGroups(widget, defaultReloadGroups);
}
shadowsList.insert(widget, ow); shadowsList.insert(widget, ow);
loadWidgetLimits(widget, _field, index, isLimited, scale); loadWidgetLimits(widget, _field, index, isLimited, scale);
} }
@ -221,20 +225,20 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
*/ */
ConfigTaskWidget::~ConfigTaskWidget() ConfigTaskWidget::~ConfigTaskWidget()
{ {
if(smartsave) if (smartsave) {
delete smartsave; delete smartsave;
foreach(QList<objectToWidget*>* pointer,defaultReloadGroups.values()) }
{ foreach(QList<objectToWidget *> *pointer, defaultReloadGroups.values()) {
if(pointer) if (pointer) {
delete pointer; delete pointer;
} }
foreach (objectToWidget* oTw, objOfInterest) }
{ foreach(objectToWidget * oTw, objOfInterest) {
if(oTw) if (oTw) {
delete oTw; delete oTw;
} }
if(timeOut) }
{ if (timeOut) {
delete timeOut; delete timeOut;
timeOut = NULL; timeOut = NULL;
} }
@ -246,6 +250,7 @@ void ConfigTaskWidget::saveObjectToSD(UAVObject *obj)
// central place (and one central queue) // central place (and one central queue)
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>(); UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
utilMngr->saveObjectToSD(obj); utilMngr->saveObjectToSD(obj);
} }
@ -253,9 +258,11 @@ void ConfigTaskWidget::saveObjectToSD(UAVObject *obj)
* Util function to get a pointer to the object manager * Util function to get a pointer to the object manager
* @return pointer to the UAVObjectManager * @return pointer to the UAVObjectManager
*/ */
UAVObjectManager* ConfigTaskWidget::getObjectManager() { UAVObjectManager *ConfigTaskWidget::getObjectManager()
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objMngr = pm->getObject<UAVObjectManager>(); UAVObjectManager *objMngr = pm->getObject<UAVObjectManager>();
Q_ASSERT(objMngr); Q_ASSERT(objMngr);
return objMngr; return objMngr;
} }
@ -267,8 +274,10 @@ UAVObjectManager* ConfigTaskWidget::getObjectManager() {
double ConfigTaskWidget::listMean(QList<double> list) double ConfigTaskWidget::listMean(QList<double> list)
{ {
double accum = 0; double accum = 0;
for(int i = 0; i < list.size(); i++)
for (int i = 0; i < list.size(); i++) {
accum += list[i]; accum += list[i];
}
return accum / list.size(); return accum / list.size();
} }
@ -283,12 +292,14 @@ double ConfigTaskWidget::listVar(QList<double> list)
double var_accum = 0; double var_accum = 0;
double mean; double mean;
for(int i = 0; i < list.size(); i++) for (int i = 0; i < list.size(); i++) {
mean_accum += list[i]; mean_accum += list[i];
}
mean = mean_accum / list.size(); 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); var_accum += (list[i] - mean) * (list[i] - mean);
}
// Use unbiased estimator // Use unbiased estimator
return var_accum / (list.size() - 1); return var_accum / (list.size() - 1);
@ -312,12 +323,12 @@ void ConfigTaskWidget::forceConnectedState()//dynamic widgets don't recieve the
void ConfigTaskWidget::onAutopilotConnect() void ConfigTaskWidget::onAutopilotConnect()
{ {
if (utilMngr) if (utilMngr) {
currentBoard = utilMngr->getBoardModel(); // TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE currentBoard = utilMngr->getBoardModel(); // TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE
}
invalidateObjects(); invalidateObjects();
isConnected = true; isConnected = true;
foreach(objectToWidget * ow,objOfInterest) foreach(objectToWidget * ow, objOfInterest) {
{
loadWidgetLimits(ow->widget, ow->field, ow->index, ow->isLimited, ow->scale); loadWidgetLimits(ow->widget, ow->field, ow->index, ow->isLimited, ow->scale);
} }
setDirty(false); setDirty(false);
@ -332,15 +343,14 @@ void ConfigTaskWidget::populateWidgets()
{ {
bool dirtyBack = dirty; bool dirtyBack = dirty;
emit populateWidgetsRequested(); emit populateWidgetsRequested();
foreach(objectToWidget * ow,objOfInterest)
{ foreach(objectToWidget * ow, objOfInterest) {
if(ow->object==NULL || ow->field==NULL || ow->widget==NULL) if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) {
{
// do nothing // do nothing
} } else {
else
setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited); setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited);
} }
}
setDirty(dirtyBack); setDirty(dirtyBack);
} }
/** /**
@ -350,26 +360,22 @@ void ConfigTaskWidget::populateWidgets()
*/ */
void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj) void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj)
{ {
if (!allowWidgetUpdates) if (!allowWidgetUpdates) {
return; return;
}
bool dirtyBack = dirty; bool dirtyBack = dirty;
emit refreshWidgetsValuesRequested(); emit refreshWidgetsValuesRequested();
foreach(objectToWidget * ow,objOfInterest) foreach(objectToWidget * ow, objOfInterest) {
{ if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) {
if(ow->object==NULL || ow->field==NULL || ow->widget==NULL)
{
// do nothing // do nothing
} } else {
else if (ow->object == obj || obj == NULL) {
{
if(ow->object==obj || obj==NULL)
setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited); setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited);
} }
}
} }
setDirty(dirtyBack); setDirty(dirtyBack);
} }
/** /**
* SLOT function used to update the uavobject fields from widgets with relation to * 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() void ConfigTaskWidget::updateObjectsFromWidgets()
{ {
emit updateObjectsFromWidgetsRequested(); emit updateObjectsFromWidgetsRequested();
foreach(objectToWidget * ow,objOfInterest)
{
if(ow->object==NULL || ow->field==NULL)
{
} foreach(objectToWidget * ow, objOfInterest) {
else if (ow->object == NULL || ow->field == NULL) {} else {
setFieldFromWidget(ow->widget, ow->field, ow->index, ow->scale); setFieldFromWidget(ow->widget, ow->field, ow->index, ow->scale);
}
} }
} }
/** /**
@ -397,9 +399,11 @@ void ConfigTaskWidget::updateObjectsFromWidgets()
void ConfigTaskWidget::helpButtonPressed() void ConfigTaskWidget::helpButtonPressed()
{ {
QString url = helpButtonList.value((QPushButton *)sender(), QString()); QString url = helpButtonList.value((QPushButton *)sender(), QString());
if(!url.isEmpty())
if (!url.isEmpty()) {
QDesktopServices::openUrl(QUrl(url, QUrl::StrictMode)); QDesktopServices::openUrl(QUrl(url, QUrl::StrictMode));
} }
}
/** /**
* Add update and save buttons to the form * Add update and save buttons to the form
* multiple buttons can be added for the same function * multiple buttons can be added for the same function
@ -408,33 +412,28 @@ void ConfigTaskWidget::helpButtonPressed()
*/ */
void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save) void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save)
{ {
if(!smartsave) if (!smartsave) {
{
smartsave = new smartSaveButton(); smartsave = new smartSaveButton();
connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets()));
connect(smartsave, SIGNAL(saveSuccessfull()), this, SLOT(clearDirty())); connect(smartsave, SIGNAL(saveSuccessfull()), this, SLOT(clearDirty()));
connect(smartsave, SIGNAL(beginOp()), this, SLOT(disableObjUpdates())); connect(smartsave, SIGNAL(beginOp()), this, SLOT(disableObjUpdates()));
connect(smartsave, SIGNAL(endOp()), this, SLOT(enableObjUpdates())); connect(smartsave, SIGNAL(endOp()), this, SLOT(enableObjUpdates()));
} }
if(update && save) if (update && save) {
smartsave->addButtons(save, update); smartsave->addButtons(save, update);
else if (update) } else if (update) {
smartsave->addApplyButton(update); smartsave->addApplyButton(update);
else if (save) } else if (save) {
smartsave->addSaveButton(save); smartsave->addSaveButton(save);
if(objOfInterest.count()>0) }
{ if (objOfInterest.count() > 0) {
foreach(objectToWidget * oTw,objOfInterest) foreach(objectToWidget * oTw, objOfInterest) {
{
smartsave->addObject((UAVDataObject *)oTw->object); smartsave->addObject((UAVDataObject *)oTw->object);
} }
} }
TelemetryManager* telMngr = pm->getObject<TelemetryManager>(); updateEnableControls();
if(telMngr->isConnected())
enableControls(true);
else
enableControls(false);
} }
/** /**
* SLOT function used the enable or disable the SAVE, UPLOAD and RELOAD buttons * 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 * @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) void ConfigTaskWidget::enableControls(bool enable)
{ {
if(smartsave) if (smartsave) {
smartsave->enableControls(enable); smartsave->enableControls(enable);
}
foreach(QPushButton * button, reloadButtonList) { foreach(QPushButton * button, reloadButtonList) {
button->setEnabled(enable); 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 * SLOT function called when on of the widgets contents added to the framework changes
*/ */
void ConfigTaskWidget::forceShadowUpdates() void ConfigTaskWidget::forceShadowUpdates()
{ {
foreach(objectToWidget * oTw,objOfInterest) foreach(objectToWidget * oTw, objOfInterest) {
{ foreach(shadow * sh, oTw->shadowsList) {
foreach (shadow * sh, oTw->shadowsList)
{
disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged()));
checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale); 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); setWidgetFromVariant(sh->widget, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale);
emit widgetContentsChanged((QWidget *)sh->widget); emit widgetContentsChanged((QWidget *)sh->widget);
connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged()));
} }
} }
setDirty(true); setDirty(true);
@ -475,36 +483,30 @@ void ConfigTaskWidget::widgetsContentsChanged()
emit widgetContentsChanged((QWidget *)sender()); emit widgetContentsChanged((QWidget *)sender());
double scale; double scale;
objectToWidget *oTw = shadowsList.value((QWidget *)sender(), NULL); objectToWidget *oTw = shadowsList.value((QWidget *)sender(), NULL);
if(oTw)
{ if (oTw) {
if(oTw->widget==(QWidget*)sender()) if (oTw->widget == (QWidget *)sender()) {
{
scale = oTw->scale; scale = oTw->scale;
checkWidgetsLimits((QWidget*)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget*)sender(), oTw->scale, oTw->getUnits()), oTw->scale); checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(),
} oTw->scale, oTw->getUnits()), oTw->scale);
else } else {
{ foreach(shadow * sh, oTw->shadowsList) {
foreach (shadow * sh, oTw->shadowsList) if (sh->widget == (QWidget *)sender()) {
{
if(sh->widget==(QWidget*)sender())
{
scale = sh->scale; scale = sh->scale;
checkWidgetsLimits((QWidget*)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), scale); checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(),
scale, oTw->getUnits()), scale);
} }
} }
} }
if(oTw->widget!=(QWidget *)sender()) if (oTw->widget != (QWidget *)sender()) {
{
disconnectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged())); disconnectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged()));
checkWidgetsLimits(oTw->widget, oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale); 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); setWidgetFromVariant(oTw->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale);
emit widgetContentsChanged((QWidget *)oTw->widget); emit widgetContentsChanged((QWidget *)oTw->widget);
connectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged()));
} }
foreach (shadow * sh, oTw->shadowsList) foreach(shadow * sh, oTw->shadowsList) {
{ if (sh->widget != (QWidget *)sender()) {
if(sh->widget!=(QWidget*)sender())
{
disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged()));
checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale); 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); setWidgetFromVariant(sh->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale);
@ -513,8 +515,9 @@ void ConfigTaskWidget::widgetsContentsChanged()
} }
} }
} }
if(smartsave) if (smartsave) {
smartsave->resetIcons(); smartsave->resetIcons();
}
setDirty(true); setDirty(true);
} }
/** /**
@ -538,20 +541,22 @@ void ConfigTaskWidget::setDirty(bool value)
*/ */
bool ConfigTaskWidget::isDirty() bool ConfigTaskWidget::isDirty()
{ {
if(isConnected) if (isConnected) {
return dirty; return dirty;
else } else {
return false; return false;
} }
}
/** /**
* SLOT function used to disable widget contents changes when related object field changes * SLOT function used to disable widget contents changes when related object field changes
*/ */
void ConfigTaskWidget::disableObjUpdates() void ConfigTaskWidget::disableObjUpdates()
{ {
allowWidgetUpdates = false; allowWidgetUpdates = false;
foreach(objectToWidget * obj,objOfInterest) foreach(objectToWidget * obj, objOfInterest) {
{ if (obj->object) {
if(obj->object)disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*))); disconnect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)));
}
} }
} }
/** /**
@ -560,12 +565,12 @@ void ConfigTaskWidget::disableObjUpdates()
void ConfigTaskWidget::enableObjUpdates() void ConfigTaskWidget::enableObjUpdates()
{ {
allowWidgetUpdates = true; allowWidgetUpdates = true;
foreach(objectToWidget * obj,objOfInterest) foreach(objectToWidget * obj, objOfInterest) {
{ if (obj->object) {
if(obj->object)
connect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection); connect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection);
} }
} }
}
/** /**
* Called when an uav object is updated * Called when an uav object is updated
* @param obj pointer to the object whitch has just been updated * @param obj pointer to the object whitch has just been updated
@ -582,8 +587,7 @@ bool ConfigTaskWidget::allObjectsUpdated()
{ {
qDebug() << "ConfigTaskWidge:allObjectsUpdated called"; qDebug() << "ConfigTaskWidge:allObjectsUpdated called";
bool ret = true; bool ret = true;
foreach(UAVObject *obj, objectUpdates.keys()) foreach(UAVObject * obj, objectUpdates.keys()) {
{
ret = ret & objectUpdates[obj]; ret = ret & objectUpdates[obj];
} }
qDebug() << "Returned:" << ret; qDebug() << "Returned:" << ret;
@ -598,15 +602,13 @@ void ConfigTaskWidget::addHelpButton(QPushButton *button, QString url)
{ {
helpButtonList.insert(button, url); helpButtonList.insert(button, url);
connect(button, SIGNAL(clicked()), this, SLOT(helpButtonPressed())); connect(button, SIGNAL(clicked()), this, SLOT(helpButtonPressed()));
} }
/** /**
* Invalidates all the uav objects "is updated" flag * Invalidates all the uav objects "is updated" flag
*/ */
void ConfigTaskWidget::invalidateObjects() void ConfigTaskWidget::invalidateObjects()
{ {
foreach(UAVObject *obj, objectUpdates.keys()) foreach(UAVObject * obj, objectUpdates.keys()) {
{
objectUpdates[obj] = false; objectUpdates[obj] = false;
} }
} }
@ -615,35 +617,36 @@ void ConfigTaskWidget::invalidateObjects()
*/ */
void ConfigTaskWidget::apply() void ConfigTaskWidget::apply()
{ {
if(smartsave) if (smartsave) {
smartsave->apply(); smartsave->apply();
} }
}
/** /**
* SLOT call this to save changes to uav objects * SLOT call this to save changes to uav objects
*/ */
void ConfigTaskWidget::save() void ConfigTaskWidget::save()
{ {
if(smartsave) if (smartsave) {
smartsave->save(); smartsave->save();
} }
}
/** /**
* Adds a new shadow widget * Adds a new shadow widget
* shadow widgets are widgets whitch have a relation to an object already present on the framework pool i.e. already added trough addUAVObjectToWidgetRelation * shadow widgets are widgets whitch have a relation to an object already present on the framework pool i.e. already added trough addUAVObjectToWidgetRelation
* This function doesn't have to be used directly, addUAVObjectToWidgetRelation will call it if a previous relation exhists. * 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) * @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<int>* defaultReloadGroups,quint32 instID) bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited,
QList<int> *defaultReloadGroups, quint32 instID)
{ {
foreach(objectToWidget * oTw,objOfInterest) foreach(objectToWidget * oTw, objOfInterest) {
{ if (!oTw->object || !oTw->widget || !oTw->field) {
if(!oTw->object || !oTw->widget || !oTw->field)
continue; continue;
if(oTw->object->getName()==object && oTw->field->getName()==field && oTw->index==index && oTw->object->getInstID()==instID) }
{ if (oTw->object->getName() == object && oTw->field->getName() == field && oTw->index == index && oTw->object->getInstID() == instID) {
shadow *sh = NULL; shadow *sh = NULL;
// prefer anything else to QLabel // prefer anything else to QLabel
if(qobject_cast<QLabel *>(oTw->widget) && !qobject_cast<QLabel *>(widget)) if (qobject_cast<QLabel *>(oTw->widget) && !qobject_cast<QLabel *>(widget)) {
{
sh = new shadow; sh = new shadow;
sh->isLimited = oTw->isLimited; sh->isLimited = oTw->isLimited;
sh->scale = oTw->scale; sh->scale = oTw->scale;
@ -653,8 +656,7 @@ bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *w
oTw->widget = widget; oTw->widget = widget;
} }
// prefer QDoubleSpinBox to anything else // prefer QDoubleSpinBox to anything else
else if(!qobject_cast<QDoubleSpinBox *>(oTw->widget) && qobject_cast<QDoubleSpinBox *>(widget)) else if (!qobject_cast<QDoubleSpinBox *>(oTw->widget) && qobject_cast<QDoubleSpinBox *>(widget)) {
{
sh = new shadow; sh = new shadow;
sh->isLimited = oTw->isLimited; sh->isLimited = oTw->isLimited;
sh->scale = oTw->scale; sh->scale = oTw->scale;
@ -662,9 +664,7 @@ bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *w
oTw->isLimited = isLimited; oTw->isLimited = isLimited;
oTw->scale = scale; oTw->scale = scale;
oTw->widget = widget; oTw->widget = widget;
} } else {
else
{
sh = new shadow; sh = new shadow;
sh->isLimited = isLimited; sh->isLimited = isLimited;
sh->scale = scale; sh->scale = scale;
@ -673,8 +673,9 @@ bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *w
shadowsList.insert(widget, oTw); shadowsList.insert(widget, oTw);
oTw->shadowsList.append(sh); oTw->shadowsList.append(sh);
connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged()));
if(defaultReloadGroups) if (defaultReloadGroups) {
addWidgetToDefaultReloadGroups(widget, defaultReloadGroups); addWidgetToDefaultReloadGroups(widget, defaultReloadGroups);
}
loadWidgetLimits(widget, oTw->field, oTw->index, isLimited, scale); loadWidgetLimits(widget, oTw->field, oTw->index, isLimited, scale);
return true; return true;
} }
@ -689,119 +690,116 @@ void ConfigTaskWidget::autoLoadWidgets()
{ {
QPushButton *saveButtonWidget = NULL; QPushButton *saveButtonWidget = NULL;
QPushButton *applyButtonWidget = NULL; QPushButton *applyButtonWidget = NULL;
foreach(QWidget * widget,this->findChildren<QWidget*>())
{ foreach(QWidget * widget, this->findChildren<QWidget *>()) {
QVariant info = widget->property("objrelation"); QVariant info = widget->property("objrelation");
if(info.isValid())
{ if (info.isValid()) {
uiRelationAutomation uiRelation; uiRelationAutomation uiRelation;
uiRelation.buttonType = none; uiRelation.buttonType = none;
uiRelation.scale = 1; uiRelation.scale = 1;
uiRelation.element = QString(); uiRelation.element = QString();
uiRelation.haslimits = false; uiRelation.haslimits = false;
foreach(QString str, info.toStringList()) foreach(QString str, info.toStringList()) {
{
QString prop = str.split(":").at(0); QString prop = str.split(":").at(0);
QString value = str.split(":").at(1); QString value = str.split(":").at(1);
if(prop== "objname")
if (prop == "objname") {
uiRelation.objname = value; uiRelation.objname = value;
else if(prop== "fieldname") } else if (prop == "fieldname") {
uiRelation.fieldname = value; uiRelation.fieldname = value;
else if(prop=="element") } else if (prop == "element") {
uiRelation.element = value; uiRelation.element = value;
else if(prop== "scale") } else if (prop == "scale") {
{ if (value == "null") {
if(value=="null")
uiRelation.scale = 1; uiRelation.scale = 1;
else } else {
uiRelation.scale = value.toDouble(); uiRelation.scale = value.toDouble();
} }
else if(prop== "haslimits") } else if (prop == "haslimits") {
{ if (value == "yes") {
if(value=="yes")
uiRelation.haslimits = true; uiRelation.haslimits = true;
else } else {
uiRelation.haslimits = false; uiRelation.haslimits = false;
} }
else if(prop== "button") } else if (prop == "button") {
{ if (value == "save") {
if(value=="save")
uiRelation.buttonType = save_button; uiRelation.buttonType = save_button;
else if(value=="apply") } else if (value == "apply") {
uiRelation.buttonType = apply_button; uiRelation.buttonType = apply_button;
else if(value=="reload") } else if (value == "reload") {
uiRelation.buttonType = reload_button; uiRelation.buttonType = reload_button;
else if(value=="default") } else if (value == "default") {
uiRelation.buttonType = default_button; uiRelation.buttonType = default_button;
else if(value=="help") } else if (value == "help") {
uiRelation.buttonType = help_button; uiRelation.buttonType = help_button;
} }
else if(prop== "buttongroup") } else if (prop == "buttongroup") {
{ foreach(QString s, value.split(",")) {
foreach(QString s,value.split(","))
{
uiRelation.buttonGroup.append(s.toInt()); uiRelation.buttonGroup.append(s.toInt());
} }
} } else if (prop == "url") {
else if(prop=="url")
uiRelation.url = str.mid(str.indexOf(":") + 1); uiRelation.url = str.mid(str.indexOf(":") + 1);
} }
if(!uiRelation.buttonType==none) }
{ if (!uiRelation.buttonType == none) {
QPushButton *button = NULL; QPushButton *button = NULL;
switch(uiRelation.buttonType) switch (uiRelation.buttonType) {
{
case save_button: case save_button:
saveButtonWidget = qobject_cast<QPushButton *>(widget); saveButtonWidget = qobject_cast<QPushButton *>(widget);
if(saveButtonWidget) if (saveButtonWidget) {
addApplySaveButtons(NULL, saveButtonWidget); addApplySaveButtons(NULL, saveButtonWidget);
}
break; break;
case apply_button: case apply_button:
applyButtonWidget = qobject_cast<QPushButton *>(widget); applyButtonWidget = qobject_cast<QPushButton *>(widget);
if(applyButtonWidget) if (applyButtonWidget) {
addApplySaveButtons(applyButtonWidget, NULL); addApplySaveButtons(applyButtonWidget, NULL);
}
break; break;
case default_button: case default_button:
button = qobject_cast<QPushButton *>(widget); button = qobject_cast<QPushButton *>(widget);
if(button) if (button) {
addDefaultButton(button, uiRelation.buttonGroup.at(0)); addDefaultButton(button, uiRelation.buttonGroup.at(0));
}
break; break;
case reload_button: case reload_button:
button = qobject_cast<QPushButton *>(widget); button = qobject_cast<QPushButton *>(widget);
if(button) if (button) {
addReloadButton(button, uiRelation.buttonGroup.at(0)); addReloadButton(button, uiRelation.buttonGroup.at(0));
}
break; break;
case help_button: case help_button:
button = qobject_cast<QPushButton *>(widget); button = qobject_cast<QPushButton *>(widget);
if(button) if (button) {
addHelpButton(button, uiRelation.url); addHelpButton(button, uiRelation.url);
}
break; break;
default: default:
break; break;
} }
} } else {
else
{
QWidget *wid = qobject_cast<QWidget *>(widget); QWidget *wid = qobject_cast<QWidget *>(widget);
if(wid) if (wid) {
addUAVObjectToWidgetRelation(uiRelation.objname, uiRelation.fieldname, wid, uiRelation.element, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup); addUAVObjectToWidgetRelation(uiRelation.objname, uiRelation.fieldname, wid, uiRelation.element, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup);
} }
} }
} }
}
refreshWidgetsValues(); refreshWidgetsValues();
forceShadowUpdates(); forceShadowUpdates();
foreach(objectToWidget * ow,objOfInterest) foreach(objectToWidget * ow, objOfInterest) {
{ if (ow->widget) {
if(ow->widget)
qDebug() << "Master:" << ow->widget->objectName(); qDebug() << "Master:" << ow->widget->objectName();
foreach(shadow * sh,ow->shadowsList) }
{ foreach(shadow * sh, ow->shadowsList) {
if(sh->widget) if (sh->widget) {
qDebug() << "Child" << sh->widget->objectName(); qDebug() << "Child" << sh->widget->objectName();
} }
} }
} }
}
/** /**
* Adds a widget to a list of default/reload groups * Adds a widget to a list of default/reload groups
* default/reload groups are groups of widgets to be set with default or reloaded (values from persistent memory) when a defined button is pressed * default/reload groups are groups of widgets to be set with default or reloaded (values from persistent memory) when a defined button is pressed
@ -810,29 +808,23 @@ void ConfigTaskWidget::autoLoadWidgets()
*/ */
void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> *groups) void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> *groups)
{ {
foreach(objectToWidget * oTw,objOfInterest) foreach(objectToWidget * oTw, objOfInterest) {
{
bool addOTW = false; bool addOTW = false;
if(oTw->widget==widget)
if (oTw->widget == widget) {
addOTW = true; addOTW = true;
else } else {
{ foreach(shadow * sh, oTw->shadowsList) {
foreach(shadow * sh, oTw->shadowsList) if (sh->widget == widget) {
{
if(sh->widget==widget)
addOTW = true; addOTW = true;
} }
} }
if(addOTW) }
{ if (addOTW) {
foreach(int i,*groups) foreach(int i, *groups) {
{ if (defaultReloadGroups.contains(i)) {
if(defaultReloadGroups.contains(i))
{
defaultReloadGroups.value(i)->append(oTw); defaultReloadGroups.value(i)->append(oTw);
} } else {
else
{
defaultReloadGroups.insert(i, new QList<objectToWidget *>()); defaultReloadGroups.insert(i, new QList<objectToWidget *>());
defaultReloadGroups.value(i)->append(oTw); defaultReloadGroups.value(i)->append(oTw);
} }
@ -868,11 +860,12 @@ void ConfigTaskWidget::defaultButtonClicked()
{ {
int group = sender()->property("group").toInt(); int group = sender()->property("group").toInt();
emit defaultRequested(group); emit defaultRequested(group);
QList<objectToWidget *> *list = defaultReloadGroups.value(group); QList<objectToWidget *> *list = defaultReloadGroups.value(group);
foreach(objectToWidget * oTw,*list) foreach(objectToWidget * oTw, *list) {
{ if (!oTw->object || !oTw->field) {
if(!oTw->object || !oTw->field)
continue; continue;
}
UAVDataObject *temp = ((UAVDataObject *)oTw->object)->dirtyClone(); UAVDataObject *temp = ((UAVDataObject *)oTw->object)->dirtyClone();
setWidgetFromField(oTw->widget, temp->getField(oTw->field->getName()), oTw->index, oTw->scale, oTw->isLimited); setWidgetFromField(oTw->widget, temp->getField(oTw->field->getName()), oTw->index, oTw->scale, oTw->isLimited);
} }
@ -882,12 +875,14 @@ void ConfigTaskWidget::defaultButtonClicked()
*/ */
void ConfigTaskWidget::reloadButtonClicked() void ConfigTaskWidget::reloadButtonClicked()
{ {
if(timeOut) if (timeOut) {
return; return;
}
int group = sender()->property("group").toInt(); int group = sender()->property("group").toInt();
QList<objectToWidget *> *list = defaultReloadGroups.value(group, NULL); QList<objectToWidget *> *list = defaultReloadGroups.value(group, NULL);
if(!list) if (!list) {
return; return;
}
ObjectPersistence *objper = dynamic_cast<ObjectPersistence *>(getObjectManager()->getObject(ObjectPersistence::NAME)); ObjectPersistence *objper = dynamic_cast<ObjectPersistence *>(getObjectManager()->getObject(ObjectPersistence::NAME));
timeOut = new QTimer(this); timeOut = new QTimer(this);
QEventLoop *eventLoop = new QEventLoop(this); QEventLoop *eventLoop = new QEventLoop(this);
@ -895,17 +890,16 @@ void ConfigTaskWidget::reloadButtonClicked()
connect(objper, SIGNAL(objectUpdated(UAVObject *)), eventLoop, SLOT(quit())); connect(objper, SIGNAL(objectUpdated(UAVObject *)), eventLoop, SLOT(quit()));
QList<temphelper> temp; QList<temphelper> temp;
foreach(objectToWidget * oTw,*list) foreach(objectToWidget * oTw, *list) {
{ if (oTw->object != NULL) {
if (oTw->object != NULL)
{
temphelper value; temphelper value;
value.objid = oTw->object->getObjID(); value.objid = oTw->object->getObjID();
value.objinstid = oTw->object->getInstID(); value.objinstid = oTw->object->getInstID();
if(temp.contains(value)) if (temp.contains(value)) {
continue; continue;
else } else {
temp.append(value); temp.append(value);
}
ObjectPersistence::DataFields data; ObjectPersistence::DataFields data;
data.Operation = ObjectPersistence::OPERATION_LOAD; data.Operation = ObjectPersistence::OPERATION_LOAD;
data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT; data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT;
@ -915,22 +909,20 @@ void ConfigTaskWidget::reloadButtonClicked()
objper->updated(); objper->updated();
timeOut->start(500); timeOut->start(500);
eventLoop->exec(); eventLoop->exec();
if(timeOut->isActive()) if (timeOut->isActive()) {
{
oTw->object->requestUpdate(); oTw->object->requestUpdate();
if(oTw->widget) if (oTw->widget) {
setWidgetFromField(oTw->widget, oTw->field, oTw->index, oTw->scale, oTw->isLimited); setWidgetFromField(oTw->widget, oTw->field, oTw->index, oTw->scale, oTw->isLimited);
} }
}
timeOut->stop(); timeOut->stop();
} }
} }
if(eventLoop) if (eventLoop) {
{
delete eventLoop; delete eventLoop;
eventLoop = NULL; eventLoop = NULL;
} }
if(timeOut) if (timeOut) {
{
delete timeOut; delete timeOut;
timeOut = NULL; timeOut = NULL;
} }
@ -941,86 +933,56 @@ void ConfigTaskWidget::reloadButtonClicked()
*/ */
void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget *widget, const char *function) void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget *widget, const char *function)
{ {
if(!widget) if (!widget) {
return; return;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget)) }
{ if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
connect(cb, SIGNAL(currentIndexChanged(int)), this, function); connect(cb, SIGNAL(currentIndexChanged(int)), this, function);
} } else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
connect(cb, SIGNAL(valueChanged(int)), this, function); connect(cb, SIGNAL(valueChanged(int)), this, function);
} } else if (MixerCurveWidget * cb = qobject_cast<MixerCurveWidget *>(widget)) {
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
{
connect(cb, SIGNAL(curveUpdated()), this, function); connect(cb, SIGNAL(curveUpdated()), this, function);
} } else if (QTableWidget * cb = qobject_cast<QTableWidget *>(widget)) {
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
{
connect(cb, SIGNAL(cellChanged(int, int)), this, function); connect(cb, SIGNAL(cellChanged(int, int)), this, function);
} } else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
connect(cb, SIGNAL(valueChanged(int)), this, function); connect(cb, SIGNAL(valueChanged(int)), this, function);
} } else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
connect(cb, SIGNAL(valueChanged(double)), this, function); connect(cb, SIGNAL(valueChanged(double)), this, function);
} } else if (QCheckBox * cb = qobject_cast<QCheckBox *>(widget)) {
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
connect(cb, SIGNAL(stateChanged(int)), this, function); connect(cb, SIGNAL(stateChanged(int)), this, function);
} } else if (QPushButton * cb = qobject_cast<QPushButton *>(widget)) {
else if(QPushButton * cb=qobject_cast<QPushButton *>(widget))
{
connect(cb, SIGNAL(clicked()), this, function); connect(cb, SIGNAL(clicked()), this, function);
} } else {
else
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
}
} }
/** /**
* Disconnects widgets "contents changed" signals to a slot * 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; return;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget)) }
{ if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
disconnect(cb, SIGNAL(currentIndexChanged(int)), this, function); disconnect(cb, SIGNAL(currentIndexChanged(int)), this, function);
} } else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
disconnect(cb, SIGNAL(valueChanged(int)), this, function); disconnect(cb, SIGNAL(valueChanged(int)), this, function);
} } else if (MixerCurveWidget * cb = qobject_cast<MixerCurveWidget *>(widget)) {
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
{
disconnect(cb, SIGNAL(curveUpdated()), this, function); disconnect(cb, SIGNAL(curveUpdated()), this, function);
} } else if (QTableWidget * cb = qobject_cast<QTableWidget *>(widget)) {
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
{
disconnect(cb, SIGNAL(cellChanged(int, int)), this, function); disconnect(cb, SIGNAL(cellChanged(int, int)), this, function);
} } else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
disconnect(cb, SIGNAL(valueChanged(int)), this, function); disconnect(cb, SIGNAL(valueChanged(int)), this, function);
} } else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
disconnect(cb, SIGNAL(valueChanged(double)), this, function); disconnect(cb, SIGNAL(valueChanged(double)), this, function);
} } else if (QCheckBox * cb = qobject_cast<QCheckBox *>(widget)) {
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
disconnect(cb, SIGNAL(stateChanged(int)), this, function); disconnect(cb, SIGNAL(stateChanged(int)), this, function);
} } else if (QPushButton * cb = qobject_cast<QPushButton *>(widget)) {
else if(QPushButton * cb=qobject_cast<QPushButton *>(widget))
{
disconnect(cb, SIGNAL(clicked()), this, function); disconnect(cb, SIGNAL(clicked()), this, function);
} } else {
else
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
}
} }
/** /**
* Sets a widget value from an UAVObject field * Sets a widget value from an UAVObject field
@ -1032,11 +994,11 @@ void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget * widget,const char
*/ */
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; return false;
}
QVariant ret = getVariantFromWidget(widget, scale, field->getUnits()); QVariant ret = getVariantFromWidget(widget, scale, field->getUnits());
if(ret.isValid()) if (ret.isValid()) {
{
field->setValue(ret, index); field->setValue(ret, index);
return true; return true;
} }
@ -1053,28 +1015,17 @@ bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * fiel
*/ */
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, QString units) QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, QString units)
{ {
if(QComboBox * cb=qobject_cast<QComboBox *>(widget)) if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
{
return (QString)cb->currentText(); return (QString)cb->currentText();
} } else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
return (double)(cb->value() * scale); return (double)(cb->value() * scale);
} } else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
return (double)(cb->value() * scale); return (double)(cb->value() * scale);
} } else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
return (double)(cb->value() * scale); return (double)(cb->value() * scale);
} } else if (QCheckBox * cb = qobject_cast<QCheckBox *>(widget)) {
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
return (QString)(cb->isChecked() ? "TRUE" : "FALSE"); return (QString)(cb->isChecked() ? "TRUE" : "FALSE");
} } else if (QLineEdit * cb = qobject_cast<QLineEdit *>(widget)) {
else if(QLineEdit * cb=qobject_cast<QLineEdit *>(widget))
{
QString value = (QString)cb->displayText(); QString value = (QString)cb->displayText();
if (units == "hex") { if (units == "hex") {
bool ok; bool ok;
@ -1082,10 +1033,10 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, Q
} else { } else {
return value; return value;
} }
} } else {
else
return QVariant(); return QVariant();
} }
}
/** /**
* Sets a widget from a variant * Sets a widget from a variant
* @param widget pointer for the widget to set * @param widget pointer for the widget to set
@ -1096,42 +1047,30 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, Q
*/ */
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units) bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units)
{ {
if(QComboBox * cb=qobject_cast<QComboBox *>(widget)) if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
{
cb->setCurrentIndex(cb->findText(value.toString())); cb->setCurrentIndex(cb->findText(value.toString()));
return true; return true;
} } else if (QLabel * cb = qobject_cast<QLabel *>(widget)) {
else if(QLabel * cb=qobject_cast<QLabel *>(widget)) if (scale == 0) {
{
if(scale==0)
cb->setText(value.toString()); cb->setText(value.toString());
else } else {
cb->setText(QString::number((value.toDouble() / scale))); cb->setText(QString::number((value.toDouble() / scale)));
return true;
} }
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget)) return true;
{ } else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
cb->setValue((double)(value.toDouble() / scale)); cb->setValue((double)(value.toDouble() / scale));
return true; return true;
} } else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
cb->setValue((int)qRound(value.toDouble() / scale)); cb->setValue((int)qRound(value.toDouble() / scale));
return true; return true;
} } else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
cb->setValue((int)qRound(value.toDouble() / scale)); cb->setValue((int)qRound(value.toDouble() / scale));
return true; return true;
} } else if (QCheckBox * cb = qobject_cast<QCheckBox *>(widget)) {
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
bool bvalue = value.toString() == "TRUE"; bool bvalue = value.toString() == "TRUE";
cb->setChecked(bvalue); cb->setChecked(bvalue);
return true; return true;
} } else if (QLineEdit * cb = qobject_cast<QLineEdit *>(widget)) {
else if(QLineEdit * cb=qobject_cast<QLineEdit *>(widget))
{
if ((scale == 0) || (scale == 1)) { if ((scale == 0) || (scale == 1)) {
if (units == "hex") { if (units == "hex") {
cb->setText(QString::number(value.toUInt(), 16).toUpper()); cb->setText(QString::number(value.toUInt(), 16).toUpper());
@ -1142,10 +1081,10 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou
cb->setText(QString::number((value.toDouble() / scale))); cb->setText(QString::number((value.toDouble() / scale)));
} }
return true; return true;
} } else {
else
return false; return false;
} }
}
/** /**
* Sets a widget from a variant * Sets a widget from a variant
@ -1170,82 +1109,62 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou
*/ */
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; return false;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget)) }
{ if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
if(cb->count()==0) if (cb->count() == 0) {
loadWidgetLimits(cb, field, index, hasLimits, scale); loadWidgetLimits(cb, field, index, hasLimits, scale);
} }
}
QVariant var = field->getValue(index); QVariant var = field->getValue(index);
checkWidgetsLimits(widget, field, index, hasLimits, var, scale); checkWidgetsLimits(widget, field, index, hasLimits, var, scale);
bool ret = setWidgetFromVariant(widget, var, scale, field->getUnits()); bool ret = setWidgetFromVariant(widget, var, scale, field->getUnits());
if(ret) if (ret) {
return true; return true;
else } else {
{
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
return false; 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; return;
if(!field->isWithinLimits(value,index,currentBoard)) }
{ if (!field->isWithinLimits(value, index, currentBoard)) {
if(!widget->property("styleBackup").isValid()) if (!widget->property("styleBackup").isValid()) {
widget->setProperty("styleBackup", widget->styleSheet()); widget->setProperty("styleBackup", widget->styleSheet());
}
widget->setStyleSheet(outOfLimitsStyle); widget->setStyleSheet(outOfLimitsStyle);
widget->setProperty("wasOverLimits", (bool)true); widget->setProperty("wasOverLimits", (bool)true);
if(QComboBox * cb=qobject_cast<QComboBox *>(widget)) if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
{ if (cb->findText(value.toString()) == -1) {
if(cb->findText(value.toString())==-1)
cb->addItem(value.toString()); cb->addItem(value.toString());
} }
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget)) } else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
{ if ((double)(value.toDouble() / scale) > cb->maximum()) {
if((double)(value.toDouble()/scale)>cb->maximum())
{
cb->setMaximum((double)(value.toDouble() / scale)); cb->setMaximum((double)(value.toDouble() / scale));
} } else if ((double)(value.toDouble() / scale) < cb->minimum()) {
else if((double)(value.toDouble()/scale)<cb->minimum())
{
cb->setMinimum((double)(value.toDouble() / scale)); cb->setMinimum((double)(value.toDouble() / scale));
} }
} else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
} if ((int)qRound(value.toDouble() / scale) > cb->maximum()) {
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
if((int)qRound(value.toDouble()/scale)>cb->maximum())
{
cb->setMaximum((int)qRound(value.toDouble() / scale)); 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((int)qRound(value.toDouble()/scale)<cb->minimum()) } else if (QSlider * cb = qobject_cast<QSlider *>(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)); cb->setMinimum((int)qRound(value.toDouble() / scale));
} }
} }
else if(QSlider * cb=qobject_cast<QSlider *>(widget)) } else if (widget->property("wasOverLimits").isValid()) {
{ if (widget->property("wasOverLimits").toBool()) {
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); widget->setProperty("wasOverLimits", (bool)false);
if(widget->property("styleBackup").isValid()) if (widget->property("styleBackup").isValid()) {
{
QString style = widget->property("styleBackup").toString(); QString style = widget->property("styleBackup").toString();
widget->setStyleSheet(style); widget->setStyleSheet(style);
} }
@ -1256,60 +1175,56 @@ void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * fiel
void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double scale) void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double scale)
{ {
if(!widget || !field) if (!widget || !field) {
return; return;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget)) }
{ if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
cb->clear(); cb->clear();
QStringList option = field->getOptions(); QStringList option = field->getOptions();
if(hasLimits) if (hasLimits) {
{ foreach(QString str, option) {
foreach(QString str,option) if (field->isWithinLimits(str, index, currentBoard)) {
{
if(field->isWithinLimits(str,index,currentBoard))
cb->addItem(str); cb->addItem(str);
} }
} }
else } else {
cb->addItems(option); cb->addItems(option);
} }
if(!hasLimits) }
if (!hasLimits) {
return; return;
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget)) } else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
{ if (field->getMaxLimit(index).isValid()) {
if(field->getMaxLimit(index).isValid())
{
cb->setMaximum((double)(field->getMaxLimit(index, currentBoard).toDouble() / scale)); cb->setMaximum((double)(field->getMaxLimit(index, currentBoard).toDouble() / scale));
} }
if(field->getMinLimit(index,currentBoard).isValid()) if (field->getMinLimit(index, currentBoard).isValid()) {
{
cb->setMinimum((double)(field->getMinLimit(index, currentBoard).toDouble() / scale)); cb->setMinimum((double)(field->getMinLimit(index, currentBoard).toDouble() / scale));
} }
} } else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget)) if (field->getMaxLimit(index, currentBoard).isValid()) {
{
if(field->getMaxLimit(index,currentBoard).isValid())
{
cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale)); cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale));
} }
if(field->getMinLimit(index,currentBoard).isValid()) if (field->getMinLimit(index, currentBoard).isValid()) {
{
cb->setMinimum((int)qRound(field->getMinLimit(index, currentBoard).toDouble() / scale)); cb->setMinimum((int)qRound(field->getMinLimit(index, currentBoard).toDouble() / scale));
} }
} } else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
else if(QSlider * cb=qobject_cast<QSlider *>(widget)) if (field->getMaxLimit(index, currentBoard).isValid()) {
{
if(field->getMaxLimit(index,currentBoard).isValid())
{
cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale)); cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale));
} }
if(field->getMinLimit(index,currentBoard).isValid()) if (field->getMinLimit(index, currentBoard).isValid()) {
{
cb->setMinimum((int)(field->getMinLimit(index, currentBoard).toDouble() / scale)); cb->setMinimum((int)(field->getMinLimit(index, currentBoard).toDouble() / scale));
} }
} }
} }
void ConfigTaskWidget::updateEnableControls()
{
TelemetryManager *telMngr = pm->getObject<TelemetryManager>();
Q_ASSERT(telMngr);
enableControls(telMngr->isConnected());
}
void ConfigTaskWidget::disableMouseWheelEvents() void ConfigTaskWidget::disableMouseWheelEvents()
{ {
// Disable mouse wheel events // Disable mouse wheel events
@ -1327,13 +1242,13 @@ void ConfigTaskWidget::disableMouseWheelEvents()
} }
} }
bool ConfigTaskWidget::eventFilter( QObject * obj, QEvent * evt ) { bool ConfigTaskWidget::eventFilter(QObject *obj, QEvent *evt)
{
// Filter all wheel events, and ignore them // Filter all wheel events, and ignore them
if (evt->type() == QEvent::Wheel && if (evt->type() == QEvent::Wheel &&
(qobject_cast<QAbstractSpinBox *>(obj) || (qobject_cast<QAbstractSpinBox *>(obj) ||
qobject_cast<QComboBox *>(obj) || qobject_cast<QComboBox *>(obj) ||
qobject_cast<QAbstractSlider*>( obj ) )) qobject_cast<QAbstractSlider *>(obj))) {
{
evt->ignore(); evt->ignore();
return true; return true;
} }

View File

@ -48,19 +48,16 @@
#include <QUrl> #include <QUrl>
#include <QEvent> #include <QEvent>
class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget: public QWidget class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget : public QWidget {
{
Q_OBJECT Q_OBJECT
public: public:
struct shadow struct shadow {
{
QWidget *widget; QWidget *widget;
double scale; double scale;
bool isLimited; bool isLimited;
}; };
struct objectToWidget struct objectToWidget {
{
UAVObject *object; UAVObject *object;
UAVObjectField *field; UAVObjectField *field;
QWidget *widget; QWidget *widget;
@ -68,7 +65,8 @@ public:
double scale; double scale;
bool isLimited; bool isLimited;
QList<shadow *> shadowsList; QList<shadow *> shadowsList;
QString getUnits() const { QString getUnits() const
{
if (field) { if (field) {
return field->getUnits(); return field->getUnits();
} }
@ -76,19 +74,17 @@ public:
} }
}; };
struct temphelper struct temphelper {
{
quint32 objid; quint32 objid;
quint32 objinstid; 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 }; enum buttonTypeEnum { none, save_button, apply_button, reload_button, default_button, help_button };
struct uiRelationAutomation struct uiRelationAutomation {
{
QString objname; QString objname;
QString fieldname; QString fieldname;
QString element; QString element;
@ -141,7 +137,10 @@ public:
void setDirty(bool value); void setDirty(bool value);
bool allObjectsUpdated(); bool allObjectsUpdated();
void setOutOfLimitsStyle(QString style){outOfLimitsStyle=style;} void setOutOfLimitsStyle(QString style)
{
outOfLimitsStyle = style;
}
void addHelpButton(QPushButton *button, QString url); void addHelpButton(QPushButton *button, QString url);
void forceShadowUpdates(); void forceShadowUpdates();
void forceConnectedState(); void forceConnectedState();
@ -195,6 +194,7 @@ private:
void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale); void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale);
QString outOfLimitsStyle; QString outOfLimitsStyle;
QTimer *timeOut; QTimer *timeOut;
protected slots: protected slots:
virtual void disableObjUpdates(); virtual void disableObjUpdates();
virtual void enableObjUpdates(); virtual void enableObjUpdates();
@ -207,6 +207,7 @@ protected slots:
protected: protected:
virtual void enableControls(bool enable); virtual void enableControls(bool enable);
void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale); void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale);
void updateEnableControls();
}; };
#endif // CONFIGTASKWIDGET_H #endif // CONFIGTASKWIDGET_H

View File

@ -43,17 +43,15 @@ MixerNode::MixerNode(MixerCurveWidget *graphWidget)
setFlag(ItemSendsGeometryChanges); setFlag(ItemSendsGeometryChanges);
setCacheMode(DeviceCoordinateCache); setCacheMode(DeviceCoordinateCache);
setZValue(-1); setZValue(-1);
cmdActive = false;
vertical = false; vertical = false;
cmdNode = false;
cmdToggle = true;
drawNode = true; drawNode = true;
drawText = true; drawText = true;
posColor0 = "#1c870b"; //greenish? positiveColor = "#609FF2"; //blueish?
posColor1 = "#116703"; //greenish? neutralColor = "#14CE24"; //greenish?
negColor0 = "#aa0000"; //red negativeColor = "#EF5F5F"; //redish?
negColor1 = "#aa0000"; //red disabledColor = "#dddddd";
disabledTextColor = "#aaaaaa";
} }
void MixerNode::addEdge(Edge *edge) void MixerNode::addEdge(Edge *edge)
@ -70,7 +68,7 @@ QList<Edge *> MixerNode::edges() const
QRectF MixerNode::boundingRect() 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 QPainterPath MixerNode::shape() const
@ -82,48 +80,50 @@ QPainterPath MixerNode::shape() const
void MixerNode::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *) 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()); painter->setFont(graph->font());
if (drawNode) { if (drawNode) {
QRadialGradient gradient(-3, -3, 10); 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) { if (option->state & QStyle::State_Sunken) {
gradient.setCenter(3, 3); gradient.setCenter(3, 3);
gradient.setFocalPoint(3, 3); gradient.setFocalPoint(3, 3);
gradient.setColorAt(1, Qt::darkBlue); QColor selColor = color.darker();
gradient.setColorAt(0, Qt::darkBlue); gradient.setColorAt(1, selColor.darker());
gradient.setColorAt(0, selColor);
} else { } else {
if (cmdNode) { gradient.setColorAt(0, graph->isEnabled() ? color : disabledColor);
gradient.setColorAt(0, cmdActive ? posColor0 : negColor0); gradient.setColorAt(1, graph->isEnabled() ? color.darker() : disabledColor);
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);
}
}
} }
painter->setBrush(gradient); painter->setBrush(gradient);
painter->setPen(QPen(Qt::black, 0)); painter->setPen(graph->isEnabled() ? QPen(Qt::black, 0) : QPen(disabledTextColor));
painter->drawEllipse(boundingRect()); painter->drawEllipse(boundingRect());
if (!image.isNull()) if (!image.isNull()) {
painter->drawImage(boundingRect().adjusted(1, 1, -1, -1), image); painter->drawImage(boundingRect().adjusted(1, 1, -1, -1), image);
} }
}
if (drawText) { if (drawText) {
if(graph->isEnabled()) {
painter->setPen(QPen(drawNode ? Qt::white : Qt::black, 0)); painter->setPen(QPen(drawNode ? Qt::white : Qt::black, 0));
if (cmdNode) { } else {
painter->drawText(0,4,text); painter->setPen(QPen(disabledTextColor));
}
else {
painter->drawText( (value() < 0) ? -13 : -11, 4, text);
} }
painter->drawText( (value() < 0) ? -10 : -8, 3, text);
} }
} }
@ -131,13 +131,6 @@ void MixerNode::verticalMove(bool flag){
vertical = flag; vertical = flag;
} }
void MixerNode::commandNode(bool enable){
cmdNode = enable;
}
void MixerNode::commandText(QString text){
cmdText = text;
}
double MixerNode::value() { double MixerNode::value() {
double h = graph->sceneRect().height(); double h = graph->sceneRect().height();
double ratio = (h - pos().y()) / h; double ratio = (h - pos().y()) / h;
@ -186,10 +179,6 @@ QVariant MixerNode::itemChange(GraphicsItemChange change, const QVariant &val)
void MixerNode::mousePressEvent(QGraphicsSceneMouseEvent *event) void MixerNode::mousePressEvent(QGraphicsSceneMouseEvent *event)
{ {
if (cmdNode) {
graph->cmdActivated(this);
//return;
}
update(); update();
QGraphicsItem::mousePressEvent(event); QGraphicsItem::mousePressEvent(event);
} }

View File

@ -39,8 +39,7 @@ QT_BEGIN_NAMESPACE
class QGraphicsSceneMouseEvent; class QGraphicsSceneMouseEvent;
QT_END_NAMESPACE QT_END_NAMESPACE
class MixerNode : public QObject,public QGraphicsItem class MixerNode : public QObject, public QGraphicsItem {
{
Q_OBJECT Q_OBJECT
public: public:
MixerNode(MixerCurveWidget *graphWidget); MixerNode(MixerCurveWidget *graphWidget);
@ -48,27 +47,37 @@ public:
QList<Edge *> edges() const; QList<Edge *> edges() const;
enum { Type = UserType + 10 }; enum { Type = UserType + 10 };
int type() const { return Type; } int type() const
{
void setName(QString name) { cmdName = name; } return Type;
const QString& getName() { return cmdName; } }
void verticalMove(bool flag); 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 setPositiveColor(QColor color = "#609FF2")
void setCommandActive(bool enable) { cmdActive = enable; } {
void setToggle(bool enable) { cmdToggle = enable; } positiveColor = color;
bool getToggle() { return cmdToggle; } }
void setPositiveColor(QString color0 = "#00ff00", QString color1 = "#00ff00") { posColor0 = color0; posColor1 = color1; } void setNegativeColor(QColor color = "#EF5F5F")
void setNegativeColor(QString color0 = "#ff0000", QString color1 = "#ff0000") { negColor0 = color0; negColor1 = color1; } {
void setImage(QImage img) { image = img; } negativeColor = color;
void setDrawNode(bool draw) { drawNode = draw; } }
void setDrawText(bool draw) { drawText = draw; }
void setImage(QImage img)
{
image = img;
}
void setDrawNode(bool draw)
{
drawNode = draw;
}
void setDrawText(bool draw)
{
drawText = draw;
}
QRectF boundingRect() const; QRectF boundingRect() const;
QPainterPath shape() const; QPainterPath shape() const;
@ -76,9 +85,6 @@ public:
double value(); double value();
signals:
void commandActivated(QString text);
protected: protected:
QVariant itemChange(GraphicsItemChange change, const QVariant &val); QVariant itemChange(GraphicsItemChange change, const QVariant &val);
@ -89,22 +95,19 @@ private:
QList<Edge *> edgeList; QList<Edge *> edgeList;
QPointF newPos; QPointF newPos;
MixerCurveWidget *graph; MixerCurveWidget *graph;
QString posColor0;
QString posColor1; QColor positiveColor;
QString negColor0; QColor neutralColor;
QString negColor1; QColor negativeColor;
QColor disabledColor;
QColor disabledTextColor;
QImage image; QImage image;
bool vertical; bool vertical;
QString cmdName;
bool cmdActive;
bool cmdNode;
bool cmdToggle;
QString cmdText;
bool drawNode; bool drawNode;
bool drawText; bool drawText;
int index; int index;
}; };
#endif // MIXERCURVEPOINT_H #endif // MIXERCURVEPOINT_H

View File

@ -66,286 +66,42 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent)
plot = new QGraphicsSvgItem(); plot = new QGraphicsSvgItem();
renderer->load(QString(":/uavobjectwidgetutils/images/curve-bg.svg")); renderer->load(QString(":/uavobjectwidgetutils/images/curve-bg.svg"));
plot->setSharedRenderer(renderer); plot->setSharedRenderer(renderer);
//plot->setElementId("map");
scene->addItem(plot); scene->addItem(plot);
plot->setZValue(-1); plot->setZValue(-1);
scene->setSceneRect(plot->boundingRect()); scene->setSceneRect(plot->boundingRect());
setScene(scene); 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); initNodes(MixerCurveWidget::NODE_NUMELEM);
} }
MixerCurveWidget::~MixerCurveWidget() MixerCurveWidget::~MixerCurveWidget()
{ {
while (!nodePool.isEmpty()) while (!nodeList.isEmpty()) {
delete nodePool.takeFirst(); delete nodeList.takeFirst();
while (!edgePool.isEmpty())
delete edgePool.takeFirst();
while (!cmdNodePool.isEmpty())
delete cmdNodePool.takeFirst();
} }
MixerNode* MixerCurveWidget::getCommandNode(int index) while (!edgeList.isEmpty()) {
delete edgeList.takeFirst();
}
}
void MixerCurveWidget::setPositiveColor(QString color)
{ {
MixerNode* node; for (int i=0; i < nodeList.count(); i++) {
MixerNode* node = nodeList.at(i);
if (index >= 0 && index < cmdNodePool.count()) node->setPositiveColor(color);
{
node = cmdNodePool.at(index);
}
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)
{
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; i<nodePool.count(); i++) {
MixerNode* node = nodePool.at(i);
node->setPositiveColor(color0, color1);
}
}
void MixerCurveWidget::setNegativeColor(QString color0, QString color1)
{
negColor0 = color0;
negColor1 = color1;
for (int i=0; i<nodePool.count(); i++) {
MixerNode* node = nodePool.at(i);
node->setNegativeColor(color0, color1);
} }
} }
void MixerCurveWidget::setNegativeColor(QString color)
{
for (int i=0; i < nodeList.count(); i++) {
MixerNode* node = nodeList.at(i);
node->setNegativeColor(color);
}
}
/** /**
Init curve: create a (flat) curve with a specified number of points. 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()) { foreach(Edge *edge, node->edges()) {
if (edge->sourceNode() == node) { if (edge->sourceNode() == node) {
scene()->removeItem(edge); scene()->removeItem(edge);
delete edge;
} }
} }
scene()->removeItem(node); scene()->removeItem(node);
delete node;
} }
nodeList.clear(); nodeList.clear();
@ -382,7 +140,7 @@ void MixerCurveWidget::initNodes(int numPoints)
MixerNode* prevNode = 0; MixerNode* prevNode = 0;
for (int i=0; i < numPoints; i++) { for (int i=0; i < numPoints; i++) {
MixerNode *node = getNode(i); MixerNode *node = new MixerNode(this);
nodeList.append(node); nodeList.append(node);
scene()->addItem(node); scene()->addItem(node);
@ -390,7 +148,7 @@ void MixerCurveWidget::initNodes(int numPoints)
node->setPos(0,0); node->setPos(0,0);
if (prevNode) { if (prevNode) {
scene()->addItem(getEdge(i, prevNode, node)); scene()->addItem(new Edge(prevNode, node));
} }
prevNode = node; prevNode = node;
@ -469,7 +227,6 @@ void MixerCurveWidget::showEvent(QShowEvent *event)
// the result is usually a ahrsbargraph that is way too small. // the result is usually a ahrsbargraph that is way too small.
QRectF rect = plot->boundingRect(); QRectF rect = plot->boundingRect();
resizeCommands();
fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio); fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio);
} }
@ -478,61 +235,17 @@ void MixerCurveWidget::resizeEvent(QResizeEvent* event)
Q_UNUSED(event); Q_UNUSED(event);
QRectF rect = plot->boundingRect(); QRectF rect = plot->boundingRect();
resizeCommands();
fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio); fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio);
} }
void MixerCurveWidget::resizeCommands() void MixerCurveWidget::changeEvent(QEvent *event)
{ {
QRectF rect = plot->boundingRect(); QGraphicsView::changeEvent(event);
if(event->type() == QEvent::EnabledChange) {
MixerNode* node; foreach (MixerNode *node, nodeList) {
//popup node->update();
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);
} }
//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) void MixerCurveWidget::itemMoved(double itemValue)
@ -575,87 +288,3 @@ double MixerCurveWidget::setRange(double min, double max)
return curveMax - curveMin; return curveMax - curveMin;
} }
MixerNode* MixerCurveWidget::getCmdNode(const QString& name)
{
MixerNode* node = 0;
for (int i=0; i<cmdNodePool.count(); i++) {
MixerNode* n = cmdNodePool.at(i);
if (n->getName() == name)
node = n;
}
return node;
}
void MixerCurveWidget::setCommandText(const QString& name, const QString& text)
{
for (int i=0; i<cmdNodePool.count(); i++) {
MixerNode* n = cmdNodePool.at(i);
if (n->getName() == name) {
n->commandText(text);
n->update();
}
}
}
void MixerCurveWidget::activateCommand(const QString& name)
{
for (int i=1; i<cmdNodePool.count()-2; i++) {
MixerNode* node = cmdNodePool.at(i);
node->setCommandActive(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; i<cmdNodePool.count()-2; i++) {
MixerNode* node = cmdNodePool.at(i);
if (show)
node->show();
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; i<cmdNodePool.count()-2; i++) {
MixerNode* n = cmdNodePool.at(i);
n->setCommandActive(false);
n->update();
}
node->setCommandActive(true);
}
}
node->update();
emit commandActivated(node);
}

View File

@ -37,8 +37,7 @@
#include "mixercurveline.h" #include "mixercurveline.h"
#include "uavobjectwidgetutils_global.h" #include "uavobjectwidgetutils_global.h"
class UAVOBJECTWIDGETUTILS_EXPORT MixerCurveWidget : public QGraphicsView class UAVOBJECTWIDGETUTILS_EXPORT MixerCurveWidget : public QGraphicsView {
{
Q_OBJECT Q_OBJECT
public: public:
@ -58,55 +57,34 @@ public:
double getMax(); double getMax();
double setRange(double min, double max); 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: signals:
void curveUpdated(); void curveUpdated();
void curveMinChanged(double value); void curveMinChanged(double value);
void curveMaxChanged(double value); void curveMaxChanged(double value);
void commandActivated(MixerNode* node);
private slots: private slots:
private: private:
QGraphicsSvgItem *plot; QGraphicsSvgItem *plot;
QList<MixerNode*> nodePool; QList<Edge *> edgeList;
QList<MixerNode*> cmdNodePool;
QList<Edge*> edgePool;
QList<MixerNode *> nodeList; QList<MixerNode *> nodeList;
double curveMin; double curveMin;
double curveMax; double curveMax;
bool curveUpdating; bool curveUpdating;
QString posColor0;
QString posColor1;
QString negColor0;
QString negColor1;
void initNodes(int numPoints); void initNodes(int numPoints);
MixerNode* getNode(int index); void setPositiveColor(QString color);
MixerNode* getCommandNode(int index); void setNegativeColor(QString color);
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: protected:
void showEvent(QShowEvent *event); void showEvent(QShowEvent *event);
void resizeEvent(QResizeEvent *event); void resizeEvent(QResizeEvent *event);
void changeEvent(QEvent *event);
}; };
#endif /* MIXERCURVEWIDGET_H_ */ #endif /* MIXERCURVEWIDGET_H_ */

View File

@ -12,18 +12,23 @@ namespace Ui {
class PopupWidget; class PopupWidget;
} }
class UAVOBJECTWIDGETUTILS_EXPORT PopupWidget : public QDialog class UAVOBJECTWIDGETUTILS_EXPORT PopupWidget : public QDialog {
{
Q_OBJECT Q_OBJECT
public: public:
explicit PopupWidget(QWidget *parent = 0); explicit PopupWidget(QWidget *parent = 0);
void popUp(QWidget *widget = 0); void popUp(QWidget *widget = 0);
void setWidget(QWidget *widget); void setWidget(QWidget *widget);
QWidget* getWidget() { return m_widget; }
QHBoxLayout* getLayout() { return m_layout; }
signals: QWidget *getWidget()
{
return m_widget;
}
QHBoxLayout *getLayout()
{
return m_layout;
}
public slots: public slots:
bool close(); bool close();

View File

@ -37,11 +37,12 @@
#include "uavobjectutilmanager.h" #include "uavobjectutilmanager.h"
#include <QObject> #include <QObject>
#include <QDebug> #include <QDebug>
class smartSaveButton:public QObject
{ class smartSaveButton : public QObject {
enum buttonTypeEnum { save_button, apply_button }; enum buttonTypeEnum { save_button, apply_button };
public: public:
Q_OBJECT Q_OBJECT
public: public:
smartSaveButton(); smartSaveButton();
void addButtons(QPushButton *save, QPushButton *apply); void addButtons(QPushButton *save, QPushButton *apply);
@ -53,14 +54,17 @@ public:
void addApplyButton(QPushButton *apply); void addApplyButton(QPushButton *apply);
void addSaveButton(QPushButton *save); void addSaveButton(QPushButton *save);
void resetIcons(); void resetIcons();
signals: signals:
void preProcessOperations(); void preProcessOperations();
void saveSuccessfull(); void saveSuccessfull();
void beginOp(); void beginOp();
void endOp(); void endOp();
public slots: public slots:
void apply(); void apply();
void save(); void save();
private slots: private slots:
void processClick(); void processClick();
void processOperation(QPushButton *button, bool save); void processOperation(QPushButton *button, bool save);
@ -75,10 +79,9 @@ private:
QEventLoop loop; QEventLoop loop;
QList<UAVDataObject *> objects; QList<UAVDataObject *> objects;
QMap<QPushButton *, buttonTypeEnum> buttonList; QMap<QPushButton *, buttonTypeEnum> buttonList;
protected:
public slots: public slots:
void enableControls(bool value); void enableControls(bool value);
}; };

View File

@ -120,6 +120,7 @@ CFLAGS += -mapcs-frame
CFLAGS += -fomit-frame-pointer CFLAGS += -fomit-frame-pointer
CFLAGS += -Wall -Wextra CFLAGS += -Wall -Wextra
CFLAGS += -Wfloat-equal -Wunsuffixed-float-constants -Wdouble-promotion CFLAGS += -Wfloat-equal -Wunsuffixed-float-constants -Wdouble-promotion
CFLAGS += -Wshadow
CFLAGS += -Werror CFLAGS += -Werror
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I.
CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<))))

View File

@ -8,6 +8,8 @@
<field name="PressureNoise" units="m" type="float" elements="1" defaultvalue="0.4"/> <field name="PressureNoise" units="m" type="float" elements="1" defaultvalue="0.4"/>
<field name="AccelNoise" units="m/s^2" type="float" elements="1" defaultvalue="5"/> <field name="AccelNoise" units="m/s^2" type="float" elements="1" defaultvalue="5"/>
<field name="AccelDrift" units="m/s^2" type="float" elements="1" defaultvalue="0.001"/> <field name="AccelDrift" units="m/s^2" type="float" elements="1" defaultvalue="0.001"/>
<field name="ThrottleExp" units="" type="uint8" elements="1" defaultvalue="128"/>
<field name="ThrottleRate" units="m/s" type="uint8" elements="1" defaultvalue="5"/>
<access gcs="readwrite" flight="readwrite"/> <access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/> <telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/> <telemetryflight acked="true" updatemode="onchange" period="0"/>