1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-29 14:52:12 +01:00

Merge branch 'rel-14.06' into next

This commit is contained in:
Alessio Morale 2014-07-02 23:28:35 +02:00
commit 2b3aab41c4
13 changed files with 262 additions and 89 deletions

View File

@ -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

View File

@ -1,3 +1,130 @@
--- 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
(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.

View File

@ -32,6 +32,14 @@
#include <systemalarms.h>
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 */

View File

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

View File

@ -62,6 +62,7 @@
#include "velocitystate.h"
#include "taskinfo.h"
#include <pios_struct_helper.h>
#include <sanitycheck.h>
#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();

View File

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

View File

@ -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(&currentHwSettings);
FrameType_t currentFrameType = GetCurrentFrameType();
// check whether the Hw Configuration has changed from the one used at boot time
if (memcmp(&bootHwSettings, &currentHwSettings, sizeof(HwSettingsData)) != 0) {
if ((memcmp(&bootHwSettings, &currentHwSettings, sizeof(HwSettingsData)) != 0) ||
(currentFrameType != bootFrameType)) {
ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL, SYSTEMALARMS_EXTENDEDALARMSTATUS_REBOOTREQUIRED, 0);
}
}

View File

@ -73,6 +73,7 @@
#include "paths.h"
#include "CoordinateConversions.h"
#include <sanitycheck.h>
#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();

View File

@ -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 */

View File

