From ce7f8eec7bb8b8f4501d35b3f5c86b81612ad4e9 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Fri, 27 Jun 2014 19:16:12 +0200 Subject: [PATCH 01/13] Update WhatsNew and Credits for release --- CREDITS.txt | 5 ++- WHATSNEW.txt | 115 +++++++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 119 insertions(+), 1 deletion(-) diff --git a/CREDITS.txt b/CREDITS.txt index 1f55e7f34..1f79a6ac7 100644 --- a/CREDITS.txt +++ b/CREDITS.txt @@ -89,7 +89,6 @@ Mat Wellington Kendal Wells David Willis Dmitriy Zaitsev -Bertrand Songis Andre Bernet Anthony Gomes Cliff Geerdes @@ -99,3 +98,7 @@ Laurent Lalanne Patrick Huebner Rich von Lehe Stefan Cenkov +Andrés Chavarría Krauser +Bertrand Oresve +Cosimo Corrado + diff --git a/WHATSNEW.txt b/WHATSNEW.txt index 2cb236948..ee79f820a 100644 --- a/WHATSNEW.txt +++ b/WHATSNEW.txt @@ -1,3 +1,118 @@ +--- RELEASE-14.06 --- Peanuts Schnapps --- +This is the Mid 2014 release. +This version still supports the CopterControl and CC3D. +It includes several additions and changes aimed at gps/navigation functionalities +(that are expected to be fully available on next release). + +Some additions in this release: +- Addition of GPS assisted flight modes for revo: - Return To Base, Position hold, AutoCruise and Position Vario(LOS, FPV and NSEW); +- Stabilization refactoring that enhance rate performances; +- Sensor calibration has been redesigned for better usability; + +The full list of features, improvements and bugfixes in this release is accessible here: + +http://progress.openpilot.org/issues/?filter=11460 + +** New Feature & Improvements + * [OP-943] - Start using F4's Core Coupled RAM for more than just the IRQ handler stack + * [OP-974] - Make Bootloader Version available while flight software is running + * [OP-975] - Reconsider the calibration process + * [OP-1068] - Add support for magnetometer calibration matrix in place of scaling parameters + * [OP-1149] - Handle thermal bias calculation/calibration to gyro and accel + * [OP-1150] - Create UI to allow users to perform board thermal calibration + * [OP-1159] - Remove "Rev" checkboxes on input tab for channels on which it doesn't have an effect + * [OP-1161] - Add Alarm for Magnetometer if disturbed or uncalibrated + * [OP-1174] - Beautify Uploader gadget popups + * [OP-1194] - Scope gadget - plot and legend visibility state should be persisted between runs + * [OP-1198] - Allow GCS gadgets to save/restore individual state + * [OP-1216] - Refactor Flight Control Modules + * [OP-1230] - Automatically load the correct firmware file when GCS is running in a development environment + * [OP-1233] - Add make options to skip qmake and build a specific GCS directory + * [OP-1245] - Add GUI to control if, what, when and how to do flight side logging. + * [OP-1250] - Add GPS Protocol configuration in the Hardware configuration panel + * [OP-1258] - Update GCC ARM Embedded to 4.8-2014-q1 + * [OP-1259] - Cruise Control tweaks + * [OP-1260] - Rattitude tweaks + * [OP-1273] - Implementation of the PixHawk airspeed sensor based on the MS4525DO + * [OP-1282] - Include I2C Alarm into Eagletree speed sensor module + * [OP-1287] - GPS assisted flight for Revo + * [OP-1299] - Autodetect number of cells in Battery module + * [OP-1302] - Improve on board led functionality + * [OP-1303] - Add PathPlan Alarm in System Health + * [OP-1307] - Create a bare DiscoveryF4 target for debugging and development purposes + * [OP-1308] - Set the same logic to CRITICAL Alarm and same logic to ERROR Alarm + * [OP-1312] - Implement a PIOS WS281x driver + * [OP-1319] - Fix minor spelling mistakes in fw code + * [OP-1335] - ConfigTaskWidget - Add support to bind GComboBox to integer property + * [OP-1339] - System Health panel improvement + * [OP-1350] - TakeOff location handling to be used with RTH + * [OP-1365] - Add instrumentation functions for flight code + +** Bug + * [OP-1026] - Provide some standard method of calibrating CPU speed and load measurement for boards + * [OP-1033] - Data transfer errors on USB HID on F1 devices + * [OP-1043] - Ground OPLinkMini refuses to connect to one Revo unless first connected to another Revo + * [OP-1056] - GPS does not set home location when erased after lock has been established + * [OP-1080] - Unreliable detection of board through OPLink + * [OP-1100] - GCS plist for mac shows wrong associated filetypes, leftover from qtcreator + * [OP-1131] - Firmware mismatch check is not done if Uploader gadget is not active + * [OP-1172] - Some fonts are not defined in config files + * [OP-1196] - Board rotation in GCS not shown correctly upon connection but correctly saved in memory + * [OP-1212] - Fix Priority queue handling in telemetry + * [OP-1227] - High CPU load in ratitude mode on CopterControl + * [OP-1232] - Setting high telemetry rates for periodic uavobject triggers eventsystem warning. + * [OP-1235] - Some fixes for altitude estimation + * [OP-1237] - Blank/Black Buttons on Vehicle Configuration Multirotor Throttle Curve + * [OP-1241] - TxPID Does not work for Bank 3 PID settings + * [OP-1243] - OPMap widget context menu duplicating some menu separators each time its opened + * [OP-1252] - Update GCS to qt 5.2.1 + * [OP-1266] - Gyro and accel thermal compensation is not applied if one or more coefficients have negative value + * [OP-1267] - Incorrect UAV position on GCS OPMap after homeLocation modification + * [OP-1272] - Unable to debug in SWD mode a revo board + * [OP-1283] - SystemHealthGadgetWidget::updateAlarms misinterprets coordinates in SVG file + * [OP-1284] - RTB flies into ground if base is high + * [OP-1285] - Erase Settings ToolTip is wrong + * [OP-1286] - GCS Map "Go To Place" doesn't work + * [OP-1288] - GPS PositionHold immediately flies several meters away if Home is not close + * [OP-1291] - Fix matlab import after UAVTalk changes + * [OP-1294] - Fix stack sizes for CopterControl + * [OP-1295] - Autoupdate not working + * [OP-1296] - Altitude Hold causes copter to ascent at full throttle when far from home location + * [OP-1297] - OPMap fails to read in saved waypoints correctly + * [OP-1300] - SystemHealth gadget does not show "Configuration Alarm" + * [OP-1301] - Hardware settings can't be saved with CC/CC3D + * [OP-1304] - Revo stack alarm + * [OP-1314] - Fix Airspeed stack size + * [OP-1315] - Unable to arm UAV when AirspeedSensorType is set to GroundspeedBaseWindEstimation + * [OP-1323] - GCS font fixes + * [OP-1325] - Fix event system warnings to be errors + * [OP-1326] - Set AIrspeedSensor default back to "None" + * [OP-1327] - SystemAlarms must be non-acked + * [OP-1329] - Various fixes to airspeed module + * [OP-1330] - Cannot set homelocation.set=false when gps reception is optimal + * [OP-1331] - Input and Output Channel Configuration alignments issues + * [OP-1332] - PiOS alarms does not reset alarm state on timer overflow + * [OP-1333] - Output Channel Configuration alignments issues + * [OP-1340] - Auto-update greyed out - not available + * [OP-1343] - GCS Configuration - Input Channel ResponseTime not saved + * [OP-1346] - Input Channel Response Time mismatch between GCS config screen and UAVObject + * [OP-1348] - Config Gadget flashes next panel when connecting/disconnecting board + * [OP-1351] - GCS Calibration UI polishing + * [OP-1352] - Headwind-improvements for FixedWingPathFollower + * [OP-1353] - HITL Flightgear fails to set Position and velocity correctly + * [OP-1354] - Current and voltage not shown in PFD + * [OP-1355] - Magnetometer calibration and board rotation don't play along + * [OP-1363] - Sanitychecks MUST check if magnetometers and GPS are enabled for any pathfollower modes (outdoor mode selected) + * [OP-1371] - Sanitychecks overzealous: hitl/sitl broken + +** Tasks + * [OP-1274] - Update FreeRTOS to 8.0 + * [OP-1337] - French translations updates (14.04/05) + * [OP-1254] - Update to QT5.2.1 for Linux x86/64 + * [OP-1263] - Move SDL out of Qt install + * [OP-1309] - Stabilization refactoring + + --- RELEASE-14.01 --- Cruising Ratt --- This is the first 2014 software release. This version still supports the CopterControl and CC3D. From fdbe58e8e6f6ecbf4ff44381b75d88699a610eae Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sun, 29 Jun 2014 16:06:54 +0200 Subject: [PATCH 02/13] OP-1375 Update Mag Ki and Kp default settings --- shared/uavobjectdefinition/attitudesettings.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/shared/uavobjectdefinition/attitudesettings.xml b/shared/uavobjectdefinition/attitudesettings.xml index 208fd49ba..1c1ad6b8d 100644 --- a/shared/uavobjectdefinition/attitudesettings.xml +++ b/shared/uavobjectdefinition/attitudesettings.xml @@ -4,8 +4,8 @@ - - + + From 52a909185b6cf209372d9f44e9de4e6ced53e724 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sun, 29 Jun 2014 17:22:41 +0200 Subject: [PATCH 03/13] OP-1374 - Add sanitycheck API to detect frame type --- flight/libraries/inc/sanitycheck.h | 10 +++++ flight/libraries/sanitycheck.c | 59 ++++++++++++++++++++---------- 2 files changed, 50 insertions(+), 19 deletions(-) diff --git a/flight/libraries/inc/sanitycheck.h b/flight/libraries/inc/sanitycheck.h index f324486ae..9576d1030 100644 --- a/flight/libraries/inc/sanitycheck.h +++ b/flight/libraries/inc/sanitycheck.h @@ -32,6 +32,14 @@ #include +typedef enum { + FRAME_TYPE_MULTIROTOR, + FRAME_TYPE_HELI, + FRAME_TYPE_FIXED_WING, + FRAME_TYPE_GROUND, + FRAME_TYPE_CUSTOM, +} FrameType_t; + #define SANITYCHECK_STATUS_ERROR_NONE SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE #define SANITYCHECK_STATUS_ERROR_FLIGHTMODE SYSTEMALARMS_EXTENDEDALARMSTATUS_FLIGHTMODE @@ -45,4 +53,6 @@ extern int32_t configuration_check(); +FrameType_t GetCurrentFrameType(); + #endif /* SANITYCHECK_H */ diff --git a/flight/libraries/sanitycheck.c b/flight/libraries/sanitycheck.c index cda3b443a..83e498447 100644 --- a/flight/libraries/sanitycheck.c +++ b/flight/libraries/sanitycheck.c @@ -94,26 +94,8 @@ int32_t configuration_check() // Classify airframe type - bool multirotor; - uint8_t airframe_type; + bool multirotor = (GetCurrentFrameType() == FRAME_TYPE_MULTIROTOR); - SystemSettingsAirframeTypeGet(&airframe_type); - switch (airframe_type) { - case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX: - case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP: - case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO: - case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP: - case SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX: - case SYSTEMSETTINGS_AIRFRAMETYPE_TRI: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXX: - multirotor = true; - break; - default: - multirotor = false; - } // For each available flight mode position sanity check the available // modes @@ -272,3 +254,42 @@ static bool check_stabilization_settings(int index, bool multirotor, bool copter return true; } + +FrameType_t GetCurrentFrameType() +{ + uint8_t airframe_type; + + SystemSettingsAirframeTypeGet(&airframe_type); + switch ((SystemSettingsAirframeTypeOptions)airframe_type) { + case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX: + case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP: + case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO: + case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP: + case SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX: + case SYSTEMSETTINGS_AIRFRAMETYPE_TRI: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXX: + return FRAME_TYPE_MULTIROTOR; + + case SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWING: + case SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWINGELEVON: + case SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWINGVTAIL: + return FRAME_TYPE_FIXED_WING; + + case SYSTEMSETTINGS_AIRFRAMETYPE_HELICP: + return FRAME_TYPE_HELI; + + case SYSTEMSETTINGS_AIRFRAMETYPE_GROUNDVEHICLECAR: + case SYSTEMSETTINGS_AIRFRAMETYPE_GROUNDVEHICLEDIFFERENTIAL: + case SYSTEMSETTINGS_AIRFRAMETYPE_GROUNDVEHICLEMOTORCYCLE: + return FRAME_TYPE_GROUND; + + case SYSTEMSETTINGS_AIRFRAMETYPE_VTOL: + case SYSTEMSETTINGS_AIRFRAMETYPE_CUSTOM: + return FRAME_TYPE_CUSTOM; + } + // anyway it should not reach here + return FRAME_TYPE_CUSTOM; +} From 3ae85f6434bff4a4efa2c717e14e2af9086e9ff1 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sun, 29 Jun 2014 17:23:15 +0200 Subject: [PATCH 04/13] OP-1374 - Issue a Boot Alarm (reboot) if frame type is changed --- flight/modules/System/systemmod.c | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/flight/modules/System/systemmod.c b/flight/modules/System/systemmod.c index 8595642dc..aa6a8f54d 100644 --- a/flight/modules/System/systemmod.c +++ b/flight/modules/System/systemmod.c @@ -96,11 +96,12 @@ static xQueueHandle objectPersistenceQueue; static enum { STACKOVERFLOW_NONE = 0, STACKOVERFLOW_WARNING = 1, STACKOVERFLOW_CRITICAL = 3 } stackOverflow; static bool mallocFailed; static HwSettingsData bootHwSettings; +static FrameType_t bootFrameType; static struct PIOS_FLASHFS_Stats fsStats; // Private functions static void objectUpdatedCb(UAVObjEvent *ev); -static void hwSettingsUpdatedCb(UAVObjEvent *ev); +static void checkSettingsUpdatedCb(UAVObjEvent *ev); #ifdef DIAG_TASKS static void taskMonitorForEachCallback(uint16_t task_id, const struct pios_task_info *task_info, void *context); static void callbackSchedulerForEachCallback(int16_t callback_id, const struct pios_callback_info *callback_info, void *context); @@ -195,8 +196,10 @@ static void systemTask(__attribute__((unused)) void *parameters) // Load a copy of HwSetting active at boot time HwSettingsGet(&bootHwSettings); + bootFrameType = GetCurrentFrameType(); // Whenever the configuration changes, make sure it is safe to fly - HwSettingsConnectCallback(hwSettingsUpdatedCb); + HwSettingsConnectCallback(checkSettingsUpdatedCb); + SystemSettingsConnectCallback(checkSettingsUpdatedCb); #ifdef DIAG_TASKS TaskInfoData taskInfoData; @@ -396,13 +399,15 @@ static void objectUpdatedCb(UAVObjEvent *ev) /** * Called whenever hardware settings changed */ -static void hwSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) +static void checkSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { HwSettingsData currentHwSettings; HwSettingsGet(¤tHwSettings); + FrameType_t currentFrameType = GetCurrentFrameType(); // check whether the Hw Configuration has changed from the one used at boot time - if (memcmp(&bootHwSettings, ¤tHwSettings, sizeof(HwSettingsData)) != 0) { + if ((memcmp(&bootHwSettings, ¤tHwSettings, sizeof(HwSettingsData)) != 0) || + (currentFrameType != bootFrameType)) { ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL, SYSTEMALARMS_EXTENDEDALARMSTATUS_REBOOTREQUIRED, 0); } } From 30491c799238ef9b61d52dbdb1f59ec7984ee02c Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sun, 29 Jun 2014 17:23:57 +0200 Subject: [PATCH 05/13] OP-1374 - Autostart the relevant PathFollower for known frame types --- .../modules/FixedWingPathFollower/fixedwingpathfollower.c | 6 +++++- flight/modules/VtolPathFollower/vtolpathfollower.c | 5 ++++- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c b/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c index 5cdbe7c9e..556a10db8 100644 --- a/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c +++ b/flight/modules/FixedWingPathFollower/fixedwingpathfollower.c @@ -62,6 +62,7 @@ #include "velocitystate.h" #include "taskinfo.h" #include +#include #include "sin_lookup.h" #include "paths.h" @@ -112,7 +113,10 @@ int32_t FixedWingPathFollowerInitialize() HwSettingsInitialize(); HwSettingsOptionalModulesData optionalModules; HwSettingsOptionalModulesGet(&optionalModules); - if (optionalModules.FixedWingPathFollower == HWSETTINGS_OPTIONALMODULES_ENABLED) { + FrameType_t frameType = GetCurrentFrameType(); + + if ((optionalModules.FixedWingPathFollower == HWSETTINGS_OPTIONALMODULES_ENABLED) || + (frameType == FRAME_TYPE_FIXED_WING)) { followerEnabled = true; FixedWingPathFollowerSettingsInitialize(); FixedWingPathFollowerStatusInitialize(); diff --git a/flight/modules/VtolPathFollower/vtolpathfollower.c b/flight/modules/VtolPathFollower/vtolpathfollower.c index 259d81fe4..cc09e0b6b 100644 --- a/flight/modules/VtolPathFollower/vtolpathfollower.c +++ b/flight/modules/VtolPathFollower/vtolpathfollower.c @@ -73,6 +73,7 @@ #include "paths.h" #include "CoordinateConversions.h" +#include #include "cameradesired.h" #include "poilearnsettings.h" @@ -128,8 +129,10 @@ int32_t VtolPathFollowerInitialize() HwSettingsOptionalModulesData optionalModules; HwSettingsOptionalModulesGet(&optionalModules); + FrameType_t frameType = GetCurrentFrameType(); - if (optionalModules.VtolPathFollower == HWSETTINGS_OPTIONALMODULES_ENABLED) { + if ((optionalModules.VtolPathFollower == HWSETTINGS_OPTIONALMODULES_ENABLED) || + (frameType == FRAME_TYPE_MULTIROTOR)) { VtolPathFollowerSettingsInitialize(); NedAccelInitialize(); PathDesiredInitialize(); From 80d3d7c9540fbe69d34d0176572dc8c18e4e7c1c Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sun, 29 Jun 2014 18:36:46 +0200 Subject: [PATCH 06/13] OP-1374 hotfix to filtercf on checking of magnetometer calibration fabsf() --- flight/modules/StateEstimation/filtercf.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/modules/StateEstimation/filtercf.c b/flight/modules/StateEstimation/filtercf.c index 807618004..15b61a665 100644 --- a/flight/modules/StateEstimation/filtercf.c +++ b/flight/modules/StateEstimation/filtercf.c @@ -234,7 +234,7 @@ static filterResult complementaryFilter(struct data *this, float gyro[3], float float magBias[3]; RevoCalibrationmag_biasArrayGet(magBias); // don't trust Mag for initial orientation if it has not been calibrated - if (magBias[0] < 1e-6f && magBias[1] < 1e-6f && magBias[2] < 1e-6f) { + if (fabsf(magBias[0]) < 1e-6f && fabsf(magBias[1]) < 1e-6f && fabsf(magBias[2]) < 1e-6f) { this->magCalibrated = false; mag[0] = 100.0f; mag[1] = 0.0f; From a3e808032c7b19287499e7a9a548530a2ea1fc5d Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sun, 29 Jun 2014 22:10:35 +0200 Subject: [PATCH 07/13] OP-1378 - Review the flight mode settings limits --- shared/uavobjectdefinition/flightmodesettings.xml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/shared/uavobjectdefinition/flightmodesettings.xml b/shared/uavobjectdefinition/flightmodesettings.xml index 19c9b4433..1d76697ae 100644 --- a/shared/uavobjectdefinition/flightmodesettings.xml +++ b/shared/uavobjectdefinition/flightmodesettings.xml @@ -83,27 +83,27 @@ limits="\ %0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ %0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ - %0903NE:Autotune:AutoCruise;\ + %0903NE:POI:PathPlanner:Autotune:AutoCruise;\ \ %0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ %0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ - %0903NE:Autotune:AutoCruise;\ + %0903NE:POI:PathPlanner:Autotune:AutoCruise;\ \ %0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ %0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ - %0903NE:Autotune:AutoCruise;\ + %0903NE:POI:PathPlanner:Autotune:AutoCruise;\ \ %0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ %0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ - %0903NE:Autotune:AutoCruise;\ + %0903NE:POI:PathPlanner:Autotune:AutoCruise;\ \ %0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ %0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ - %0903NE:Autotune:AutoCruise;\ + %0903NE:POI:PathPlanner:Autotune:AutoCruise;\ \ %0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ %0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\ - %0903NE:Autotune:AutoCruise"/> + %0903NE:POI:PathPlanner:Autotune:AutoCruise"/> From cb5ce3b41fa8b4777a214e7d95b5b0ef11672d10 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Mon, 30 Jun 2014 23:39:11 +0200 Subject: [PATCH 08/13] Update WhatsNew for release --- WHATSNEW.txt | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/WHATSNEW.txt b/WHATSNEW.txt index ee79f820a..292ab0333 100644 --- a/WHATSNEW.txt +++ b/WHATSNEW.txt @@ -1,4 +1,16 @@ ---- RELEASE-14.06 --- Peanuts Schnapps --- +--- RELEASE-14.06-RC2 --- Peanuts Schnapps --- +This Release Candidate fixes the following issues: + *[OP-1378] - Check Limits for flight modes + *[OP-1377] - Calibration config panel has Apply button even when not in Expert mode + *[OP-1376] - Calibration results not saved to SD + *[OP-1375] - Update Mag Ki and Kp default settings + *[OP-1374] - Automatically enable the right PathFollower + *[OP-1337] - Fixes for French translation + +The full list of features, improvements and bugfixes in this release candidate is accessible here: +http://progress.openpilot.org/issues/?filter=11462 + +--- RELEASE-14.06-RC1 --- Peanuts Schnapps --- This is the Mid 2014 release. This version still supports the CopterControl and CC3D. It includes several additions and changes aimed at gps/navigation functionalities From 4389f767f3e6b0e3be8938d58fc1f7c71f5559a5 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Wed, 2 Jul 2014 23:27:58 +0200 Subject: [PATCH 09/13] uncrustify --- .../targets/boards/coptercontrol/firmware/inc/pios_config.h | 4 ++-- .../openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h b/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h index 3878d90d0..e7da296e9 100644 --- a/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h +++ b/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h @@ -171,10 +171,10 @@ #endif #define PIOS_TELEM_RX_STACK_SIZE 410 #define PIOS_TELEM_TX_STACK_SIZE 560 -#define PIOS_EVENTDISPATCHER_STACK_SIZE 95 +#define PIOS_EVENTDISPATCHER_STACK_SIZE 95 /* This can't be too high to stop eventdispatcher thread overflowing */ -#define PIOS_EVENTDISAPTCHER_QUEUE 10 +#define PIOS_EVENTDISAPTCHER_QUEUE 10 /* Revolution series */ /* #define REVOLUTION */ diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp index f13aca0e5..4fe823e6a 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -86,7 +86,7 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); HwSettings::DataFields hwSettingsData = hwSettings->getData(); - if(hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_GPS] != HwSettings::OPTIONALMODULES_ENABLED) { + if (hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_GPS] != HwSettings::OPTIONALMODULES_ENABLED) { m_telemetry->gpsProtocol->setEnabled(false); m_telemetry->gpsProtocol->setToolTip(tr("Enable GPS module and reboot the board to be able to select GPS protocol")); } else { From 4de8575fa928ab67e494a2adca2d4a2848241357 Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Thu, 3 Jul 2014 00:22:40 +0200 Subject: [PATCH 10/13] OP-1384 gyro calibration will not zero revo board rotation anymore --- .../calibration/gyrobiascalibrationmodel.cpp | 17 ++++++++--------- .../calibration/gyrobiascalibrationmodel.h | 3 +-- .../src/plugins/config/configrevowidget.cpp | 2 -- 3 files changed, 9 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp index 4e1c9ab31..b65b30055 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp +++ b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp @@ -55,18 +55,23 @@ GyroBiasCalibrationModel::GyroBiasCalibrationModel(QObject *parent) : void GyroBiasCalibrationModel::start() { - // Store and reset board rotation before calibration starts - storeAndClearBoardRotation(); + // reset dirty state to forget previous unsaved runs + m_dirty = false; + // configure board for calibration RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); memento.revoCalibrationData = revoCalibrationData; revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_FALSE; revoCalibration->setData(revoCalibrationData); - // Disable gyro bias correction while calibrating AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData(); memento.attitudeSettingsData = attitudeSettingsData; + // Disable gyro bias correction while calibrating attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE; + // Zero board rotation + attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = 0; + attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = 0; + attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = 0; attitudeSettings->setData(attitudeSettingsData); UAVObject::Metadata gyroStateMetadata = gyroState->getMetadata(); @@ -89,9 +94,6 @@ void GyroBiasCalibrationModel::start() gyro_state_accum_y.clear(); gyro_state_accum_z.clear(); - // reset dirty state to forget previous unsaved runs - m_dirty = false; - started(); progressChanged(0); displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_NED); @@ -149,9 +151,6 @@ void GyroBiasCalibrationModel::getSample(UAVObject *obj) revoCalibration->setData(memento.revoCalibrationData); attitudeSettings->setData(memento.attitudeSettingsData); - // Recall saved board rotation - recallBoardRotation(); - stopped(); displayInstructions(tr("Gyroscope calibration completed successfully."), WizardModel::Success); displayVisualHelp(CALIBRATION_HELPER_IMAGE_EMPTY); diff --git a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h index e979ca621..fce6b7e41 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h @@ -57,8 +57,7 @@ public: signals: void started(); void stopped(); - void storeAndClearBoardRotation(); - void recallBoardRotation(); + void progressChanged(int value); void displayVisualHelp(QString elementID); void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info); diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 5c6feabed..b9d13d245 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -157,8 +157,6 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_gyroBiasCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations())); connect(m_gyroBiasCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations())); - connect(m_gyroBiasCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation())); - connect(m_gyroBiasCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation())); connect(m_gyroBiasCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)), this, SLOT(addInstructions(QString, WizardModel::MessageType))); connect(m_gyroBiasCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString))); From 0ccf4e2ea29283d6972a55c6046113c2704602cf Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Thu, 3 Jul 2014 00:23:51 +0200 Subject: [PATCH 11/13] OP-1384 minor changes to thermal calibration textual instructions --- .../config/calibration/thermal/thermalcalibrationhelper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationhelper.cpp b/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationhelper.cpp index 1190fb537..d7997251e 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationhelper.cpp @@ -407,7 +407,7 @@ void ThermalCalibrationHelper::updateTemperature(float temp) } if (!m_rangeReached && (range() >= TargetTempDelta)) { m_rangeReached = true; - addInstructions(tr("Target temperature span has been acquired. You may now end acquisition or continue.")); + addInstructions(tr("Target temperature span has been acquired. Acquisition may be ended or, preferably, continued.")); } emit temperatureRangeChanged(range()); From 20df4b7903538b1fc7c125a6bd9dbc07767a0590 Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Thu, 3 Jul 2014 00:51:49 +0200 Subject: [PATCH 12/13] OP-1384 updated calibration help text --- .../src/plugins/config/revosensors.ui | 67 +++++++++---------- 1 file changed, 31 insertions(+), 36 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index c563269b4..ca6c107ee 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -968,42 +968,37 @@ A setting of 0.00 disables the filter. <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> -<tr> -<td style="border: none;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;">Help</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Steps 1, 2 and 3 are necessary.</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Step 4 is optional but may help achieve the best possible results.</span></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 1: Accelerometer and Magnetometer calibration</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">These calibrations will compute the scale for Magnetometer and Accelerometer sensors. </span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Press </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> to begin calibration and follow the instructions which will be displayed. </span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">For optimal calibration, perform the acceleration calibration with the board not mounted in the craft.</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">In this way you can accurately level the board on your desk/table during the process. </span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Magnetometer calibration needs to be performed inside your plane/copter to account for metal/magnetic elements on board.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Note 1</span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> </span><span style=" font-family:'Ubuntu'; font-size:11pt; text-decoration: underline;">Your HomeLocation must be set first</span><span style=" font-family:'Ubuntu'; font-size:11pt;">, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Note 2</span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> There is no need to point exactly at South/North/West/East. These are just used to easily tell the user how to point the plane/craft. </span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">You can simply assume that North is in front of you, right is East, etc., and perform the calibration this way.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 2: Board level calibration</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step will ensure that board leveling is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> and do not move your airframe at all until the end of the calibration.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 3: Gyro bias calculation</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step allows to calibrate the gyro measured value when the board is steady. To perform the calibration leave the board/aircraft completely steady and pres </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start</span><span style=" font-family:'Ubuntu'; font-size:11pt;">. </span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 4: Thermal calibration</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">The calibration will compute sensors bias variations at different temperatures while the board warms up.</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This allows a certain amount of correction of those bias variations against temperature changes. It does improve both altitude hold and yaw performances.</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">To perform this calibration leave the board to cool down at room temperature in the coldest places available.</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">After 15-20 minutes, attach the usb connector to the board and press </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start,</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> leaving the board steady. Wait until completed.</span></p></td></tr></table></body></html> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600;">Help</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Steps 1, 2 and 3 are necessary.</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Step 4 is optional but may help achieve the best possible results.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 1: Accelerometer and Magnetometer calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step will calibrate the scale for the Magnetometer and the Accelerometer sensors. </span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;"> to begin, and follow the instructions for each step. </span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">For best results with the accelerometer calibration, it is advised that it be performed with a free unmounted flight controller as this allows one to accurately position the board for each orientation in the sequence.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">The magnetometer calibration must be performed with the board mounted in the airframe in order for the measurements to incorporate any bias produced by local onboard metal/magnetic elements.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Note 1: Before the magnetometer or the accelerometer calibration is performed your Home Location must be set. This step is needed in order to determine the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Note 2: There is no need to align the airframe exactly south, north, east or west during the individual steps. The directions indicated serve only to tell you in which direction the airframe should be positioned relative to some point. One can simply assume that North is in front of you, East is to the right, West is to the left and South is pointing at you.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 2: Board level calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step will ensure that board leveling is accurate. Place the airframe as horizontally as possible (use a spirit level if necessary), then press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;">. Do not move the airframe at all until the end of the calibration.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 3: Gyro bias calculation</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step will allow you to calibrate the gyro measured value when the board is steady. To perform the calibration leave the board/airframe completely stationary and press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;">. </span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 4: Thermal calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">The calibration will compute sensors bias variations at different temperatures while the board warms up.</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This allows a certain amount of correction of those bias variations against temperature changes. It improves altitude hold accuracy and and reduces yaw drift.</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">To perform this calibration disconnect any power from the board and leave it to cool down at room temperature for 15-20 minutes. Then attach the usb connector to the board and press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;">, leaving the board completely stationary. Wait until complete.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p></body></html> Qt::LinksAccessibleByKeyboard|Qt::LinksAccessibleByMouse|Qt::TextBrowserInteraction|Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse From f345adae449e735f642a7c341fb81987b6285440 Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Thu, 3 Jul 2014 00:54:00 +0200 Subject: [PATCH 13/13] OPO-1384 thermal calibration ui : changed label Variance back to Gradient --- ground/openpilotgcs/src/plugins/config/configrevowidget.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index b9d13d245..9445c060e 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -330,7 +330,7 @@ void ConfigRevoWidget::displayTemperature(float temperature) void ConfigRevoWidget::displayTemperatureGradient(float temperatureGradient) { - m_ui->temperatureGradientLabel->setText(tr("Variance: %1°C/min").arg(format(temperatureGradient))); + m_ui->temperatureGradientLabel->setText(tr("Gradient: %1°C/min").arg(format(temperatureGradient))); } void ConfigRevoWidget::displayTemperatureRange(float temperatureRange)