1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-20 10:54:14 +01:00

Merge remote-tracking branch 'origin/rel-12.10.2' into next

Conflicts:
	MILESTONES.txt
This commit is contained in:
Oleg Semyonov 2012-11-29 17:31:50 +02:00
commit ea1199603b
18 changed files with 236 additions and 101 deletions

View File

@ -6,47 +6,41 @@ It is sorted alphabetically by name and formatted so that it allows for easy gre
The fields are:
Name (N)
Email (E),
Description of work (D)
Current maintainer function (M)
----------
N: Connor Abbott
E: connor (at) abbott (dot) cx
D: Win32 OpenPilot port
N: David Ankers
E: david (at) openpilot (dot) org
D: Co-founder, Project Coordination
D: Minor GCS infrastructure, updating the credit file
M: Admin
N: Sergiy Anikeyev
D: Improvments to Camera Gimbal control
N: Pedro Assuncao
E: pedro (dot) agda (plus) openpilot (at) gmail (dot) com
D: Initial GCS Settings Gadget work
N: Fredrik Arvidsson
E: fredrik (at) arvidssons (dot) org
W: GCS Setup Wizard
D: GCS Setup Wizard
M: GCS Setup Wizard
N: Werner Backes
E: werner (at) bit-1 (dot) de
D: Port of CopterControl to PS3 Move Controller (MoveCopter)
N: Jose Barros
E: josembarros (at) hotmail (dot) com
D: Next-Gen OP Map Lib, Y-Modem Library, Uploader Plugin
D: OP Bootloader, AHRS Bootloader, OPUploadTool and much else
M: Bootloader, OP MAP Lib
N: David "Buzz" Carlson
E: chebuzz (plus) openpilot (at) gmail (dot) com
D: 3D ModelView GCS Plugin, sponsor of HITL merge work and XPlane addition
N: James Cotton
E: peabody124 (plus) openpilot (at) gmail (dot) com
D: Multiplatform HID implementation (firmware & GCS), GCS Joystick control
D: Posix OpenPilot work and Mac implementation
D: Firmware implementation of Professor Schinstock's INS/GPS
@ -54,187 +48,154 @@ D: Android GCS and much else
M: Architecture co-lead, Android GCS Lead
N: Steve Doll
E: speakfree07 (at) hotmail (dot) com
D: Much Artwork, Logo rework, Welcome page design
N: Piotr Esden-Tempski
E: esden (at) esden (dot) net
D: Floss-JTAG Rev A, 4-layer initial design
N: Richard Flay
D: Multiple fixes / Review guru
N: Darren Furniss
E: furnibird (plus) openpilot (at) gmail (dot) com
W: GCS Artwork and Android GCS Artwork
D: GCS Artwork and Android GCS Artwork
N: Frederic Goddeeris
E: fredericgoddeeris (at) hotmail (dot) com
D: I2C work and FreeRTOS work, MK integration
D: EagleTree OSD implementation
N: Daniel Godin
E: dgodin (at) dnsct (dot) com
W: Sponsor: Notify Plugin for the GCS
D: Sponsor: Notify Plugin for the GCS
N: Bani Greyling
E: bani (dot) greyling (plus) openpilot (at) gmail (dot) com
D: GCS Scope plugin
N: Nuno Guedes
E: muralha (plus) openpilot (at) gmail (dot) com
D: 3D artwork, moving surfaces and work on ModelView
D: PFD Artwork
N: Erik Gustavsson
D: Attitude LPF improvments to Self Level
N: Peter Gunnarsson
E: peter (at) pyne (dot) se
D: GCS Core Developer
D: Multiple GCS plugins, Gadget foundations, UAVObject viewer
N: Dean Hall
E: dwhall256 (plus) openpilot (at) gmail (dot) com
D: Creator of http://pythononachip.org
N: Joe Hlebasko
E: joe (dot) hlebasko(plus) openpilot (at) gmail (dot) com
D: Early versions of Main Board & Production OP GPS
M: Hardware Architecture Team
N: Andy Honecker
E: andywh (at) yahoo (dot) com
D: Hardware design review and optimisation
N: Mark James
E: mjames (plus) openpilot (at) gmail (dot) com
D: Some of Silk Icon set used in GCS - http://www.famfamfam.com/lab/icons/silk
N: Sami Korhonen
E: samik (dot) korhonen (plus) openpilot (at) gmail (dot) com
D: GPS Module, Spektrum RC Module, OSD work
M: OpenPilot OSD
N: Thorsten Klose
E: thorsten (dot) klose (at) dmx (dot) de
D: Embedded STM32 infrastructure
N: Hallvard Kristiansen
E: hal (at) fleshmx (dot) com
D: GCS Artwork, Quad layout diagrams
N: Mike Labranche
E: mdlabranche (plus) openpilot (at) gmail (dot) com
D: Tab bar Telem Monitor
N: Edouard Lafargue
E: edouard (at) lafargue (dot) name
D: GCS Dial Plugins, GCS PFD Plugin, GCS GPS plugin, GCS Config plugin
D: Artwork including standard display dials
N: Matt Lipski
E: mattlipski (plus) openpilot (at) gmail (dot) com
D: Deluxe Dials Set artwork, (Artificial Horizon, Compass, Turn Indicator)
N: Les Newell
E: les (dot) newell (at) fastmail (dot) co (dot) uk
D: Advanced mixer matrix, SPI protocol based on UAVObjects, feedforward
N: Ken Northup
E: helos360 (at) bellsouth (dot) net
D: 3D Modelling, Easystar adaption from FMS
N: Guy McCaldin
E: guymcc (at) gmail (dot) com
D: Artwork and design including work on the Deluxe Dial Set
N: Cathy Moss
E: cmoss296 (at) blueyonder (dot) co (dot) uk
D: Hardware design Lead: Gen 2 Mainboard, PipXtreme, Current Sensor
D: PipXtreme designer, creator OP Map Plugin
N: Angus Peart
E: gussy (at) openpilot (dot) org
D: Co-founder, Principal hardware architect.
D: Hardware design of early OpenPilot, AHRS, GPS and other hardware
N: Dmytro Poplavskiy
E: dmytro (dot) poplavskiy (plus) openpilot (at) gmail (dot) com
W: QML PFD, QML Welcome page
D: QML PFD, QML Welcome page
M: Qml plugins
N: Eric Price
E: corvus (dot) corax (at) cybertrench (dot) com
D: IL2 HITL GCS Plugin, Posix OpenPilot, Advanced stabilisation module
M: SITL Posix, SLAM work
N: Richard Querin
E: rfquerin (plus) openpilot (at) gmail (dot) com
D: Graphic Design, OpenPilot Logo
N: Laurent Ribon
E: ribon (dot) l (at) club-internet (dot) fr
D: The GLC_lib as used in the ModelView Plugin
D: See: http://www.glc-lib.net/
N: Julien Rouviere
E: julien (dot) rouviere (plus) openpilot (at) gmail (dot) com
D: GCS Framework and Plugins for the GCS
N: Zik Saleeba
E: zik (at) zikzak (dot) net
D: Initial schematic based on Zik's Flying Fox schematic
N: Professor Dale Schinstock
E: dales (at) ksu (dot) edu
D: Lead AHRS Developer
D: Lead INS Developer
D: Creator of the OpenPilot INS / EKF
N: Professor Kenn Sebesta
E: kenn (at) openpilot (dot) org
D: Lead Fixed Wing Developer
M: Fixed Wing support
D: Lead Fixed Wing Developer CC3D / Controls
D: GCS improvments including HiTL Merge
M: Fixed Wing support CC3D
N: Oleg Semyonov
E: os-openpilot-org (at) os-propo (dot) info
D: Core tester & Project organisation
D: Core Developer & Project organisation
D: TxPID module
M: CameraStab module
M: Common part of multi-platform packaging system
M: Windows NSIS Installer
M: Russian Documentation Lead
N: Stacey Sheldon
E: stac (at) solidgoldbomb (dot) org
D: Core Embedded Developer
D: SPI protocol for AHRS, I2C rewrite and much core work
N: Troy Schultz
E: troy (dot) schultz (at) rogers (dot) com
D: INS design review and optimisation
N: Dr. Erhard Siegl
E: Erhard (dot) Siegl (at) zogazoga (dot) at
D: Configuration engine for the GCS
N: Pete Stapley
E: pete (at) stapleylabs (dot) com
D: PPM inputs
N: Rowan Taubitz
E: rowan (at) zantek (dot) com (dot) au
D: Hardware debugging and testing, creation of 2-layer Floss-JTAG Rev B
D: Creation of Next-Gen FOSS-JTAG board
N: Andrew Thoms
E: electronics (at) andrewspizza (dot) net
D: IP Telemtry plugin for the GCS
D: Helicopter support code and mixing for CCPM
N: Vassilis Varveropoulos
E: vassilis (at) openpilot (dot) org
D: Co-founder, Principal embedded software architect.
D: Module architecture and UAVTalk/UAVObjects implementation.
N: Alex Vrubel
E: alex (dot) vrubel (plus) openpilot (at) gmail (dot) com
D: Russian translation of the GCS
N: Brian Webb
E: webbbn (plus) openpilot (at) gmail (dot) com
W: Modem lead developer
D: Modem lead developer
M: OP Modems

