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:
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/CREDITS.html b/ground/openpilotgcs/src/plugins/coreplugin/CREDITS.html
index cd1c8661d..e61d5f9ed 100644
--- a/ground/openpilotgcs/src/plugins/coreplugin/CREDITS.html
+++ b/ground/openpilotgcs/src/plugins/coreplugin/CREDITS.html
@@ -7,6 +7,7 @@ Without the work of the people in this file OpenPilot would not be what it is to
Connor Abbott
David Ankers
+Sergiy Anikeyev
Pedro Assuncao
Fredrik Arvidsson
Werner Backes
@@ -16,6 +17,7 @@ David Carlson
James Cotton
Steve Doll
Piotr Esden-Tempski
+Richard Flay
Peter Farnworth
Ed Faulkner
Darren Furniss
@@ -23,6 +25,7 @@ Frederic Goddeeris
Daniel Godin
Bani Greyling
Nuno Guedes
+Erik Gustavsson
Peter Gunnarsson
Dean Hall
Joe Hlebasko
diff --git a/ground/openpilotgcs/src/plugins/importexport/importexportgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/importexport/importexportgadgetwidget.cpp
index 6e1d4d2c3..35d4696a0 100644
--- a/ground/openpilotgcs/src/plugins/importexport/importexportgadgetwidget.cpp
+++ b/ground/openpilotgcs/src/plugins/importexport/importexportgadgetwidget.cpp
@@ -199,8 +199,7 @@ void ImportExportGadgetWidget::importConfiguration(const QString& fileName)
void ImportExportGadgetWidget::on_helpButton_clicked()
{
- qDebug() << "Show Help";
- QDesktopServices::openUrl(QUrl("http://wiki.openpilot.org/Import_Export_plugin"));
+ QDesktopServices::openUrl(QUrl("http://wiki.openpilot.org/x/OQBj"));
}
diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui
index 762980787..34c29e8c0 100644
--- a/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui
+++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui
@@ -57,13 +57,13 @@ p, li { white-space: pre-wrap; }
-
- Calculate gyro and accelerometer bias
+ Upgrade now
QToolButton { border: none }
- Calculate
+ Upgrade
diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp
index 2c86dc2e1..d62fdd1e3 100644
--- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp
+++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp
@@ -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()
diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h
index 44f2125b1..b72e40f63 100644
--- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h
+++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h
@@ -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;
diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp
index 715b237b7..d4ef26ba6 100755
--- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp
+++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp
@@ -28,6 +28,7 @@
#include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h"
#include
#include
+#include "flightstatus.h"
#define DFU_DEBUG true
@@ -49,7 +50,7 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent)
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()));
- connect(m_config->haltButton, SIGNAL(clicked()), this, SLOT(goToBootloader()));
+ connect(m_config->haltButton, SIGNAL(clicked()), this, SLOT(systemHalt()));
connect(m_config->resetButton, SIGNAL(clicked()), this, SLOT(systemReset()));
connect(m_config->bootButton, SIGNAL(clicked()), this, SLOT(systemBoot()));
connect(m_config->safeBootButton, SIGNAL(clicked()), this, SLOT(systemSafeBoot()));
@@ -120,6 +121,18 @@ void UploaderGadgetWidget::connectSignalSlot(QWidget *widget)
connect(qobject_cast(widget),SIGNAL(uploadStarted()),this,SLOT(uploadStarted()));
connect(qobject_cast(widget),SIGNAL(uploadEnded(bool)),this,SLOT(uploadEnded(bool)));
}
+
+FlightStatus *UploaderGadgetWidget::getFlightStatus()
+{
+ ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
+ Q_ASSERT(pm);
+ UAVObjectManager *objManager = pm->getObject();
+ Q_ASSERT(objManager);
+ FlightStatus *status = dynamic_cast(objManager->getObject(QString("FlightStatus")));
+ Q_ASSERT(status);
+ return status;
+}
+
void UploaderGadgetWidget::onPhisicalHWConnect()
{
m_config->bootButton->setEnabled(false);
@@ -348,6 +361,26 @@ void UploaderGadgetWidget::goToBootloader(UAVObject* callerObj, bool success)
}
+void UploaderGadgetWidget::systemHalt()
+{
+ FlightStatus* status = getFlightStatus();
+
+ // The board can not be halted when in armed state.
+ // If board is armed, or arming. Show message with notice.
+ if (status->getArmed() == FlightStatus::ARMED_DISARMED) {
+ goToBootloader();
+ }
+ else {
+ QMessageBox mbox(this);
+ mbox.setText(QString(tr("The controller board is armed and can not be halted.\n\n"
+ "Please make sure the board is not armed and then press halt again to proceed\n"
+ "or use the rescue option to force a firmware upgrade.")));
+ mbox.setStandardButtons(QMessageBox::Ok);
+ mbox.setIcon(QMessageBox::Warning);
+ mbox.exec();
+ }
+}
+
/**
Tell the mainboard to reset:
- Send the relevant IAP commands
@@ -355,14 +388,29 @@ void UploaderGadgetWidget::goToBootloader(UAVObject* callerObj, bool success)
*/
void UploaderGadgetWidget::systemReset()
{
- resetOnly = true;
- if (dfu) {
- delete dfu;
- dfu = NULL;
+ FlightStatus* status = getFlightStatus();
+
+ // The board can not be reset when in armed state.
+ // If board is armed, or arming. Show message with notice.
+ if (status->getArmed() == FlightStatus::ARMED_DISARMED) {
+ resetOnly = true;
+ if (dfu) {
+ delete dfu;
+ dfu = NULL;
+ }
+ m_config->textBrowser->clear();
+ log("Board Reset initiated.");
+ goToBootloader();
+ }
+ else {
+ QMessageBox mbox(this);
+ mbox.setText(QString(tr("The controller board is armed and can not be reset.\n\n"
+ "Please make sure the board is not armed and then press reset again to proceed\n"
+ "or power cycle to force a board reset.")));
+ mbox.setStandardButtons(QMessageBox::Ok);
+ mbox.setIcon(QMessageBox::Warning);
+ mbox.exec();
}
- m_config->textBrowser->clear();
- log("Board Reset initiated.");
- goToBootloader();
}
void UploaderGadgetWidget::systemBoot()
@@ -381,7 +429,6 @@ void UploaderGadgetWidget::systemSafeBoot()
*/
void UploaderGadgetWidget::commonSystemBoot(bool safeboot)
{
-
clearLog();
m_config->bootButton->setEnabled(false);
m_config->safeBootButton->setEnabled(false);
@@ -828,6 +875,5 @@ void UploaderGadgetWidget::versionMatchCheck()
void UploaderGadgetWidget::openHelp()
{
-
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/AoBZ", QUrl::StrictMode) );
}
diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h
index 67b988a38..9f4702e2f 100755
--- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h
+++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h
@@ -61,6 +61,8 @@
using namespace OP_DFU;
using namespace uploader;
+class FlightStatus;
+
class UPLOADER_EXPORT UploaderGadgetWidget : public QWidget
{
Q_OBJECT
@@ -94,12 +96,14 @@ private:
QErrorMessage * msg;
void connectSignalSlot(QWidget * widget);
int autoUpdateConnectTimeout;
+ FlightStatus * getFlightStatus();
private slots:
void onPhisicalHWConnect();
void versionMatchCheck();
void error(QString errorString,int errorNumber);
void info(QString infoString,int infoNumber);
void goToBootloader(UAVObject* = NULL, bool = false);
+ void systemHalt();
void systemReset();
void systemBoot();
void systemSafeBoot();
diff --git a/package/osx/OpenPilot.dmg b/package/osx/OpenPilot.dmg
index 48e7c6a76..db7496de3 100644
Binary files a/package/osx/OpenPilot.dmg and b/package/osx/OpenPilot.dmg differ
diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml
index b1b541310..bdc3971b7 100644
--- a/shared/uavobjectdefinition/stabilizationsettings.xml
+++ b/shared/uavobjectdefinition/stabilizationsettings.xml
@@ -35,6 +35,8 @@
+
+