mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-17 02:52:12 +01:00
OP-716 Added default TauAccel == 0.15 to wizard.
This commit is contained in:
parent
95455e2378
commit
2eeba593db
@ -211,13 +211,6 @@ void ConfigCCAttitudeWidget::openHelp()
|
||||
|
||||
void ConfigCCAttitudeWidget::setAccelFiltering(bool active)
|
||||
{
|
||||
AttitudeSettings* settings = AttitudeSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(settings);
|
||||
AttitudeSettings::DataFields data = settings->getData();
|
||||
|
||||
data.AccelTau = active ? DEFAULT_ENABLED_ACCEL_TAU : 0.0f;
|
||||
|
||||
settings->setData(data);
|
||||
setDirty(true);
|
||||
}
|
||||
|
||||
@ -226,6 +219,9 @@ void ConfigCCAttitudeWidget::enableControls(bool enable)
|
||||
if(ui->zeroBias) {
|
||||
ui->zeroBias->setEnabled(enable);
|
||||
}
|
||||
if(ui->zeroGyroBiasOnArming) {
|
||||
ui->zeroGyroBiasOnArming->setEnabled(enable);
|
||||
}
|
||||
if(ui->accelFiltering) {
|
||||
ui->accelFiltering->setEnabled(enable);
|
||||
}
|
||||
@ -244,6 +240,14 @@ void ConfigCCAttitudeWidget::refreshWidgetsValues(UAVObject *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);
|
||||
|
@ -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()
|
||||
|
@ -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.15;
|
||||
|
||||
VehicleConfigurationSource *m_configSource;
|
||||
UAVObjectManager *m_uavoManager;
|
||||
|
Loading…
x
Reference in New Issue
Block a user