mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-29 14:52:12 +01:00
OP-716 Replaced AccelTau checkbox with numeric spinbox. Max value was set to 0,20 and min value to 0,00, step size 0,01. Added tooltip hinting to set to 0 to disable.
This commit is contained in:
parent
1695fda4e2
commit
a0cb604e32
@ -367,30 +367,90 @@ margin:1px;</string>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<widget class="QCheckBox" name="zeroGyroBiasOnArming">
|
||||
<property name="toolTip">
|
||||
<string>If enabled, a fast recalibration of gyro zero point will be done
|
||||
<widget class="QCheckBox" name="zeroGyroBiasOnArming">
|
||||
<property name="toolTip">
|
||||
<string>If enabled, a fast recalibration of gyro zero point will be done
|
||||
whenever the frame is armed. Do not move the airframe while
|
||||
arming it in that case!</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Zero gyros while arming aircraft</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>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_4">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set value to 0 to disable accelerators filtering.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Zero gyros while arming aircraft</string>
|
||||
<string>AccelTau</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="accelFiltering">
|
||||
<property name="text">
|
||||
<string>Accel filtering</string>
|
||||
<spacer name="horizontalSpacer_12">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QDoubleSpinBox" name="accelTauSpinnbox">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>60</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set value to 0 to disable accelerators filtering.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>0.200000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_6">
|
||||
<spacer name="horizontalSpacer_11">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
|
@ -57,8 +57,8 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
|
||||
// Connect the help button
|
||||
connect(ui->ccAttitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
connect(ui->accelFiltering, SIGNAL(toggled(bool)), this, SLOT(setAccelFiltering(bool)));
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings","ZeroDuringArming",ui->zeroGyroBiasOnArming);
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "AccelTau", ui->accelTauSpinnbox);
|
||||
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->rollBias,AttitudeSettings::BOARDROTATION_ROLL);
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->pitchBias,AttitudeSettings::BOARDROTATION_PITCH);
|
||||
@ -75,8 +75,8 @@ ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget()
|
||||
void ConfigCCAttitudeWidget::sensorsUpdated(UAVObject * obj) {
|
||||
|
||||
if (!timer.isActive()) {
|
||||
// ignore updates that come in after the timer has expired
|
||||
return;
|
||||
// ignore updates that come in after the timer has expired
|
||||
return;
|
||||
}
|
||||
|
||||
Accels * accels = Accels::GetInstance(getObjectManager());
|
||||
@ -222,33 +222,14 @@ void ConfigCCAttitudeWidget::enableControls(bool enable)
|
||||
if(ui->zeroGyroBiasOnArming) {
|
||||
ui->zeroGyroBiasOnArming->setEnabled(enable);
|
||||
}
|
||||
if(ui->accelFiltering) {
|
||||
ui->accelFiltering->setEnabled(enable);
|
||||
if(ui->accelTauSpinnbox) {
|
||||
ui->accelTauSpinnbox->setEnabled(enable);
|
||||
}
|
||||
ConfigTaskWidget::enableControls(enable);
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
{
|
||||
AttitudeSettings* settings = AttitudeSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(settings);
|
||||
AttitudeSettings::DataFields data = settings->getData();
|
||||
ui->accelFiltering->setChecked(data.AccelTau > 0.0f);
|
||||
|
||||
ConfigTaskWidget::refreshWidgetsValues(obj);
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::updateObjectsFromWidgets()
|
||||
{
|
||||
AttitudeSettings* settings = AttitudeSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(settings);
|
||||
AttitudeSettings::DataFields data = settings->getData();
|
||||
|
||||
data.AccelTau = ui->accelFiltering->isChecked() ? DEFAULT_ENABLED_ACCEL_TAU : 0.0f;
|
||||
|
||||
settings->setData(data);
|
||||
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
|
||||
ui->zeroBiasProgress->setValue(0);
|
||||
}
|
||||
|
@ -72,9 +72,6 @@ private:
|
||||
protected:
|
||||
virtual void enableControls(bool enable);
|
||||
|
||||
protected slots:
|
||||
void refreshWidgetsValues(UAVObject * obj=NULL);
|
||||
|
||||
};
|
||||
|
||||
#endif // CCATTITUDEWIDGET_H
|
||||
|
Loading…
x
Reference in New Issue
Block a user