View File

@ -1,8 +1,10 @@
Short summary of changes. For a complete list see the git log.
2012-11-12
Implemented smoothing filter for accelerometer data.
2012-11-11
Added support for Mode 3 and Mode 4 to the TX Configuration Wizard.
Few minor bugfixes.
--- RELEASE-12.10.1 ---

View File

@ -1,11 +1,15 @@
+ Halt/Reset buttons don't work if board is armed. But no way to use them if "Always armed". Use rescue as workaround.
+ Missing Translations, use English.
+ Radio Wizard confused by a reversed throttle, fix it on your transmitter before starting wizard.
+ [Windows 8] USB Driver is broken.
+ Firmware Update Instructions on Firmware Tab not entirely accurate for all upgrade paths.
+ Radio Wizard Throttle display does not show full range properly.
+ Tricopter's using Vehicle Wizard need to check servo does not need reversed manually.
+ XAircraft ESCs uses non-standard PPM range which may cause issues with Vehicle Wizard.
+ Spectrum Satellite Receivers setup in Radio Wizard may have wrong protocol set.
+ Old Intel 965 have an OpenGL bug that turns the QML PFD black and while.
+ [OP-691] Helicopter configuration change still resets camera/accessory mixers (some code refactoring is desired).
Here is a list of some known unresolved issues. If an issue has JIRA ID [OP-XXX], you may track it using the
following URL: http://bugs.openpilot.org/browse/OP-XXX
+ Missing Translations, use English.
+ Radio Wizard confused by a reversed throttle, fix it on your transmitter before starting wizard.
+ Radio Wizard Throttle display does not show full range properly.
+ [Windows 8] USB Driver is broken.
+ Firmware Update Instructions on Firmware Tab not entirely accurate for all upgrade paths.
+ Tricopter's using Vehicle Wizard need to check servo does not need reversed manually.
+ XAircraft ESCs uses non-standard PPM range which may cause issues with Vehicle Wizard.
+ Spectrum Satellite Receivers setup in Radio Wizard may have wrong protocol set.
+ Old Intel 965 have an OpenGL bug that turns the QML PFD black and while.
+ [OP-732] Import UAV Settings for inactive modules crashes the running firmware (board restarts).
Workaround: update firmware, power cycle, enable modules, power cycle, import configuration.
+ [OP-747] Board infinitely reboots itself after firmware upgrade (settings erase firmware is a workaround).

