mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-03 11:24:10 +01:00
OP-935 Renames 'Camera stab' to 'Gimbal'. Adds functionality to store-clear and recall board rotation during calibration.
This commit is contained in:
parent
c7d42c876e
commit
3b7c274c78
@ -104,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);
|
||||||
|
@ -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
|
||||||
@ -1045,11 +1117,31 @@ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object)
|
|||||||
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->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);
|
||||||
|
}
|
||||||
|
@ -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
|
||||||
|
@ -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,8 +16,11 @@
|
|||||||
<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>false</bool>
|
||||||
|
</property>
|
||||||
<property name="currentIndex">
|
<property name="currentIndex">
|
||||||
<number>0</number>
|
<number>1</number>
|
||||||
</property>
|
</property>
|
||||||
<widget class="QWidget" name="tab_2">
|
<widget class="QWidget" name="tab_2">
|
||||||
<attribute name="title">
|
<attribute name="title">
|
||||||
@ -499,28 +502,275 @@ p, li { white-space: pre-wrap; }
|
|||||||
<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="Minimum">
|
||||||
|
<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><html><head/><body><p>This information must be set to enable calibration the Revolution controllers sensors. <br/>Set home location using context menu in the map widget.</p></body></html></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 +782,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 +1009,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>
|
||||||
|
Loading…
Reference in New Issue
Block a user