@ -7161,27 +7161,27 @@ p, li { white-space: pre-wrap; }
<message>
<location/>
<source>Accelerometer calibration</source>
<translation type="unfinished">Étalonnage accéléromètres</translation>
<translation>Étalonnage des accéléromètres</translation>
</message>
<message>
<location/>
<source>Magnetometer calibration</source>
<translation type="unfinished">Étalonnage magnétomètre</translation>
<translation>Étalonnage du magnétomètre</translation>
</message>
<message>
<location/>
<source>Board level calibration</source>
<translation type="unfinished">Étalonnage du niveau de la carte</translation>
<translation>Étalonnage du niveau de la carte</translation>
</message>
<message>
<location/>
<source>Gyro bias calibration</source>
<translation type="unfinished">Étalonnage de l&apos;ajustement des Gyros</translation>
<translation>Étalonnage de l&apos;ajustement des gyroscopes</translation>
</message>
<message>
<location/>
<source>Thermal calibration</source>
<translation type="unfinished">Étalonnage de la compensation de température</translation>
<translation>Étalonnage de la compensation en température</translation>
</message>
<message>
<location/>
@ -7210,7 +7210,7 @@ p, li { white-space: pre-wrap; }
<message>
<location/>
<source>Help</source>
<translation type="unfinished">Aide</translation>
<translation>Aide</translation>
</message>
<message>
<location/>
@ -11501,7 +11501,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<source>Settings cannot be recovered after this operation.
The board will be restarted and all settings erased.</source>
<translation>Les paramètres ne pourront être récupérés après cette opération.
La carte sera redémarrée et tous les paramètres éffacés.</translation>
La carte sera redémarrée et tous les paramètres effacés.</translation>
</message>
<message>
<location line="+9"/>
@ -14106,12 +14106,12 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location filename="../../../src/plugins/config/calibration/gyrobiascalibrationmodel.cpp" line="+98"/>
<source>Calibrating the gyroscopes. Keep the vehicle steady...</source>
<translation type="unfinished">Étalonnage en cours des gyroscopes. Maintenez l&apos;appareil sans le bouger...</translation>
<translation>Étalonnage en cours des gyroscopes. Maintenez l&apos;appareil sans le bouger...</translation>
</message>
<message>
<location line="+58"/>
<source>Gyroscope calibration completed successfully.</source>
<translation type="unfinished">Étalonnage des gyroscopes calculé avec succès.</translation>
<translation>Étalonnage des gyroscopes calculé avec succès.</translation>
</message>
</context>
<context>
@ -14123,7 +14123,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location filename="../../../src/plugins/config/calibration/levelcalibrationmodel.cpp" line="+72"/>
<source>Place horizontally and press Save Position...</source>
<translation type="unfinished"></translation>
<translation>Positionner horizontalement et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+18"/>
@ -14133,12 +14133,12 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location line="+40"/>
<source>Leave horizontally, rotate 180° along yaw axis and press Save Position...</source>
<translation type="unfinished"></translation>
<translation>Garder horizontalement, tourner de 180° sur l&apos;axe de Yaw et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+17"/>
<source>Board level calibration completed successfully.</source>
<translation type="unfinished"></translation>
<translation>Mise à niveau de la carte calculé avec succès.</translation>
</message>
<message>
<source>Leave horizontally, rotate 180° along yaw axis and click Save Position button...</source>
@ -14206,92 +14206,92 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location filename="../../../src/plugins/config/calibration/sixpointcalibrationmodel.cpp" line="+59"/>
<source>Place horizontally, nose pointing north and press Save Position...</source>
<translation type="unfinished">Positionner horizontalement, le nez en direction du nord et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner horizontalement, le nez en direction du nord et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+2"/>
<source>Place with nose down, right side west and press Save Position...</source>
<translation type="unfinished">Positionner avec le nez vers le bas, le coté droit vers l&apos;ouest et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner avec le nez vers le bas, le coté droit vers l&apos;ouest et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+2"/>
<source>Place right side down, nose west and press Save Position...</source>
<translation type="unfinished">Positionner le flanc droit vers le bas, le nez en direction de l&apos;ouest et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner le flanc droit vers le bas, le nez en direction de l&apos;ouest et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+2"/>
<source>Place upside down, nose east and press Save Position...</source>
<translation type="unfinished">Positionner à l&apos;envers, le nez vers l&apos;est et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner à l&apos;envers, le nez vers l&apos;est et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+2"/>
<source>Place with nose up, left side north and press Save Position...</source>
<translation type="unfinished">Positionner le nez vers le haut, le flanc droit vers le nord et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner le nez vers le haut, le flanc gauche vers le nord et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+2"/>
<source>Place with left side down, nose south and press Save Position...</source>
<translation type="unfinished">Positionner avec le flanc gauche vers le bas, le nez vers le sud et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner avec le flanc gauche vers le bas, le nez vers le sud et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+4"/>
<source>Place horizontally and press Save Position...</source>
<translation type="unfinished">Positionner horizontalement et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner horizontalement et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+2"/>
<source>Place with nose down and press Save Position...</source>
<translation type="unfinished">Positionner avec le nez vers le bas et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner avec le nez vers le bas et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+2"/>
<source>Place right side down and press Save Position...</source>
<translation type="unfinished">Positionner le flanc droit vers le bas et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner le flanc droit vers le bas et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+2"/>
<source>Place upside down and press Save Position...</source>
<translation type="unfinished">Positionner à l&apos;envers et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner à l&apos;envers et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+2"/>
<source>Place with nose up and press Save Position...</source>
<translation type="unfinished">Positionner avec le nez vers le haut et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner avec le nez vers le haut et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+2"/>
<source>Place with left side down and press Save Position...</source>
<translation type="unfinished">Positionner le flanc gauche vers le bas et cliquer sur le bouton Enregistrer Position...</translation>
<translation>Positionner le flanc gauche vers le bas et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+44"/>
<source>Home location not set, please set your home location and retry.</source>
<translation type="unfinished">Position Home non définie, veuillez régler votre position Home et essayez à nouveau.</translation>
<translation>Position Home non définie, veuillez régler votre position Home et essayez à nouveau.</translation>
</message>
<message>
<location line="+1"/>
<source>Aborting calibration!</source>
<translation type="unfinished">Étalonnage abandonné !</translation>
<translation>Étalonnage abandonné !</translation>
</message>
<message>
<location line="+120"/>
<source>Hold...</source>
<translation type="unfinished">Maintenir en position...</translation>
<translation>Maintenir en position...</translation>
</message>
<message>
<location line="+214"/>
<source>Magnetometer calibration completed successfully.</source>
<translation type="unfinished">Étalonnage du magnétomètre terminée avec succès.</translation>
<translation>Étalonnage du magnétomètre terminé avec succès.</translation>
</message>
<message>
<location line="+4"/>
<source>Accelerometer calibration completed successfully.</source>
<translation type="unfinished">Étalonnage des accéléromètres terminée avec succès.</translation>
<translation>Étalonnage des accéléromètres terminé avec succès.</translation>
</message>
<message>
<location line="+4"/>
<source>Calibration failed! Please review the help and retry.</source>
<translation type="unfinished">Échec étalonnage ! Veuillez lire les instructions et essayer à nouveau.</translation>
<translation>Échec étalonnage ! Veuillez lire les instructions et essayer à nouveau.</translation>
</message>
<message>
<source>Sensor scale and bias computed succesfully.</source>
@ -14316,12 +14316,12 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location filename="../../../src/plugins/config/calibration/thermal/compensationcalculationtransition.h" line="+59"/>
<source>Thermal calibration completed successfully.</source>
<translation type="unfinished">Étalonnage terminé avec succès.</translation>
<translation>Étalonnage température terminé avec succès.</translation>
</message>
<message>
<location line="+4"/>
<source>Calibration failed! Please review the help and retry.</source>
<translation type="unfinished">Échec étalonnage ! Veuillez relire les instructions et essayer à nouveau.</translation>
<translation>Échec étalonnage ! Veuillez relire les instructions et essayer à nouveau.</translation>
</message>
</context>
<context>
@ -14391,13 +14391,13 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<location line="+9"/>
<source>Timing out in %1 seconds</source>
<translatorcomment>Expiration du temps d&apos;attente dans %1 secondes - Shorted / size allowed</translatorcomment>
<translation type="unfinished">Expiration dans %1 secondes</translation>
<translation>Expiration dans %1 secondes</translation>
</message>
<message>
<location line="+2"/>
<source>Timed out after %1 seconds</source>
<translatorcomment>Expiration du temps d&apos;attente après %1 secondes Shorted : size allowed</translatorcomment>
<translation type="unfinished">Expiration après %1 secondes</translation>
<translation>Expiration après %1 secondes</translation>
</message>
</context>
<context>
@ -14405,7 +14405,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location filename="../../../src/plugins/config/calibration/thermal/boardsetuptransition.h" line="+75"/>
<source>Configuring board for calibration.</source>
<translation type="unfinished"></translation>
<translation>Configuration de la carte pour la calibration.</translation>
</message>
</context>
<context>
@ -14413,22 +14413,22 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location filename="../../../src/plugins/config/calibration/thermal/dataacquisitiontransition.h" line="+63"/>
<source>Please wait during samples acquisition. This can take several minutes...</source>
<translation type="unfinished">Veuillez attendre pendant l&apos;acquisition des échantillons. Cela peut plusieurs minutes...</translation>
<translation>Veuillez attendre pendant l&apos;acquisition des échantillons. Cela peut prendre plusieurs minutes...</translation>
</message>
<message>
<location line="+1"/>
<source>Acquisition will run until the rate of temperature change is less than %1°C/min.</source>
<translation type="unfinished">L&apos;acquisition s&apos;effectue jusqu&apos;à ce que le changement de température soit inférieur à %1°C/min.</translation>
<translation>L&apos;acquisition s&apos;effectue jusqu&apos;à ce que le changement de température soit inférieur à %1°C/min.</translation>
</message>
<message>
<location line="+1"/>
<source>For the calibration to be valid, the temperature span during acquisition must be greater than %1°C.</source>
<translation type="unfinished">Pour que la calibration soit valide, la différence de température durant l&apos;acquisition doit être supérieure à %1°C.</translation>
<translation>Pour que la calibration soit valide, la différence de température durant l&apos;acquisition doit être supérieure à %1°C.</translation>
</message>
<message>
<location line="+1"/>
<source>Estimating acquisition duration...</source>
<translation type="unfinished">Estimation de la durée d&apos;acquisition...</translation>
<translation>Estimation de la durée d&apos;acquisition...</translation>
</message>
</context>
<context>
@ -14436,7 +14436,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location filename="../../../src/plugins/config/calibration/thermal/settingshandlingtransitions.h" line="+75"/>
<source>Saving initial settings.</source>
<translation type="unfinished"></translation>
<translation>Enregistrement des paramètres initiaux.</translation>
</message>
</context>
<context>
@ -14444,7 +14444,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location line="+40"/>
<source>Restoring board configuration.</source>
<translation type="unfinished"></translation>
<translation>Restauration des paramètres de la carte.</translation>
</message>
</context>
<context>
@ -14452,37 +14452,37 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location filename="../../../src/plugins/config/calibration/thermal/thermalcalibrationhelper.cpp" line="+318"/>
<source>Barometer is calibrated.</source>
<translation type="unfinished">Baromètre calibré.</translation>
<translation>Le baromètre est calibré.</translation>
</message>
<message>
<location line="+3"/>
<source>Failed to calibrate barometer!</source>
<translation type="unfinished">Échec de la calibration du baromètre !</translation>
<translation>Échec de la calibration du baromètre !</translation>
</message>
<message>
<location line="+23"/>
<source>Gyro is calibrated.</source>
<translation type="unfinished">Gyroscope calibré.</translation>
<translation>Les gyroscopes sont calibrés.</translation>
</message>
<message>
<location line="+3"/>
<source>Failed to calibrate gyro!</source>
<translation type="unfinished">Échec de la calibration des gyroscopes !</translation>
<translation>Échec de la calibration des gyroscopes !</translation>
</message>
<message>
<location line="+63"/>
<source>Target temperature span has been acquired. You may now end acquisition or continue.</source>
<translation type="unfinished">La différence de température a é atteinte. Vous pouvez arrêter maintenant ou continuer.</translation>
<translation>La différence de température a é atteinte. Vous pouvez arrêter maintenant ou continuer.</translation>
</message>
<message>
<location line="+32"/>
<source>m&apos;&apos;s&apos;&apos;&apos;&apos;</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location line="+1"/>
<source>Estimated acquisition duration is %1.</source>
<translation type="unfinished">La durée estimée d&apos;acquisition est de %1.</translation>
<translation>La durée estimée de l&apos;acquisition est de %1.</translation>
</message>
</context>
<context>
@ -14490,17 +14490,17 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location filename="../../../src/plugins/config/configrevowidget.cpp" line="+318"/>
<source>Temperature: %1°C</source>
<translation type="unfinished">Température : %1°C</translation>
<translation>Température : %1°C</translation>
</message>
<message>
<location line="+5"/>
<source>Variance: %1°C/min</source>
<translation type="unfinished">Variation : %1°C/min</translation>
<translation>Variation : %1°C/min</translation>
</message>
<message>
<location line="+5"/>
<source>Sampled range: %1°C</source>
<translation type="unfinished">Plage d&apos;échantillonnage : %1°C</translation>
<translation>Plage d&apos;échantillonnage : %1°C</translation>
</message>
</context>
</TS>

View File

@ -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 {

View File

@ -4,8 +4,8 @@
<field name="BoardRotation" units="deg" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="0,0,0"/>
<field name="AccelKp" units="channel" type="float" elements="1" defaultvalue="0.05"/>
<field name="AccelKi" units="channel" type="float" elements="1" defaultvalue="0.0001"/>
<field name="MagKi" units="" type="float" elements="1" defaultvalue="0"/>
<field name="MagKp" units="" type="float" elements="1" defaultvalue="0"/>
<field name="MagKi" units="" type="float" elements="1" defaultvalue="0.000001"/>
<field name="MagKp" units="" type="float" elements="1" defaultvalue="0.01"/>
<field name="AccelTau" units="" type="float" elements="1" defaultvalue="0"/>
<field name="YawBiasRate" units="channel" type="float" elements="1" defaultvalue="0.000001"/>
<field name="ZeroDuringArming" units="channel" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>

View File

@ -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"/>
<field name="ArmedTimeout" units="ms" type="uint16" elements="1" defaultvalue="30000"/>
<field name="ArmingSequenceTime" units="ms" type="uint16" elements="1" defaultvalue="1000"/>