View File

@ -240,8 +240,8 @@ C:
D:
V:
M: First Auto landing on a fixed Wing using Revo
C:
M: First Auto spot landing on a fixed Wing using Revo
C:
D:
V:

View File

@ -79,6 +79,7 @@ uint8_t max_axislock_rate = 0;
float weak_leveling_kp = 0;
uint8_t weak_leveling_max = 0;
bool lowThrottleZeroIntegral;
bool lowThrottleZeroAxis[MAX_AXES];
float vbar_decay = 0.991f;
struct pid pids[PID_MAX];
@ -357,6 +358,18 @@ static void stabilizationTask(void* parameters)
actuatorDesired.UpdateTime = dT * 1000;
actuatorDesired.Throttle = stabDesired.Throttle;
// Suppress desired output while disarmed or throttle low, for configured axis
if (flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED || stabDesired.Throttle < 0) {
if (lowThrottleZeroAxis[ROLL])
actuatorDesired.Roll = 0.0f;
if (lowThrottleZeroAxis[PITCH])
actuatorDesired.Pitch = 0.0f;
if (lowThrottleZeroAxis[YAW])
actuatorDesired.Yaw = 0.0f;
}
if(PARSE_FLIGHT_MODE(flightStatus.FlightMode) != FLIGHTMODE_MANUAL) {
ActuatorDesiredSet(&actuatorDesired);
} else {
@ -460,7 +473,12 @@ static void SettingsUpdatedCb(UAVObjEvent * ev)
// Whether to zero the PID integrals while throttle is low
lowThrottleZeroIntegral = settings.LowThrottleZeroIntegral == STABILIZATIONSETTINGS_LOWTHROTTLEZEROINTEGRAL_TRUE;
// Whether to suppress (zero) the StabilizationDesired output for each axis while disarmed or throttle is low
lowThrottleZeroAxis[ROLL] = settings.LowThrottleZeroAxis[STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_ROLL] == STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_TRUE;
lowThrottleZeroAxis[PITCH] = settings.LowThrottleZeroAxis[STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_PITCH] == STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_TRUE;
lowThrottleZeroAxis[YAW] = settings.LowThrottleZeroAxis[STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_YAW] == STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_TRUE;
// The dT has some jitter iteration to iteration that we don't want to
// make thie result unpredictable. Still, it's nicer to specify the constant
// based on a time (in ms) rather than a fixed multiplier. The error between

View File

@ -1498,7 +1498,7 @@ font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Tricopter Yaw Motor channel</string>
<string>Tricopter Yaw Servo channel</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>

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

@ -7,6 +7,7 @@ Without the work of the people in this file OpenPilot would not be what it is to
<pre>
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

View File

@ -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"));
}

