1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-01 09:24:10 +01:00

Merge branch 'thread/OP-716' into rel-12.10.2

This commit is contained in:
Oleg Semyonov 2012-11-21 17:19:45 +02:00
commit 56dba23d2a
5 changed files with 107 additions and 11 deletions

View File

@ -111,7 +111,7 @@
<x>0</x>
<y>0</y>
<width>750</width>
<height>466</height>
<height>483</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
@ -391,6 +391,86 @@ arming it in that case!</string>
</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/>
</property>
<property name="text">
<string>AccelTau</string>
</property>
</widget>
</item>
<item>
<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="accelTauSpinbox">
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Accelerometer filtering.
Sets the amount of lowpass filtering of accelerometer data
for the attitude estimation. Higher values apply a stronger
filter, which may help with drifting in attitude mode.
Range: 0.00 - 0.20, Good starting value: 0.05 - 0.10
Start low and raise until drift stops.
A setting of 0.00 disables the filter.</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_11">
<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>
</layout>

View File

@ -56,7 +56,9 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
// Connect the help button
connect(ui->ccAttitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
addUAVObjectToWidgetRelation("AttitudeSettings","ZeroDuringArming",ui->zeroGyroBiasOnArming);
addUAVObjectToWidgetRelation("AttitudeSettings", "AccelTau", ui->accelTauSpinbox);
addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->rollBias,AttitudeSettings::BOARDROTATION_ROLL);
addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->pitchBias,AttitudeSettings::BOARDROTATION_PITCH);
@ -73,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());
@ -207,16 +209,27 @@ void ConfigCCAttitudeWidget::openHelp()
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/44Cf", QUrl::StrictMode) );
}
void ConfigCCAttitudeWidget::setAccelFiltering(bool active)
{
setDirty(true);
}
void ConfigCCAttitudeWidget::enableControls(bool enable)
{
if(ui->zeroBias)
if(ui->zeroBias) {
ui->zeroBias->setEnabled(enable);
}
if(ui->zeroGyroBiasOnArming) {
ui->zeroGyroBiasOnArming->setEnabled(enable);
}
if(ui->accelTauSpinbox) {
ui->accelTauSpinbox->setEnabled(enable);
}
ConfigTaskWidget::enableControls(enable);
}
void ConfigCCAttitudeWidget::updateObjectsFromWidgets()
{
ConfigTaskWidget::updateObjectsFromWidgets();
ui->zeroBiasProgress->setValue(0);
}

View File

@ -52,6 +52,7 @@ private slots:
void timeout();
void startAccelCalibration();
void openHelp();
void setAccelFiltering(bool active);
private:
Ui_ccattitude *ui;
@ -65,6 +66,7 @@ private:
QList<double> x_accum, y_accum, z_accum;
QList<double> x_gyro_accum, y_gyro_accum, z_gyro_accum;
static const float DEFAULT_ENABLED_ACCEL_TAU = 0.1;
static const int NUM_SENSOR_UPDATES = 300;
static const float ACCEL_SCALE = 0.004f * 9.81f;
protected:

View File

@ -292,12 +292,12 @@ void VehicleConfigurationHelper::applyFlighModeConfiguration()
void VehicleConfigurationHelper::applyLevellingConfiguration()
{
AttitudeSettings* attitudeSettings = AttitudeSettings::GetInstance(m_uavoManager);
Q_ASSERT(attitudeSettings);
AttitudeSettings::DataFields data = attitudeSettings->getData();
if(m_configSource->isLevellingPerformed())
{
accelGyroBias bias = m_configSource->getLevellingBias();
AttitudeSettings* attitudeSettings = AttitudeSettings::GetInstance(m_uavoManager);
Q_ASSERT(attitudeSettings);
AttitudeSettings::DataFields data = attitudeSettings->getData();
data.AccelBias[0] += bias.m_accelerometerXBias;
data.AccelBias[1] += bias.m_accelerometerYBias;
@ -305,10 +305,10 @@ void VehicleConfigurationHelper::applyLevellingConfiguration()
data.GyroBias[0] = -bias.m_gyroXBias;
data.GyroBias[1] = -bias.m_gyroYBias;
data.GyroBias[2] = -bias.m_gyroZBias;
attitudeSettings->setData(data);
addModifiedObject(attitudeSettings, tr("Writing gyro and accelerometer bias settings"));
}
data.AccelTau = DEFAULT_ENABLED_ACCEL_TAU;
attitudeSettings->setData(data);
addModifiedObject(attitudeSettings, tr("Writing gyro and accelerometer bias settings"));
}
void VehicleConfigurationHelper::applyStabilizationConfiguration()

View File

@ -68,6 +68,7 @@ private:
static const int MIXER_TYPE_DISABLED = 0;
static const int MIXER_TYPE_MOTOR = 1;
static const int MIXER_TYPE_SERVO = 2;
static const float DEFAULT_ENABLED_ACCEL_TAU = 0.1;
VehicleConfigurationSource *m_configSource;
UAVObjectManager *m_uavoManager;