View File

@ -57,13 +57,13 @@ p, li { white-space: pre-wrap; }
<item>
<widget class="QToolButton" name="startUpdate">
<property name="toolTip">
<string>Calculate gyro and accelerometer bias</string>
<string>Upgrade now</string>
</property>
<property name="styleSheet">
<string notr="true">QToolButton { border: none }</string>
</property>
<property name="text">
<string>Calculate</string>
<string>Upgrade</string>
</property>
<property name="icon">
<iconset resource="../wizardResources.qrc">

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;

View File

@ -28,6 +28,7 @@
#include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h"
#include <coreplugin/coreconstants.h>
#include <QDebug>
#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<deviceWidget *>(widget),SIGNAL(uploadStarted()),this,SLOT(uploadStarted()));
connect(qobject_cast<deviceWidget *>(widget),SIGNAL(uploadEnded(bool)),this,SLOT(uploadEnded(bool)));
}
FlightStatus *UploaderGadgetWidget::getFlightStatus()
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Q_ASSERT(pm);
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
Q_ASSERT(objManager);
FlightStatus *status = dynamic_cast<FlightStatus*>(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) );
}

View File

@ -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();

Binary file not shown.

View File

@ -35,6 +35,8 @@
<field name="LowThrottleZeroIntegral" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
<field name="LowThrottleZeroAxis" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="FALSE,TRUE" defaultvalue="FALSE,FALSE,FALSE"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>