1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-18 08:54:15 +01:00

Merge branch 'next' into abeck/OP_1503v3-yaffs

This commit is contained in:
abeck70 2014-10-23 21:25:54 +11:00
commit 942945850b
98 changed files with 15662 additions and 12371 deletions

View File

@ -119,5 +119,44 @@ static inline float y_on_curve(float x, const pointf points[], int num_points)
// Find the y value on the selected line.
return y_on_line(x, &points[end_point - 1], &points[end_point]);
}
// Fast inverse square root implementation from "quake3-1.32b/code/game/q_math.c"
// http://en.wikipedia.org/wiki/Fast_inverse_square_root
static inline float fast_invsqrtf(float number)
{
float x2, y;
const float threehalfs = 1.5F;
union {
float f;
uint32_t u;
} i;
x2 = number * 0.5F;
y = number;
i.f = y; // evil floating point bit level hacking
i.u = 0x5f3759df - (i.u >> 1); // what the fxck?
y = i.f;
y = y * (threehalfs - (x2 * y * y)); // 1st iteration
// y = y * ( threehalfs - ( x2 * y * y ) ); // 2nd iteration, this can be removed
return y;
}
/**
* Ultrafast pow() aproximation needed for expo
* Based on Algorithm by Martin Ankerl
*/
static inline float fastPow(float a, float b)
{
union {
double d;
int32_t x[2];
} u = { (double)a };
u.x[1] = (int32_t)(b * (u.x[1] - 1072632447) + 1072632447);
u.x[0] = 0;
return (float)u.d;
}
#endif /* MATHMISC_H */

View File

@ -89,9 +89,12 @@ float pid_apply_setpoint(struct pid *pid, const pid_scaler *scaler, const float
float diff = ((deriv_gamma * setpoint - measured) - pid->lastErr);
pid->lastErr = (deriv_gamma * setpoint - measured);
if (pid->d > 0.0f && dT > 0.0f) {
// low pass filter derivative term. below formula is the same as
// dterm = (1-alpha)*pid->lastDer + alpha * (...)/dT
// with alpha = dT/(deriv_tau+dT)
dterm = pid->lastDer + dT / (dT + deriv_tau) * ((scaler->d * diff * pid->d / dT) - pid->lastDer);
pid->lastDer = dterm; // ^ set constant to 1/(2*pi*f_cutoff)
} // 7.9577e-3 means 20 Hz f_cutoff
pid->lastDer = dterm;
}
return (err * scaler->p * pid->p) + pid->iAccumulator / 1000.0f + dterm;
}

View File

@ -41,14 +41,23 @@
#include "altitude.h"
#include "barosensor.h" // object that will be updated by the module
#include "revosettings.h"
#include <mathmisc.h>
#if defined(PIOS_INCLUDE_HCSR04)
#include "sonaraltitude.h" // object that will be updated by the module
#endif
#include "taskinfo.h"
// Private constants
#define STACK_SIZE_BYTES 550
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
#define STACK_SIZE_BYTES 550
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
// Interval in number of sample to recalculate temp bias
#define TEMP_CALIB_INTERVAL 10
// LPF
#define TEMP_DT (1.0f / 120.0f)
#define TEMP_LPF_FC 5.0f
static const float temp_alpha = TEMP_DT / (TEMP_DT + 1.0f / (2.0f * M_PI_F * TEMP_LPF_FC));
// Private types
@ -57,6 +66,11 @@ static xTaskHandle taskHandle;
static RevoSettingsBaroTempCorrectionPolynomialData baroCorrection;
static RevoSettingsBaroTempCorrectionExtentData baroCorrectionExtent;
static volatile bool tempCorrectionEnabled;
static float baro_temp_bias = 0;
static float baro_temperature = NAN;
static uint8_t temp_calibration_count = 0;
// Private functions
static void altitudeTask(void *parameters);
static void SettingsUpdatedCb(UAVObjEvent *ev);
@ -166,13 +180,22 @@ static void altitudeTask(__attribute__((unused)) void *parameters)
temp = PIOS_MS5611_GetTemperature();
press = PIOS_MS5611_GetPressure();
if (tempCorrectionEnabled) {
if (isnan(baro_temperature)) {
baro_temperature = temp;
}
baro_temperature = temp_alpha * (temp - baro_temperature) + baro_temperature;
if (tempCorrectionEnabled && !temp_calibration_count) {
temp_calibration_count = TEMP_CALIB_INTERVAL;
// pressure bias = A + B*t + C*t^2 + D * t^3
// in case the temperature is outside of the calibrated range, uses the nearest extremes
float ctemp = temp > baroCorrectionExtent.max ? baroCorrectionExtent.max :
(temp < baroCorrectionExtent.min ? baroCorrectionExtent.min : temp);
press -= baroCorrection.a + ((baroCorrection.d * ctemp + baroCorrection.c) * ctemp + baroCorrection.b) * ctemp;
float ctemp = boundf(baro_temperature, baroCorrectionExtent.max, baroCorrectionExtent.min);
baro_temp_bias = baroCorrection.a + ((baroCorrection.d * ctemp + baroCorrection.c) * ctemp + baroCorrection.b) * ctemp;
}
press -= baro_temp_bias;
float altitude = 44330.0f * (1.0f - powf((press) / MS5611_P0, (1.0f / 5.255f)));
if (!isnan(altitude)) {

View File

@ -64,8 +64,8 @@
#include "CoordinateConversions.h"
#include <pios_notify.h>
#include <mathmisc.h>
#include <pios_constants.h>
#include <pios_instrumentation_helper.h>
PERF_DEFINE_COUNTER(counterUpd);
@ -79,16 +79,25 @@ PERF_DEFINE_COUNTER(counterAtt);
// - 0xA7710004 number of accel samples read for each loop (cc only).
// Private constants
#define STACK_SIZE_BYTES 540
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3)
#define STACK_SIZE_BYTES 540
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3)
#define SENSOR_PERIOD 4
#define UPDATE_RATE 25.0f
// Attitude module loop interval (defined by sensor rate in pios_config.h)
static const uint32_t sensor_period_ms = ((uint32_t)1000.0f / PIOS_SENSOR_RATE);
#define UPDATE_EXPECTED (1.0f / 500.0f)
#define UPDATE_MIN 1.0e-6f
#define UPDATE_MAX 1.0f
#define UPDATE_ALPHA 1.0e-2f
#define UPDATE_RATE 25.0f
// Interval in number of sample to recalculate temp bias
#define TEMP_CALIB_INTERVAL 30
// LPF
#define TEMP_DT (1.0f / PIOS_SENSOR_RATE)
#define TEMP_LPF_FC 5.0f
static const float temp_alpha = TEMP_DT / (TEMP_DT + 1.0f / (2.0f * M_PI_F * TEMP_LPF_FC));
#define UPDATE_EXPECTED (1.0f / PIOS_SENSOR_RATE)
#define UPDATE_MIN 1.0e-6f
#define UPDATE_MAX 1.0f
#define UPDATE_ALPHA 1.0e-2f
// Private types
@ -130,6 +139,10 @@ static bool apply_accel_temp = false;
static AccelGyroSettingsgyro_temp_coeffData gyro_temp_coeff;;
static AccelGyroSettingsaccel_temp_coeffData accel_temp_coeff;
static AccelGyroSettingstemp_calibrated_extentData temp_calibrated_extent;
static float temperature = NAN;
static float accel_temp_bias[3] = { 0 };
static float gyro_temp_bias[3] = { 0 };
static uint8_t temp_calibration_count = 0;
// Accel and Gyro scaling (this is the product of sensor scale and adjustement in AccelGyroSettings
static AccelGyroSettingsgyro_scaleData gyro_scale;
@ -142,8 +155,7 @@ static volatile int32_t trim_accels[3];
static volatile int32_t trim_samples;
int32_t const MAX_TRIM_FLIGHT_SAMPLES = 65535;
#define GRAV 9.81f
#define STD_CC_ACCEL_SCALE (GRAV * 0.004f)
#define STD_CC_ACCEL_SCALE (PIOS_CONST_MKS_GRAV_ACCEL_F * 0.004f)
/* 0.004f is gravity / LSB */
#define STD_CC_ANALOG_GYRO_NEUTRAL 1665
#define STD_CC_ANALOG_GYRO_GAIN 0.42f
@ -222,12 +234,6 @@ static void AttitudeTask(__attribute__((unused)) void *parameters)
AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE);
// Set critical error and wait until the accel is producing data
while (PIOS_ADXL345_FifoElements() == 0) {
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_CRITICAL);
PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE);
}
bool cc3d = BOARDISCC3D;
if (cc3d) {
@ -236,6 +242,11 @@ static void AttitudeTask(__attribute__((unused)) void *parameters)
#endif
} else {
#if defined(PIOS_INCLUDE_ADXL345)
// Set critical error and wait until the accel is producing data
while (PIOS_ADXL345_FifoElements() == 0) {
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_CRITICAL);
PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE);
}
accel_test = PIOS_ADXL345_Test();
#endif
@ -257,7 +268,7 @@ static void AttitudeTask(__attribute__((unused)) void *parameters)
settingsUpdatedCb(AttitudeSettingsHandle());
PIOS_DELTATIME_Init(&dtconfig, UPDATE_EXPECTED, UPDATE_MIN, UPDATE_MAX, UPDATE_ALPHA);
portTickType lastSysTime = xTaskGetTickCount();
// Main task loop
while (1) {
FlightStatusData flightStatus;
@ -317,6 +328,7 @@ static void AttitudeTask(__attribute__((unused)) void *parameters)
PERF_MEASURE_PERIOD(counterPeriod);
AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE);
}
vTaskDelayUntil(&lastSysTime, sensor_period_ms / portTICK_PERIOD_MS);
}
}
@ -454,7 +466,7 @@ static int32_t updateSensorsCC3D(AccelStateData *accelStateData, GyroStateData *
#if defined(PIOS_INCLUDE_MPU6000)
xQueueHandle queue = PIOS_MPU6000_GetQueue();
BaseType_t ret = xQueueReceive(queue, (void *)&mpu6000_data, SENSOR_PERIOD);
BaseType_t ret = xQueueReceive(queue, (void *)&mpu6000_data, sensor_period_ms);
while (ret == pdTRUE) {
gyros[0] += mpu6000_data.gyro_x;
gyros[1] += mpu6000_data.gyro_y;
@ -470,6 +482,7 @@ static int32_t updateSensorsCC3D(AccelStateData *accelStateData, GyroStateData *
// check if further samples are already in queue
ret = xQueueReceive(queue, (void *)&mpu6000_data, 0);
}
PERF_TRACK_VALUE(counterAccelSamples, count);
if (!count) {
return -1; // Error, no data
@ -488,21 +501,39 @@ static int32_t updateSensorsCC3D(AccelStateData *accelStateData, GyroStateData *
accels[1] *= accel_scale.Y * invcount;
accels[2] *= accel_scale.Z * invcount;
temp *= invcount;
float ctemp = temp > temp_calibrated_extent.max ? temp_calibrated_extent.max :
(temp < temp_calibrated_extent.min ? temp_calibrated_extent.min
: temp);
if (isnan(temperature)) {
temperature = temp;
}
temperature = temp_alpha * (temp - temperature) + temperature;
if ((apply_gyro_temp || apply_accel_temp) && !temp_calibration_count) {
temp_calibration_count = TEMP_CALIB_INTERVAL;
float ctemp = boundf(temperature, temp_calibrated_extent.max, temp_calibrated_extent.min);
if (apply_gyro_temp) {
gyro_temp_bias[0] = (gyro_temp_coeff.X + gyro_temp_coeff.X2 * ctemp) * ctemp;
gyro_temp_bias[1] = (gyro_temp_coeff.Y + gyro_temp_coeff.Y2 * ctemp) * ctemp;
gyro_temp_bias[2] = (gyro_temp_coeff.Z + gyro_temp_coeff.Z2 * ctemp) * ctemp;
}
if (apply_accel_temp) {
accel_temp_bias[0] = accel_temp_coeff.X * ctemp;
accel_temp_bias[1] = accel_temp_coeff.Y * ctemp;
accel_temp_bias[2] = accel_temp_coeff.Z * ctemp;
}
}
temp_calibration_count--;
if (apply_gyro_temp) {
gyros[0] -= (gyro_temp_coeff.X + gyro_temp_coeff.X2 * ctemp) * ctemp;
gyros[1] -= (gyro_temp_coeff.Y + gyro_temp_coeff.Y2 * ctemp) * ctemp;
gyros[2] -= (gyro_temp_coeff.Z + gyro_temp_coeff.Z2 * ctemp) * ctemp;
gyros[0] -= gyro_temp_bias[0];
gyros[1] -= gyro_temp_bias[1];
gyros[2] -= gyro_temp_bias[2];
}
if (apply_accel_temp) {
accels[0] -= accel_temp_coeff.X * ctemp;
accels[1] -= accel_temp_coeff.Y * ctemp;
accels[2] -= accel_temp_coeff.Z * ctemp;
accels[0] -= accel_temp_bias[0];
accels[1] -= accel_temp_bias[1];
accels[2] -= accel_temp_bias[2];
}
// gyrosData->temperature = 35.0f + ((float)mpu6000_data.temperature + 512.0f) / 340.0f;
// accelsData->temperature = 35.0f + ((float)mpu6000_data.temperature + 512.0f) / 340.0f;
@ -587,24 +618,24 @@ __attribute__((optimize("O3"))) static void updateAttitude(AccelStateData *accel
CrossProduct((const float *)accels_filtered, (const float *)grot_filtered, accel_err);
// Account for accel magnitude
float accel_mag = sqrtf(accels_filtered[0] * accels_filtered[0] + accels_filtered[1] * accels_filtered[1] + accels_filtered[2] * accels_filtered[2]);
if (accel_mag < 1.0e-3f) {
float inv_accel_mag = fast_invsqrtf(accels_filtered[0] * accels_filtered[0] + accels_filtered[1] * accels_filtered[1] + accels_filtered[2] * accels_filtered[2]);
if (inv_accel_mag > 1e3f) {
return;
}
// Account for filtered gravity vector magnitude
float grot_mag;
float inv_grot_mag;
if (accel_filter_enabled) {
grot_mag = sqrtf(grot_filtered[0] * grot_filtered[0] + grot_filtered[1] * grot_filtered[1] + grot_filtered[2] * grot_filtered[2]);
inv_grot_mag = fast_invsqrtf(grot_filtered[0] * grot_filtered[0] + grot_filtered[1] * grot_filtered[1] + grot_filtered[2] * grot_filtered[2]);
} else {
grot_mag = 1.0f;
inv_grot_mag = 1.0f;
}
if (grot_mag < 1.0e-3f) {
if (inv_grot_mag > 1e3f) {
return;
}
const float invMag = 1.0f / (accel_mag * grot_mag);
const float invMag = (inv_accel_mag * inv_grot_mag);
accel_err[0] *= invMag;
accel_err[1] *= invMag;
accel_err[2] *= invMag;
@ -645,21 +676,20 @@ __attribute__((optimize("O3"))) static void updateAttitude(AccelStateData *accel
}
// Renomalize
float qmag = sqrtf(q[0] * q[0] + q[1] * q[1] + q[2] * q[2] + q[3] * q[3]);
float inv_qmag = fast_invsqrtf(q[0] * q[0] + q[1] * q[1] + q[2] * q[2] + q[3] * q[3]);
// If quaternion has become inappropriately short or is nan reinit.
// THIS SHOULD NEVER ACTUALLY HAPPEN
if ((fabsf(qmag) < 1e-3f) || isnan(qmag)) {
if ((fabsf(inv_qmag) > 1e3f) || isnan(inv_qmag)) {
q[0] = 1;
q[1] = 0;
q[2] = 0;
q[3] = 0;
} else {
const float invQmag = 1.0f / qmag;
q[0] = q[0] * invQmag;
q[1] = q[1] * invQmag;
q[2] = q[2] * invQmag;
q[3] = q[3] * invQmag;
q[0] = q[0] * inv_qmag;
q[1] = q[1] * inv_qmag;
q[2] = q[2] * inv_qmag;
q[3] = q[3] * inv_qmag;
}
AttitudeStateData attitudeState;
@ -777,7 +807,7 @@ static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent *objEv)
accelGyroSettings.accel_scale.X = trim_accels[0] / trim_samples;
accelGyroSettings.accel_scale.Y = trim_accels[1] / trim_samples;
// Z should average -grav
accelGyroSettings.accel_scale.Z = trim_accels[2] / trim_samples + GRAV;
accelGyroSettings.accel_scale.Z = trim_accels[2] / trim_samples + PIOS_CONST_MKS_GRAV_ACCEL_F;
attitudeSettings.TrimFlight = ATTITUDESETTINGS_TRIMFLIGHT_NORMAL;
AttitudeSettingsSet(&attitudeSettings);
} else {

View File

@ -99,6 +99,7 @@ void takeOffLocationHandlerInit();
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ACRO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ACRO) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
@ -116,6 +117,7 @@ void takeOffLocationHandlerInit();
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_ACRO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ACRO) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
@ -133,6 +135,7 @@ void takeOffLocationHandlerInit();
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_ACRO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ACRO) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
@ -150,6 +153,7 @@ void takeOffLocationHandlerInit();
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_ACRO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ACRO) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
@ -167,6 +171,7 @@ void takeOffLocationHandlerInit();
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_ACRO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ACRO) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
@ -184,6 +189,7 @@ void takeOffLocationHandlerInit();
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_VIRTUALBAR == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_ACRO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ACRO) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_RATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \

View File

@ -29,6 +29,7 @@
*/
#include "inc/manualcontrol.h"
#include <mathmisc.h>
#include <manualcontrolcommand.h>
#include <stabilizationdesired.h>
#include <flightmodesettings.h>
@ -39,6 +40,28 @@
// Private types
// Private functions
static float applyExpo(float value, float expo);
static float applyExpo(float value, float expo)
{
// note: fastPow makes a small error, therefore result needs to be bound
float exp = boundf(fastPow(1.00695f, expo), 0.5f, 2.0f);
// magic number scales expo
// so that
// expo=100 yields value**10
// expo=0 yields value**1
// expo=-100 yields value**(1/10)
// (pow(2.0,1/100)~=1.00695)
if (value > 0.0f) {
return boundf(fastPow(value, exp), 0.0f, 1.0f);
} else if (value < -0.0f) {
return boundf(-fastPow(-value, exp), -1.0f, 0.0f);
} else {
return 0.0f;
}
}
/**
@ -64,6 +87,9 @@ void stabilizedHandler(bool newinit)
StabilizationBankData stabSettings;
StabilizationBankGet(&stabSettings);
cmd.Roll = applyExpo(cmd.Roll, stabSettings.StickExpo.Roll);
cmd.Pitch = applyExpo(cmd.Pitch, stabSettings.StickExpo.Pitch);
cmd.Yaw = applyExpo(cmd.Yaw, stabSettings.StickExpo.Yaw);
uint8_t *stab_settings;
FlightStatusData flightStatus;
FlightStatusGet(&flightStatus);
@ -100,6 +126,7 @@ void stabilizedHandler(bool newinit)
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd.Roll * stabSettings.RollMax :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd.Roll * stabSettings.ManualRate.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ACRO) ? cmd.Roll * stabSettings.ManualRate.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) ? cmd.Roll * stabSettings.RollMax :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) ? cmd.Roll * stabSettings.ManualRate.Roll :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd.Roll * stabSettings.RollMax :
@ -112,6 +139,7 @@ void stabilizedHandler(bool newinit)
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd.Pitch * stabSettings.PitchMax :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd.Pitch * stabSettings.ManualRate.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ACRO) ? cmd.Pitch * stabSettings.ManualRate.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) ? cmd.Pitch * stabSettings.PitchMax :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) ? cmd.Pitch * stabSettings.ManualRate.Pitch :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd.Pitch * stabSettings.PitchMax :
@ -134,6 +162,7 @@ void stabilizedHandler(bool newinit)
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd.Yaw * stabSettings.YawMax :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd.Yaw * stabSettings.ManualRate.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ACRO) ? cmd.Yaw * stabSettings.ManualRate.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE) ? cmd.Yaw * stabSettings.YawMax :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) ? cmd.Yaw * stabSettings.ManualRate.Yaw :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd.Yaw * stabSettings.YawMax :

View File

@ -58,19 +58,36 @@
#include <accelgyrosettings.h>
#include <flightstatus.h>
#include <taskinfo.h>
#include <pios_math.h>
#include <CoordinateConversions.h>
#include <pios_board_info.h>
// Private constants
#define STACK_SIZE_BYTES 1000
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3)
#define SENSOR_PERIOD 2
#define STACK_SIZE_BYTES 1000
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3)
#define ZERO_ROT_ANGLE 0.00001f
static const uint32_t sensor_period_ms = ((uint32_t)1000.0f / PIOS_SENSOR_RATE);
// Interval in number of sample to recalculate temp bias
#define TEMP_CALIB_INTERVAL 30
// LPF
#define TEMP_DT (1.0f / PIOS_SENSOR_RATE)
#define TEMP_LPF_FC 5.0f
static const float temp_alpha = TEMP_DT / (TEMP_DT + 1.0f / (2.0f * M_PI_F * TEMP_LPF_FC));
#define ZERO_ROT_ANGLE 0.00001f
// Private types
#define PIOS_INSTRUMENT_MODULE
#include <pios_instrumentation_helper.h>
PERF_DEFINE_COUNTER(counterGyroSamples);
PERF_DEFINE_COUNTER(counterSensorPeriod);
// Counters:
// - 0x53000001 Sensor fetch rate(period)
// - 0x53000002 number of gyro samples read for each loop
// Private functions
static void SensorsTask(void *parameters);
@ -96,6 +113,13 @@ static float mag_transform[3][3] = {
static volatile bool gyro_temp_calibrated = false;
static volatile bool accel_temp_calibrated = false;
static float accel_temperature = NAN;
static float gyro_temperature = NAN;
static float accel_temp_bias[3] = { 0 };
static float gyro_temp_bias[3] = { 0 };
static uint8_t temp_calibration_count = 0;
static float R[3][3] = {
{ 0 }
};
@ -219,7 +243,8 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
vTaskDelay(10);
}
}
PERF_INIT_COUNTER(counterGyroSamples, 0x53000001);
PERF_INIT_COUNTER(counterSensorPeriod, 0x53000002);
// Main task loop
lastSysTime = xTaskGetTickCount();
bool error = false;
@ -234,7 +259,7 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS);
#endif
lastSysTime = xTaskGetTickCount();
vTaskDelayUntil(&lastSysTime, SENSOR_PERIOD / portTICK_RATE_MS);
vTaskDelayUntil(&lastSysTime, sensor_period_ms / portTICK_RATE_MS);
AlarmsSet(SYSTEMALARMS_ALARM_SENSORS, SYSTEMALARMS_ALARM_CRITICAL);
error = false;
} else {
@ -263,7 +288,7 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
count = 0;
while ((read_good = PIOS_BMA180_ReadFifo(&accel)) != 0 && !error) {
error = ((xTaskGetTickCount() - lastSysTime) > SENSOR_PERIOD) ? true : error;
error = ((xTaskGetTickCount() - lastSysTime) > sensor_period_ms) ? true : error;
}
if (error) {
// Unfortunately if the BMA180 ever misses getting read, then it will not
@ -332,6 +357,9 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
accel_samples++;
}
PERF_MEASURE_PERIOD(counterSensorPeriod);
PERF_TRACK_VALUE(counterGyroSamples, gyro_samples);
if (gyro_samples == 0) {
PIOS_MPU6000_ReadGyros(&mpu6000_data);
error = true;
@ -350,24 +378,43 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
PIOS_DEBUG_Assert(0);
}
if (isnan(accel_temperature)) {
accel_temperature = accelSensorData.temperature;
gyro_temperature = gyroSensorData.temperature;
}
accel_temperature = temp_alpha * (accelSensorData.temperature - accel_temperature) + accel_temperature;
gyro_temperature = temp_alpha * (gyroSensorData.temperature - gyro_temperature) + gyro_temperature;
if ((accel_temp_calibrated || gyro_temp_calibrated) && !temp_calibration_count) {
temp_calibration_count = TEMP_CALIB_INTERVAL;
if (accel_temp_calibrated) {
float ctemp = boundf(accel_temperature, agcal.temp_calibrated_extent.max, agcal.temp_calibrated_extent.min);
accel_temp_bias[0] = agcal.accel_temp_coeff.X * ctemp;
accel_temp_bias[1] = agcal.accel_temp_coeff.Y * ctemp;
accel_temp_bias[2] = agcal.accel_temp_coeff.Z * ctemp;
}
if (gyro_temp_calibrated) {
float ctemp = boundf(gyro_temperature, agcal.temp_calibrated_extent.max, agcal.temp_calibrated_extent.min);
gyro_temp_bias[0] = (agcal.gyro_temp_coeff.X + agcal.gyro_temp_coeff.X2 * ctemp) * ctemp;
gyro_temp_bias[1] = (agcal.gyro_temp_coeff.Y + agcal.gyro_temp_coeff.Y2 * ctemp) * ctemp;
gyro_temp_bias[2] = (agcal.gyro_temp_coeff.Z + agcal.gyro_temp_coeff.Z2 * ctemp) * ctemp;
}
}
temp_calibration_count--;
// Scale the accels
float accels[3] = { (float)accel_accum[0] / accel_samples,
(float)accel_accum[1] / accel_samples,
(float)accel_accum[2] / accel_samples };
float accels_out[3] = { accels[0] * accel_scaling * agcal.accel_scale.X - agcal.accel_bias.X,
accels[1] * accel_scaling * agcal.accel_scale.Y - agcal.accel_bias.Y,
accels[2] * accel_scaling * agcal.accel_scale.Z - agcal.accel_bias.Z };
float accels_out[3] = { accels[0] * accel_scaling * agcal.accel_scale.X - agcal.accel_bias.X - accel_temp_bias[0],
accels[1] * accel_scaling * agcal.accel_scale.Y - agcal.accel_bias.Y - accel_temp_bias[1],
accels[2] * accel_scaling * agcal.accel_scale.Z - agcal.accel_bias.Z - accel_temp_bias[2] };
if (accel_temp_calibrated) {
float ctemp = accelSensorData.temperature > agcal.temp_calibrated_extent.max ? agcal.temp_calibrated_extent.max :
(accelSensorData.temperature < agcal.temp_calibrated_extent.min ? agcal.temp_calibrated_extent.min
: accelSensorData.temperature);
accels_out[0] -= agcal.accel_temp_coeff.X * ctemp;
accels_out[1] -= agcal.accel_temp_coeff.Y * ctemp;
accels_out[2] -= agcal.accel_temp_coeff.Z * ctemp;
}
if (rotate) {
rot_mult(R, accels_out, accels);
accelSensorData.x = accels[0];
@ -385,18 +432,10 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
(float)gyro_accum[1] / gyro_samples,
(float)gyro_accum[2] / gyro_samples };
float gyros_out[3] = { gyros[0] * gyro_scaling * agcal.gyro_scale.X - agcal.gyro_bias.X,
gyros[1] * gyro_scaling * agcal.gyro_scale.Y - agcal.gyro_bias.Y,
gyros[2] * gyro_scaling * agcal.gyro_scale.Z - agcal.gyro_bias.Z };
float gyros_out[3] = { gyros[0] * gyro_scaling * agcal.gyro_scale.X - agcal.gyro_bias.X - gyro_temp_bias[0],
gyros[1] * gyro_scaling * agcal.gyro_scale.Y - agcal.gyro_bias.Y - gyro_temp_bias[1],
gyros[2] * gyro_scaling * agcal.gyro_scale.Z - agcal.gyro_bias.Z - gyro_temp_bias[2] };
if (gyro_temp_calibrated) {
float ctemp = gyroSensorData.temperature > agcal.temp_calibrated_extent.max ? agcal.temp_calibrated_extent.max :
(gyroSensorData.temperature < agcal.temp_calibrated_extent.min ? agcal.temp_calibrated_extent.min
: gyroSensorData.temperature);
gyros_out[0] -= (agcal.gyro_temp_coeff.X + agcal.gyro_temp_coeff.X2 * ctemp) * ctemp;
gyros_out[1] -= (agcal.gyro_temp_coeff.Y + agcal.gyro_temp_coeff.Y2 * ctemp) * ctemp;
gyros_out[2] -= (agcal.gyro_temp_coeff.Z + agcal.gyro_temp_coeff.Z2 * ctemp) * ctemp;
}
if (rotate) {
rot_mult(R, gyros_out, gyros);
gyroSensorData.x = gyros[0];
@ -437,8 +476,7 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS);
#endif
lastSysTime = xTaskGetTickCount();
vTaskDelayUntil(&lastSysTime, sensor_period_ms / portTICK_RATE_MS);
}
}

View File

@ -42,7 +42,7 @@
#ifdef REVOLUTION
#define UPDATE_EXPECTED (1.0f / 666.0f)
#define UPDATE_EXPECTED (1.0f / PIOS_SENSOR_RATE)
#define UPDATE_MIN 1.0e-6f
#define UPDATE_MAX 1.0f
#define UPDATE_ALPHA 1.0e-2f

View File

@ -33,6 +33,7 @@
#include <openpilot.h>
#include <pid.h>
#include <sin_lookup.h>
#include <callbackinfo.h>
#include <ratedesired.h>
#include <actuatordesired.h>
@ -54,7 +55,7 @@
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_CRITICAL
#define UPDATE_EXPECTED (1.0f / 666.0f)
#define UPDATE_EXPECTED (1.0f / PIOS_SENSOR_RATE)
#define UPDATE_MIN 1.0e-6f
#define UPDATE_MAX 1.0f
#define UPDATE_ALPHA 1.0e-2f
@ -281,6 +282,23 @@ static void stabilizationInnerloopTask()
pid_scaler scaler = create_pid_scaler(t);
actuatorDesiredAxis[t] = pid_apply_setpoint(&stabSettings.innerPids[t], &scaler, rate[t], gyro_filtered[t], dT);
break;
case STABILIZATIONSTATUS_INNERLOOP_ACRO:
{
float stickinput[3];
stickinput[0] = boundf(rate[0] / stabSettings.stabBank.ManualRate.Roll, -1.0f, 1.0f);
stickinput[1] = boundf(rate[1] / stabSettings.stabBank.ManualRate.Pitch, -1.0f, 1.0f);
stickinput[2] = boundf(rate[2] / stabSettings.stabBank.ManualRate.Yaw, -1.0f, 1.0f);
rate[t] = boundf(rate[t],
-StabilizationBankMaximumRateToArray(stabSettings.stabBank.MaximumRate)[t],
StabilizationBankMaximumRateToArray(stabSettings.stabBank.MaximumRate)[t]
);
pid_scaler ascaler = create_pid_scaler(t);
ascaler.i *= boundf(1.0f - (1.5f * fabsf(stickinput[t])), 0.0f, 1.0f); // this prevents Integral from getting too high while controlled manually
float arate = pid_apply_setpoint(&stabSettings.innerPids[t], &ascaler, rate[t], gyro_filtered[t], dT);
float factor = fabsf(stickinput[t]) * stabSettings.stabBank.AcroInsanityFactor;
actuatorDesiredAxis[t] = factor * stickinput[t] + (1.0f - factor) * arate;
}
break;
case STABILIZATIONSTATUS_INNERLOOP_DIRECT:
default:
actuatorDesiredAxis[t] = rate[t];
@ -311,6 +329,18 @@ static void stabilizationInnerloopTask()
previous_mode[t] = 255;
}
}
if (stabSettings.stabBank.EnablePiroComp == STABILIZATIONBANK_ENABLEPIROCOMP_TRUE && stabSettings.innerPids[0].iLim > 1e-3f && stabSettings.innerPids[1].iLim > 1e-3f) {
// attempted piro compensation - rotate pitch and yaw integrals (experimental)
float angleYaw = DEG2RAD(gyro_filtered[2] * dT);
float sinYaw = sinf(angleYaw);
float cosYaw = cosf(angleYaw);
float rollAcc = stabSettings.innerPids[0].iAccumulator / stabSettings.innerPids[0].iLim;
float pitchAcc = stabSettings.innerPids[1].iAccumulator / stabSettings.innerPids[1].iLim;
stabSettings.innerPids[0].iAccumulator = stabSettings.innerPids[0].iLim * (cosYaw * rollAcc + sinYaw * pitchAcc);
stabSettings.innerPids[1].iAccumulator = stabSettings.innerPids[1].iLim * (cosYaw * pitchAcc - sinYaw * rollAcc);
}
{
uint8_t armed;
FlightStatusArmedGet(&armed);

View File

@ -52,7 +52,7 @@
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_REGULAR
#define UPDATE_EXPECTED (1.0f / 666.0f)
#define UPDATE_EXPECTED (1.0f / PIOS_SENSOR_RATE)
#define UPDATE_MIN 1.0e-6f
#define UPDATE_MAX 1.0f
#define UPDATE_ALPHA 1.0e-2f

View File

@ -158,6 +158,10 @@ static void StabilizationDesiredUpdatedCb(__attribute__((unused)) UAVObjEvent *e
StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT;
StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_VIRTUALFLYBAR;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_ACRO:
StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT;
StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_ACRO;
break;
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE:
StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_RATTITUDE;
StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE;

View File

@ -47,7 +47,7 @@
#define DT_ALPHA 1e-3f
#define DT_MIN 1e-6f
#define DT_MAX 1.0f
#define DT_INIT (1.0f / 666.0f) // initialize with 666 Hz (default sensor update rate on revo)
#define DT_INIT (1.0f / PIOS_SENSOR_RATE) // initialize with board sensor rate
#define IMPORT_SENSOR_IF_UPDATED(shortname, num) \
if (IS_SET(state->updated, SENSORUPDATES_##shortname)) { \

View File

@ -40,7 +40,7 @@
#define DT_ALPHA 1e-3f
#define DT_MIN 1e-6f
#define DT_MAX 1.0f
#define DT_INIT (1.0f / 666.0f) // initialize with 666 Hz (default sensor update rate on revo)
#define DT_INIT (1.0f / PIOS_SENSOR_RATE) // initialize with board sensor rate
// Private types
struct data {

View File

@ -83,6 +83,7 @@
static void updatePIDs(UAVObjEvent *ev);
static uint8_t update(float *var, float val);
static uint8_t updateUint8(uint8_t *var, float val);
static uint8_t updateInt8(int8_t *var, float val);
static float scale(float val, float inMin, float inMax, float outMin, float outMax);
/**
@ -331,9 +332,25 @@ static void updatePIDs(UAVObjEvent *ev)
case TXPIDSETTINGS_PIDS_YAWATTITUDERESP:
needsUpdateBank |= updateUint8(&bank.YawMax, value);
break;
case TXPIDSETTINGS_PIDS_ROLLEXPO:
needsUpdateBank |= updateInt8(&bank.StickExpo.Roll, value);
break;
case TXPIDSETTINGS_PIDS_PITCHEXPO:
needsUpdateBank |= updateInt8(&bank.StickExpo.Pitch, value);
break;
case TXPIDSETTINGS_PIDS_ROLLPITCHEXPO:
needsUpdateBank |= updateInt8(&bank.StickExpo.Roll, value);
needsUpdateBank |= updateInt8(&bank.StickExpo.Pitch, value);
break;
case TXPIDSETTINGS_PIDS_YAWEXPO:
needsUpdateBank |= updateInt8(&bank.StickExpo.Yaw, value);
break;
case TXPIDSETTINGS_PIDS_GYROTAU:
needsUpdateStab |= update(&stab.GyroTau, value);
break;
case TXPIDSETTINGS_PIDS_ACROPLUSFACTOR:
needsUpdateBank |= update(&bank.AcroInsanityFactor, value);
break;
default:
PIOS_Assert(0);
}
@ -430,6 +447,21 @@ static uint8_t updateUint8(uint8_t *var, float val)
return 0;
}
/**
* Updates var using val if needed.
* \returns 1 if updated, 0 otherwise
*/
static uint8_t updateInt8(int8_t *var, float val)
{
int8_t roundedVal = (int8_t)roundf(val);
if (*var != roundedVal) {
*var = roundedVal;
return 1;
}
return 0;
}
/**
* @}
*/

View File

@ -216,7 +216,7 @@ static void readFirmwareInfo()
struct fw_version_info *fwinfo = (struct fw_version_info *)(bdinfo->fw_base + bdinfo->fw_size);
memcpy(&sysPkt.fragments.data.commit_tag_name, &fwinfo->commit_tag_name, sizeof(sysPkt.fragments.data.commit_tag_name));
memcpy(&sysPkt.fragments.data.sha1sum, &fwinfo->commit_tag_name, sizeof(sysPkt.fragments.data.sha1sum));
memcpy(&sysPkt.fragments.data.sha1sum, &fwinfo->sha1sum, sizeof(sysPkt.fragments.data.sha1sum));
}
/**

View File

@ -33,15 +33,13 @@
#ifdef PIOS_INCLUDE_MPU6000
#include "fifo_buffer.h"
#include <pios_constants.h>
/* Global Variables */
enum pios_mpu6000_dev_magic {
PIOS_MPU6000_DEV_MAGIC = 0x9da9b3ed,
};
#define PIOS_MPU6000_MAX_DOWNSAMPLE 2
struct mpu6000_dev {
uint32_t spi_id;
uint32_t slave_num;
@ -53,29 +51,58 @@ struct mpu6000_dev {
enum pios_mpu6000_dev_magic magic;
};
#ifdef PIOS_MPU6000_ACCEL
#define PIOS_MPU6000_SAMPLES_BYTES 14
#define PIOS_MPU6000_SENSOR_FIRST_REG PIOS_MPU6000_ACCEL_X_OUT_MSB
#else
#define PIOS_MPU6000_SENSOR_FIRST_REG PIOS_MPU6000_TEMP_OUT_MSB
#define PIOS_MPU6000_SAMPLES_BYTES 8
#endif
typedef union {
uint8_t buffer[1 + PIOS_MPU6000_SAMPLES_BYTES];
struct {
uint8_t dummy;
#ifdef PIOS_MPU6000_ACCEL
uint8_t Accel_X_h;
uint8_t Accel_X_l;
uint8_t Accel_Y_h;
uint8_t Accel_Y_l;
uint8_t Accel_Z_h;
uint8_t Accel_Z_l;
#endif
uint8_t Temperature_h;
uint8_t Temperature_l;
uint8_t Gyro_X_h;
uint8_t Gyro_X_l;
uint8_t Gyro_Y_h;
uint8_t Gyro_Y_l;
uint8_t Gyro_Z_h;
uint8_t Gyro_Z_l;
} data;
} mpu6000_data_t;
#define GET_SENSOR_DATA(mpudataptr, sensor) (mpudataptr.data.sensor##_h << 8 | mpudataptr.data.sensor##_l)
// ! Global structure for this device device
static struct mpu6000_dev *dev;
volatile bool mpu6000_configured = false;
static mpu6000_data_t mpu6000_data;
// ! Private functions
static struct mpu6000_dev *PIOS_MPU6000_alloc(void);
static struct mpu6000_dev *PIOS_MPU6000_alloc(const struct pios_mpu6000_cfg *cfg);
static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev *dev);
static void PIOS_MPU6000_Config(struct pios_mpu6000_cfg const *cfg);
static int32_t PIOS_MPU6000_SetReg(uint8_t address, uint8_t buffer);
static int32_t PIOS_MPU6000_GetReg(uint8_t address);
#define GRAV 9.81f
#ifdef PIOS_MPU6000_ACCEL
#define PIOS_MPU6000_SAMPLES_BYTES 14
#else
#define PIOS_MPU6000_SAMPLES_BYTES 8
#endif
static void PIOS_MPU6000_SetSpeed(const bool fast);
static bool PIOS_MPU6000_HandleData();
static bool PIOS_MPU6000_ReadFifo(bool *woken);
static bool PIOS_MPU6000_ReadSensor(bool *woken);
/**
* @brief Allocate a new device
*/
static struct mpu6000_dev *PIOS_MPU6000_alloc(void)
static struct mpu6000_dev *PIOS_MPU6000_alloc(const struct pios_mpu6000_cfg *cfg)
{
struct mpu6000_dev *mpu6000_dev;
@ -86,7 +113,7 @@ static struct mpu6000_dev *PIOS_MPU6000_alloc(void)
mpu6000_dev->magic = PIOS_MPU6000_DEV_MAGIC;
mpu6000_dev->queue = xQueueCreate(PIOS_MPU6000_MAX_DOWNSAMPLE, sizeof(struct pios_mpu6000_data));
mpu6000_dev->queue = xQueueCreate(cfg->max_downsample + 1, sizeof(struct pios_mpu6000_data));
if (mpu6000_dev->queue == NULL) {
vPortFree(mpu6000_dev);
return NULL;
@ -119,7 +146,7 @@ static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev *vdev)
*/
int32_t PIOS_MPU6000_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_mpu6000_cfg *cfg)
{
dev = PIOS_MPU6000_alloc();
dev = PIOS_MPU6000_alloc(cfg);
if (dev == NULL) {
return -1;
}
@ -129,9 +156,7 @@ int32_t PIOS_MPU6000_Init(uint32_t spi_id, uint32_t slave_num, const struct pios
dev->cfg = cfg;
/* Configure the MPU6000 Sensor */
PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_256);
PIOS_MPU6000_Config(cfg);
PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_16);
/* Set up EXTI line */
PIOS_EXTI_Init(cfg->exti_cfg);
@ -234,11 +259,6 @@ int32_t PIOS_MPU6000_ConfigureRanges(
return -1;
}
// TODO: check that changing the SPI clock speed is safe
// to do here given that interrupts are enabled and the bus has
// not been claimed/is not claimed during this call
PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_256);
// update filter settings
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_DLPF_CFG_REG, filterSetting) != 0) {
;
@ -267,7 +287,6 @@ int32_t PIOS_MPU6000_ConfigureRanges(
dev->accel_range = accelRange;
#endif
PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_16);
return 0;
}
@ -275,7 +294,7 @@ int32_t PIOS_MPU6000_ConfigureRanges(
* @brief Claim the SPI bus for the accel communications and select this chip
* @return 0 if successful, -1 for invalid device, -2 if unable to claim bus
*/
static int32_t PIOS_MPU6000_ClaimBus()
static int32_t PIOS_MPU6000_ClaimBus(bool fast_spi)
{
if (PIOS_MPU6000_Validate(dev) != 0) {
return -1;
@ -283,17 +302,28 @@ static int32_t PIOS_MPU6000_ClaimBus()
if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) {
return -2;
}
PIOS_MPU6000_SetSpeed(fast_spi);
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
return 0;
}
static void PIOS_MPU6000_SetSpeed(const bool fast)
{
if (fast) {
PIOS_SPI_SetClockSpeed(dev->spi_id, dev->cfg->fast_prescaler);
} else {
PIOS_SPI_SetClockSpeed(dev->spi_id, dev->cfg->std_prescaler);
}
}
/**
* @brief Claim the SPI bus for the accel communications and select this chip
* @return 0 if successful, -1 for invalid device, -2 if unable to claim bus
* @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
*/
static int32_t PIOS_MPU6000_ClaimBusISR(bool *woken)
static int32_t PIOS_MPU6000_ClaimBusISR(bool *woken, bool fast_spi)
{
if (PIOS_MPU6000_Validate(dev) != 0) {
return -1;
@ -301,6 +331,7 @@ static int32_t PIOS_MPU6000_ClaimBusISR(bool *woken)
if (PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) {
return -2;
}
PIOS_MPU6000_SetSpeed(fast_spi);
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
return 0;
}
@ -342,7 +373,7 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg)
{
uint8_t data;
if (PIOS_MPU6000_ClaimBus() != 0) {
if (PIOS_MPU6000_ClaimBus(false) != 0) {
return -1;
}
@ -363,7 +394,7 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg)
*/
static int32_t PIOS_MPU6000_SetReg(uint8_t reg, uint8_t data)
{
if (PIOS_MPU6000_ClaimBus() != 0) {
if (PIOS_MPU6000_ClaimBus(false) != 0) {
return -1;
}
@ -393,7 +424,7 @@ int32_t PIOS_MPU6000_ReadGyros(struct pios_mpu6000_data *data)
uint8_t buf[7] = { PIOS_MPU6000_GYRO_X_OUT_MSB | 0x80, 0, 0, 0, 0, 0, 0 };
uint8_t rec[7];
if (PIOS_MPU6000_ClaimBus() != 0) {
if (PIOS_MPU6000_ClaimBus(true) != 0) {
return -1;
}
@ -460,16 +491,16 @@ float PIOS_MPU6000_GetAccelScale()
{
switch (dev->accel_range) {
case PIOS_MPU6000_ACCEL_2G:
return GRAV / 16384.0f;
return PIOS_CONST_MKS_GRAV_ACCEL_F / 16384.0f;
case PIOS_MPU6000_ACCEL_4G:
return GRAV / 8192.0f;
return PIOS_CONST_MKS_GRAV_ACCEL_F / 8192.0f;
case PIOS_MPU6000_ACCEL_8G:
return GRAV / 4096.0f;
return PIOS_CONST_MKS_GRAV_ACCEL_F / 4096.0f;
case PIOS_MPU6000_ACCEL_16G:
return GRAV / 2048.0f;
return PIOS_CONST_MKS_GRAV_ACCEL_F / 2048.0f;
}
return 0;
}
@ -504,7 +535,7 @@ static int32_t PIOS_MPU6000_GetInterruptStatusRegISR(bool *woken)
/* Interrupt Status register can be read at high SPI clock speed */
uint8_t data;
if (PIOS_MPU6000_ClaimBusISR(woken) != 0) {
if (PIOS_MPU6000_ClaimBusISR(woken, false) != 0) {
return -1;
}
PIOS_SPI_TransferByte(dev->spi_id, (0x80 | PIOS_MPU6000_INT_STATUS_REG));
@ -525,29 +556,16 @@ static int32_t PIOS_MPU6000_ResetFifoISR(bool *woken)
{
int32_t result = 0;
/* Register writes must be at < 1MHz SPI clock.
* Speed can only be changed when SPI bus semaphore is held, but
* device chip select must not be enabled, so we use the direct
* SPI bus claim call here */
if (PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) {
if (PIOS_MPU6000_ClaimBusISR(woken, false) != 0) {
return -1;
}
/* Reduce SPI clock speed. */
PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_256);
/* Enable chip select */
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
/* Reset FIFO. */
if (PIOS_SPI_TransferByte(dev->spi_id, 0x7f & PIOS_MPU6000_USER_CTRL_REG) != 0) {
result = -2;
} else if (PIOS_SPI_TransferByte(dev->spi_id, (dev->cfg->User_ctl | PIOS_MPU6000_USERCTL_FIFO_RST)) != 0) {
result = -2;
}
/* Disable chip select. */
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
/* Increase SPI clock speed. */
PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_16);
/* Release the SPI bus semaphore. */
PIOS_SPI_ReleaseBusISR(dev->spi_id, woken);
PIOS_MPU6000_ReleaseBusISR(woken);
return result;
}
@ -562,7 +580,7 @@ static int32_t PIOS_MPU6000_FifoDepthISR(bool *woken)
uint8_t mpu6000_send_buf[3] = { PIOS_MPU6000_FIFO_CNT_MSB | 0x80, 0, 0 };
uint8_t mpu6000_rec_buf[3];
if (PIOS_MPU6000_ClaimBusISR(woken) != 0) {
if (PIOS_MPU6000_ClaimBusISR(woken, false) != 0) {
return -1;
}
@ -604,6 +622,97 @@ bool PIOS_MPU6000_IRQHandler(void)
return false;
}
bool read_ok = false;
if (dev->cfg->User_ctl & PIOS_MPU6000_USERCTL_FIFO_EN) {
read_ok = PIOS_MPU6000_ReadFifo(&woken);
} else {
read_ok = PIOS_MPU6000_ReadSensor(&woken);
}
if (read_ok) {
bool woken2 = PIOS_MPU6000_HandleData();
woken |= woken2;
}
mpu6000_irq++;
mpu6000_time_us = PIOS_DELAY_DiffuS(timeval);
return woken;
}
static bool PIOS_MPU6000_HandleData()
{
// Rotate the sensor to OP convention. The datasheet defines X as towards the right
// and Y as forward. OP convention transposes this. Also the Z is defined negatively
// to our convention
static struct pios_mpu6000_data data;
// Currently we only support rotations on top so switch X/Y accordingly
switch (dev->cfg->orientation) {
case PIOS_MPU6000_TOP_0DEG:
#ifdef PIOS_MPU6000_ACCEL
data.accel_y = GET_SENSOR_DATA(mpu6000_data, Accel_X); // chip X
data.accel_x = GET_SENSOR_DATA(mpu6000_data, Accel_Y); // chip Y
#endif
data.gyro_y = GET_SENSOR_DATA(mpu6000_data, Gyro_X); // chip X
data.gyro_x = GET_SENSOR_DATA(mpu6000_data, Gyro_Y); // chip Y
break;
case PIOS_MPU6000_TOP_90DEG:
// -1 to bring it back to -32768 +32767 range
#ifdef PIOS_MPU6000_ACCEL
data.accel_y = -1 - (GET_SENSOR_DATA(mpu6000_data, Accel_Y)); // chip Y
data.accel_x = GET_SENSOR_DATA(mpu6000_data, Accel_X); // chip X
#endif
data.gyro_y = -1 - (GET_SENSOR_DATA(mpu6000_data, Gyro_Y)); // chip Y
data.gyro_x = GET_SENSOR_DATA(mpu6000_data, Gyro_X); // chip X
break;
case PIOS_MPU6000_TOP_180DEG:
#ifdef PIOS_MPU6000_ACCEL
data.accel_y = -1 - (GET_SENSOR_DATA(mpu6000_data, Accel_X)); // chip X
data.accel_x = -1 - (GET_SENSOR_DATA(mpu6000_data, Accel_Y)); // chip Y
#endif
data.gyro_y = -1 - (GET_SENSOR_DATA(mpu6000_data, Gyro_X)); // chip X
data.gyro_x = -1 - (GET_SENSOR_DATA(mpu6000_data, Gyro_Y)); // chip Y
break;
case PIOS_MPU6000_TOP_270DEG:
#ifdef PIOS_MPU6000_ACCEL
data.accel_y = GET_SENSOR_DATA(mpu6000_data, Accel_Y); // chip Y
data.accel_x = -1 - (GET_SENSOR_DATA(mpu6000_data, Accel_X)); // chip X
#endif
data.gyro_y = GET_SENSOR_DATA(mpu6000_data, Gyro_Y); // chip Y
data.gyro_x = -1 - (GET_SENSOR_DATA(mpu6000_data, Gyro_X)); // chip X
break;
}
#ifdef PIOS_MPU6000_ACCEL
data.accel_z = -1 - (GET_SENSOR_DATA(mpu6000_data, Accel_Z));
#endif
data.gyro_z = -1 - (GET_SENSOR_DATA(mpu6000_data, Gyro_Z));
data.temperature = GET_SENSOR_DATA(mpu6000_data, Temperature);
BaseType_t higherPriorityTaskWoken;
xQueueSendToBackFromISR(dev->queue, (void *)&data, &higherPriorityTaskWoken);
return higherPriorityTaskWoken == pdTRUE;
}
static bool PIOS_MPU6000_ReadSensor(bool *woken)
{
const uint8_t mpu6000_send_buf[1 + PIOS_MPU6000_SAMPLES_BYTES] = { PIOS_MPU6000_SENSOR_FIRST_REG | 0x80 };
if (PIOS_MPU6000_ClaimBusISR(woken, true) != 0) {
return false;
}
if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_data.buffer[0], sizeof(mpu6000_data_t), NULL) < 0) {
PIOS_MPU6000_ReleaseBusISR(woken);
mpu6000_fails++;
return false;
}
PIOS_MPU6000_ReleaseBusISR(woken);
return true;
}
static bool PIOS_MPU6000_ReadFifo(bool *woken)
{
/* Temporary fix for OP-1049. Expected to be superceded for next major release
* by code changes for OP-1039.
* Read interrupt status register to check for FIFO overflow. Must be the
@ -611,128 +720,57 @@ bool PIOS_MPU6000_IRQHandler(void)
* any read clears in the status register (PIOS_MPU6000_INT_CLR_ANYRD set in
* interrupt config register) */
int32_t result;
if ((result = PIOS_MPU6000_GetInterruptStatusRegISR(&woken)) < 0) {
return woken;
if ((result = PIOS_MPU6000_GetInterruptStatusRegISR(woken)) < 0) {
return false;
}
if (result & PIOS_MPU6000_INT_STATUS_FIFO_OVERFLOW) {
/* The FIFO has overflowed, so reset it,
* to enable sample sync to be recovered.
* If the reset fails, we are in trouble, but
* we keep trying on subsequent interrupts. */
PIOS_MPU6000_ResetFifoISR(&woken);
PIOS_MPU6000_ResetFifoISR(woken);
/* Return and wait for the next new sample. */
return woken;
return false;
}
/* Usual case - FIFO has not overflowed. */
mpu6000_count = PIOS_MPU6000_FifoDepthISR(&woken);
mpu6000_count = PIOS_MPU6000_FifoDepthISR(woken);
if (mpu6000_count < PIOS_MPU6000_SAMPLES_BYTES) {
return woken;
return false;
}
if (PIOS_MPU6000_ClaimBusISR(&woken) != 0) {
return woken;
if (PIOS_MPU6000_ClaimBusISR(woken, true) != 0) {
return false;
}
static uint8_t mpu6000_send_buf[1 + PIOS_MPU6000_SAMPLES_BYTES] = { PIOS_MPU6000_FIFO_REG | 0x80 };
static uint8_t mpu6000_rec_buf[1 + PIOS_MPU6000_SAMPLES_BYTES];
const uint8_t mpu6000_send_buf[1 + PIOS_MPU6000_SAMPLES_BYTES] = { PIOS_MPU6000_FIFO_REG | 0x80 };
if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) {
PIOS_MPU6000_ReleaseBusISR(&woken);
if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_data.buffer[0], sizeof(mpu6000_data_t), NULL) < 0) {
PIOS_MPU6000_ReleaseBusISR(woken);
mpu6000_fails++;
return woken;
return false;
}
PIOS_MPU6000_ReleaseBusISR(&woken);
static struct pios_mpu6000_data data;
PIOS_MPU6000_ReleaseBusISR(woken);
// In the case where extras samples backed up grabbed an extra
if (mpu6000_count >= PIOS_MPU6000_SAMPLES_BYTES * 2) {
mpu6000_fifo_backup++;
if (PIOS_MPU6000_ClaimBusISR(&woken) != 0) {
return woken;
if (PIOS_MPU6000_ClaimBusISR(woken, true) != 0) {
return false;
}
if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) {
PIOS_MPU6000_ReleaseBusISR(&woken);
if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_data.buffer[0], sizeof(mpu6000_data_t), NULL) < 0) {
PIOS_MPU6000_ReleaseBusISR(woken);
mpu6000_fails++;
return woken;
return false;
}
PIOS_MPU6000_ReleaseBusISR(&woken);
PIOS_MPU6000_ReleaseBusISR(woken);
}
// Rotate the sensor to OP convention. The datasheet defines X as towards the right
// and Y as forward. OP convention transposes this. Also the Z is defined negatively
// to our convention
#if defined(PIOS_MPU6000_ACCEL)
// Currently we only support rotations on top so switch X/Y accordingly
switch (dev->cfg->orientation) {
case PIOS_MPU6000_TOP_0DEG:
data.accel_y = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; // chip X
data.accel_x = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; // chip Y
data.gyro_y = mpu6000_rec_buf[9] << 8 | mpu6000_rec_buf[10]; // chip X
data.gyro_x = mpu6000_rec_buf[11] << 8 | mpu6000_rec_buf[12]; // chip Y
break;
case PIOS_MPU6000_TOP_90DEG:
// -1 to bring it back to -32768 +32767 range
data.accel_y = -1 - (mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]); // chip Y
data.accel_x = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; // chip X
data.gyro_y = -1 - (mpu6000_rec_buf[11] << 8 | mpu6000_rec_buf[12]); // chip Y
data.gyro_x = mpu6000_rec_buf[9] << 8 | mpu6000_rec_buf[10]; // chip X
break;
case PIOS_MPU6000_TOP_180DEG:
data.accel_y = -1 - (mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]); // chip X
data.accel_x = -1 - (mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]); // chip Y
data.gyro_y = -1 - (mpu6000_rec_buf[9] << 8 | mpu6000_rec_buf[10]); // chip X
data.gyro_x = -1 - (mpu6000_rec_buf[11] << 8 | mpu6000_rec_buf[12]); // chip Y
break;
case PIOS_MPU6000_TOP_270DEG:
data.accel_y = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; // chip Y
data.accel_x = -1 - (mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]); // chip X
data.gyro_y = mpu6000_rec_buf[11] << 8 | mpu6000_rec_buf[12]; // chip Y
data.gyro_x = -1 - (mpu6000_rec_buf[9] << 8 | mpu6000_rec_buf[10]); // chip X
break;
}
data.gyro_z = -1 - (mpu6000_rec_buf[13] << 8 | mpu6000_rec_buf[14]);
data.accel_z = -1 - (mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]);
data.temperature = mpu6000_rec_buf[7] << 8 | mpu6000_rec_buf[8];
#else /* if defined(PIOS_MPU6000_ACCEL) */
data.gyro_x = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4];
data.gyro_y = mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6];
switch (dev->cfg->orientation) {
case PIOS_MPU6000_TOP_0DEG:
data.gyro_y = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4];
data.gyro_x = mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6];
break;
case PIOS_MPU6000_TOP_90DEG:
data.gyro_y = -1 - (mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]); // chip Y
data.gyro_x = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; // chip X
break;
case PIOS_MPU6000_TOP_180DEG:
data.gyro_y = -1 - (mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]);
data.gyro_x = -1 - (mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]);
break;
case PIOS_MPU6000_TOP_270DEG:
data.gyro_y = mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]; // chip Y
data.gyro_x = -1 - (mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]); // chip X
break;
}
data.gyro_z = -1 - (mpu6000_rec_buf[7] << 8 | mpu6000_rec_buf[8]);
data.temperature = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2];
#endif /* if defined(PIOS_MPU6000_ACCEL) */
signed portBASE_TYPE higherPriorityTaskWoken;
xQueueSendToBackFromISR(dev->queue, (void *)&data, &higherPriorityTaskWoken);
mpu6000_irq++;
mpu6000_time_us = PIOS_DELAY_DiffuS(timeval);
return woken || higherPriorityTaskWoken == pdTRUE;
return true;
}
#endif /* PIOS_INCLUDE_MPU6000 */
/**

View File

@ -116,8 +116,6 @@
#define USB_LED_OFF
#endif
#define CONNECTED_LIVE 8
/* Local type definitions */
struct pios_rfm22b_transition {
@ -360,7 +358,7 @@ static const uint8_t reg_72[] = { 0x30, 0x48, 0x48, 0x48, 0x48, 0x60, 0x90, 0xCD
static const uint8_t packet_time[] = { 80, 40, 25, 15, 13, 10, 8, 6, 5 };
static const uint8_t packet_time_ppm[] = { 26, 25, 25, 15, 13, 10, 8, 6, 5 };
static const uint8_t num_channels[] = { 32, 32, 32, 32, 32, 32, 32, 32, 32 };
static const uint8_t num_channels[] = { 4, 4, 4, 6, 8, 8, 10, 12, 16 };
static struct pios_rfm22b_dev *g_rfm22b_dev = NULL;
@ -608,8 +606,6 @@ void PIOS_RFM22B_SetChannelConfig(uint32_t rfm22b_id, enum rfm22b_datarate datar
}
}
rfm22b_dev->num_channels = num_found;
// Calculate the maximum packet length from the datarate.
float bytes_per_period = (float)data_rate[datarate] * (float)(rfm22b_dev->packet_time - 2) / 9000;
@ -1359,7 +1355,7 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
rfm22b_dev->packet_start_ticks = 0;
rfm22b_dev->tx_complete_ticks = 0;
rfm22b_dev->rfm22b_state = RFM22B_STATE_INITIALIZING;
rfm22b_dev->connected_timeout = 0;
rfm22b_dev->on_sync_channel = false;
// software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B)
rfm22_write_claim(rfm22b_dev, RFM22_op_and_func_ctrl1, RFM22_opfc1_swres);
@ -1803,8 +1799,8 @@ static enum pios_radio_event radio_txStart(struct pios_rfm22b_dev *radio_dev)
len += (radio_dev->tx_out_cb)(radio_dev->tx_out_context, p + len, max_data_len - len, NULL, &need_yield);
}
// Always send a packet if this modem is a coordinator.
if ((len == 0) && !rfm22_isCoordinator(radio_dev)) {
// Always send a packet on the sync channel if this modem is a coordinator.
if ((len == 0) && ((radio_dev->channel_index != 0) || !rfm22_isCoordinator(radio_dev))) {
return RADIO_EVENT_RX_MODE;
}
@ -1964,16 +1960,12 @@ static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *radio_d
(radio_dev->rx_in_cb)(radio_dev->rx_in_context, p, data_len, NULL, &rx_need_yield);
}
/*
* If the packet is valid and destined for us we synchronize the clock.
*/
if (!rfm22_isCoordinator(radio_dev) &&
radio_dev->rx_destination_id == rfm22_destinationID(radio_dev)) {
// We only synchronize the clock on packets from our coordinator on the sync channel.
if (!rfm22_isCoordinator(radio_dev) && (radio_dev->rx_destination_id == rfm22_destinationID(radio_dev)) && (radio_dev->channel_index == 0)) {
rfm22_synchronizeClock(radio_dev);
radio_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_CONNECTED;
radio_dev->on_sync_channel = false;
}
radio_dev->connected_timeout = CONNECTED_LIVE;
} else {
ret_event = RADIO_EVENT_RX_COMPLETE;
}
@ -2169,14 +2161,14 @@ static void rfm22_synchronizeClock(struct pios_rfm22b_dev *rfm22b_dev)
portTickType start_time = rfm22b_dev->packet_start_ticks;
// This packet was transmitted on channel 0, calculate the time delta that will force us to transmit on channel 0 at the time this packet started.
uint16_t frequency_hop_cycle_time = rfm22b_dev->packet_time * rfm22b_dev->num_channels;
uint8_t num_chan = num_channels[rfm22b_dev->datarate];
uint16_t frequency_hop_cycle_time = rfm22b_dev->packet_time * num_chan;
uint16_t time_delta = start_time % frequency_hop_cycle_time;
// Calculate the adjustment for the preamble
uint8_t offset = (uint8_t)ceil(35000.0F / data_rate[rfm22b_dev->datarate]);
rfm22b_dev->time_delta = frequency_hop_cycle_time - time_delta + offset +
rfm22b_dev->packet_time * rfm22b_dev->channel_index;
rfm22b_dev->time_delta = frequency_hop_cycle_time - time_delta + offset;
}
/**
@ -2231,11 +2223,14 @@ static bool rfm22_timeToSend(struct pios_rfm22b_dev *rfm22b_dev)
static uint8_t rfm22_calcChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t index)
{
// Make sure we don't index outside of the range.
uint8_t idx = index % rfm22b_dev->num_channels;
uint8_t num_chan = num_channels[rfm22b_dev->datarate];
uint8_t idx = index % num_chan;
// Are we switching to a new channel?
if (idx != rfm22b_dev->channel_index) {
if (!rfm22_isCoordinator(rfm22b_dev) && rfm22b_dev->connected_timeout == 0) {
// If the on_sync_channel flag is set, it means that we were on the sync channel, but no packet was received, so transition to a non-connected state.
if (!rfm22_isCoordinator(rfm22b_dev) && (rfm22b_dev->channel_index == 0) && rfm22b_dev->on_sync_channel) {
rfm22b_dev->on_sync_channel = false;
// Set the link state to disconnected.
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED) {
@ -2246,14 +2241,14 @@ static uint8_t rfm22_calcChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t ind
}
}
// Stay on first channel.
// Stay on the sync channel.
idx = 0;
} else if (idx == 0) {
// If we're switching to the sync channel, set a flag that can be used to detect if a packet was received.
rfm22b_dev->on_sync_channel = true;
}
rfm22b_dev->channel_index = idx;
if (rfm22b_dev->connected_timeout > 0)
rfm22b_dev->connected_timeout--;
}
return rfm22b_dev->channels[idx];
@ -2269,7 +2264,8 @@ static uint8_t rfm22_calcChannelFromClock(struct pios_rfm22b_dev *rfm22b_dev)
portTickType time = rfm22_coordinatorTime(rfm22b_dev, xTaskGetTickCount());
// Divide time into 8ms blocks. Coordinator sends in first 2 ms, and remote send in 5th and 6th ms.
// Channel changes occur in the last 2 ms.
uint8_t n = (time / rfm22b_dev->packet_time) % rfm22b_dev->num_channels;
uint8_t num_chan = num_channels[rfm22b_dev->datarate];
uint8_t n = (time / rfm22b_dev->packet_time) % num_chan;
return rfm22_calcChannel(rfm22b_dev, n);
}

View File

@ -159,6 +159,9 @@ struct pios_mpu6000_cfg {
enum pios_mpu6000_range gyro_range;
enum pios_mpu6000_filter filter;
enum pios_mpu6000_orientation orientation;
SPIPrescalerTypeDef fast_prescaler;
SPIPrescalerTypeDef std_prescaler;
uint8_t max_downsample;
};
/* Public Functions */

View File

@ -780,7 +780,7 @@ struct pios_rfm22b_dev {
portTickType packet_start_ticks;
portTickType tx_complete_ticks;
portTickType time_delta;
uint8_t connected_timeout;
bool on_sync_channel;
};

View File

@ -44,6 +44,7 @@ static bool PIOS_SPI_validate(__attribute__((unused)) struct pios_spi_dev *com_d
/* Should check device magic here */
return true;
}
#define SPI_MAX_BLOCK_PIO 128
#if defined(PIOS_INCLUDE_FREERTOS)
static struct pios_spi_dev *PIOS_SPI_alloc(void)
@ -432,23 +433,7 @@ int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b)
return rx_byte;
}
/**
* Transfers a block of bytes via DMA.
* \param[in] spi SPI number (0 or 1)
* \param[in] send_buffer pointer to buffer which should be sent.<BR>
* If NULL, 0xff (all-one) will be sent.
* \param[in] receive_buffer pointer to buffer which should get the received values.<BR>
* If NULL, received bytes will be discarded.
* \param[in] len number of bytes which should be transfered
* \param[in] callback pointer to callback function which will be executed
* from DMA channel interrupt once the transfer is finished.
* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will
* block until the transfer is finished.
* \return >= 0 if no error during transfer
* \return -1 if disabled SPI port selected
* \return -3 if function has been called during an ongoing DMA transfer
*/
int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback)
static int32_t SPI_DMA_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback)
{
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
@ -580,6 +565,95 @@ int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint
return 0;
}
/**
* Transfers a block of bytes via PIO.
*
* \param[in] spi_id SPI device handle
* \param[in] send_buffer pointer to buffer which should be sent.<BR>
* If NULL, 0xff (all-one) will be sent.
* \param[in] receive_buffer pointer to buffer which should get the received values.<BR>
* If NULL, received bytes will be discarded.
* \param[in] len number of bytes which should be transfered
* \return >= 0 if no error during transfer
* \return -1 if disabled SPI port selected
* \return -3 if function has been called during an ongoing DMA transfer
*/
static int32_t SPI_PIO_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len)
{
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
uint8_t b;
bool valid = PIOS_SPI_validate(spi_dev);
PIOS_Assert(valid)
/* Exit if ongoing transfer */
if (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)) {
return -3;
}
/* Make sure the RXNE flag is cleared by reading the DR register */
b = spi_dev->cfg->regs->DR;
while (len--) {
/* get the byte to send */
b = send_buffer ? *(send_buffer++) : 0xff;
/* Start the transfer */
spi_dev->cfg->regs->DR = b;
/* Wait until there is a byte to read */
while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_RXNE)) {
;
}
/* Read the rx'd byte */
b = spi_dev->cfg->regs->DR;
/* save the received byte */
if (receive_buffer) {
*(receive_buffer++) = b;
}
/* Wait until the TXE goes high */
while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_TXE)) {
;
}
}
/* Wait for SPI transfer to have fully completed */
while (spi_dev->cfg->regs->SR & SPI_I2S_FLAG_BSY) {
;
}
return 0;
}
/**
* Transfers a block of bytes via PIO or DMA.
* \param[in] spi_id SPI device handle
* \param[in] send_buffer pointer to buffer which should be sent.<BR>
* If NULL, 0xff (all-one) will be sent.
* \param[in] receive_buffer pointer to buffer which should get the received values.<BR>
* If NULL, received bytes will be discarded.
* \param[in] len number of bytes which should be transfered
* \param[in] callback pointer to callback function which will be executed
* from DMA channel interrupt once the transfer is finished.
* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will
* block until the transfer is finished.
* \return >= 0 if no error during transfer
* \return -1 if disabled SPI port selected
* \return -3 if function has been called during an ongoing DMA transfer
*/
int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback)
{
if (callback || len > SPI_MAX_BLOCK_PIO) {
return SPI_DMA_TransferBlock(spi_id, send_buffer, receive_buffer, len, callback);
}
return SPI_PIO_TransferBlock(spi_id, send_buffer, receive_buffer, len);
}
/**
* Check if a transfer is in progress
* \param[in] spi SPI number (0 or 1)

View File

@ -418,7 +418,9 @@ static uint8_t PIOS_USBHOOK_CLASS_DataOut(void *pdev, uint8_t epnum)
if ((epnum_idx < NELEMENTS(usb_epout_table)) && usb_epout_table[epnum_idx].cb) {
struct usb_ep_entry *ep = &(usb_epout_table[epnum_idx]);
if (!ep->cb(ep->context, epnum_idx, ep->max_len)) {
uint16_t len = USBD_GetRxCount(pdev, epnum);
PIOS_Assert(ep->max_len >= len);
if (!ep->cb(ep->context, epnum_idx, len)) {
/* NOTE: use real endpoint number including direction bit */
DCD_SetEPStatus(pdev, epnum, USB_OTG_EP_RX_NAK);
}

View File

@ -260,7 +260,7 @@ static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc3d = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_13,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
@ -268,7 +268,7 @@ static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc3d = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_14,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
@ -276,7 +276,7 @@ static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc3d = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
@ -360,7 +360,7 @@ static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_13,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
@ -368,7 +368,7 @@ static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_14,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
@ -376,7 +376,7 @@ static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},

View File

@ -92,6 +92,8 @@
/* #define PIOS_INCLUDE_ETASV3 */
/* #define PIOS_INCLUDE_HCSR04 */
#define PIOS_SENSOR_RATE 500.0f
/* PIOS receiver drivers */
#define PIOS_INCLUDE_PWM
#define PIOS_INCLUDE_PPM

View File

@ -119,18 +119,21 @@ static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = {
static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
.exti_cfg = &pios_exti_mpu6000_cfg,
.Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT,
// Clock at 8 khz, downsampled by 16 for 500 Hz
.Smpl_rate_div_no_dlp = 15,
// Clock at 1 khz, downsampled by 2 for 500 Hz
.Smpl_rate_div_dlp = 1,
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN | PIOS_MPU6000_USERCTL_DIS_I2C,
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
.accel_range = PIOS_MPU6000_ACCEL_8G,
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
// Clock at 8 khz, downsampled by 8 for 1000 Hz
.Smpl_rate_div_no_dlp = 7,
// Clock at 1 khz, downsampled by 1 for 1000 Hz
.Smpl_rate_div_dlp = 0,
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU6000_USERCTL_DIS_I2C,
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
.accel_range = PIOS_MPU6000_ACCEL_8G,
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
.filter = PIOS_MPU6000_LOWPASS_256_HZ,
.orientation = PIOS_MPU6000_TOP_180DEG
.orientation = PIOS_MPU6000_TOP_180DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 2
};
#endif /* PIOS_INCLUDE_MPU6000 */

View File

@ -91,6 +91,9 @@
// #define PIOS_INCLUDE_MPXV
// #define PIOS_INCLUDE_ETASV3
/* #define PIOS_INCLUDE_HCSR04 */
#define PIOS_SENSOR_RATE 500.0f
#define PIOS_INCLUDE_WS2811
/* PIOS receiver drivers */

View File

@ -1092,6 +1092,53 @@ static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = {
},
};
static const struct pios_usart_cfg pios_usart_rcvrport_cfg = {
.regs = USART6,
.remap = GPIO_AF_USART6,
.init = {
.USART_BaudRate = 57600,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART6_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.tx = {
// * 7: PC6 = TIM8 CH1, USART6 TX
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource6,
},
.rx = {
// * 8: PC7 = TIM8 CH2, USART6 RX
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource7,
}
};
#if defined(PIOS_INCLUDE_COM)
#include <pios_com_priv.h>

View File

@ -91,11 +91,12 @@
#define PIOS_INCLUDE_MPXV
#define PIOS_INCLUDE_ETASV3
#define PIOS_INCLUDE_MS4525DO
/* #define PIOS_INCLUDE_HCSR04 */
#define PIOS_SENSOR_RATE 500.0f
#define PIOS_INCLUDE_WS2811
/* #define PIOS_INCLUDE_HCSR04 */
/* PIOS receiver drivers */
#define PIOS_INCLUDE_PWM
#define PIOS_INCLUDE_PPM

View File

@ -192,18 +192,21 @@ static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = {
static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
.exti_cfg = &pios_exti_mpu6000_cfg,
.Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT,
// Clock at 8 khz, downsampled by 12 for 666Hz
.Smpl_rate_div_no_dlp = 11,
// with dlp on output rate is 500Hz
.Smpl_rate_div_dlp = 1,
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN | PIOS_MPU6000_USERCTL_DIS_I2C,
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
.accel_range = PIOS_MPU6000_ACCEL_8G,
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
// Clock at 8 khz
.Smpl_rate_div_no_dlp = 0,
// with dlp on output rate is 1000Hz
.Smpl_rate_div_dlp = 0,
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU6000_USERCTL_DIS_I2C,
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
.accel_range = PIOS_MPU6000_ACCEL_8G,
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
.filter = PIOS_MPU6000_LOWPASS_256_HZ,
.orientation = PIOS_MPU6000_TOP_180DEG
.orientation = PIOS_MPU6000_TOP_180DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 16,
};
#endif /* PIOS_INCLUDE_MPU6000 */
@ -880,25 +883,33 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PPM:
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
case HWSETTINGS_RM_RCVRPORT_PPMPWM:
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
#if defined(PIOS_INCLUDE_PPM)
PIOS_Board_configure_ppm(&pios_ppm_cfg);
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
// configure servo outputs and the remaining 5 inputs as outputs
pios_servo_cfg = &pios_servo_cfg_out_in_ppm;
}
PIOS_Board_configure_ppm(&pios_ppm_cfg);
// enable pwm on the remaining channels
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMPWM) {
PIOS_Board_configure_pwm(&pios_pwm_ppm_cfg);
}
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY) {
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
}
break;
#endif /* PIOS_INCLUDE_PPM */
case HWSETTINGS_RM_RCVRPORT_OUTPUTS:
// configure only the servo outputs
pios_servo_cfg = &pios_servo_cfg_out_in;
break;
case HWSETTINGS_RM_RCVRPORT_TELEMETRY:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
break;
}

View File

@ -89,6 +89,8 @@
#define PIOS_INCLUDE_ETASV3
/* #define PIOS_INCLUDE_HCSR04 */
#define PIOS_SENSOR_RATE 500.0f
/* PIOS receiver drivers */
#define PIOS_INCLUDE_PWM
#define PIOS_INCLUDE_PPM

View File

@ -222,18 +222,21 @@ static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = {
static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
.exti_cfg = &pios_exti_mpu6000_cfg,
.Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT,
// Clock at 8 khz, downsampled by 12 for 666Hz
.Smpl_rate_div_no_dlp = 11,
// with dlp on output rate is 500Hz
.Smpl_rate_div_dlp = 1,
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN | PIOS_MPU6000_USERCTL_DIS_I2C,
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
.accel_range = PIOS_MPU6000_ACCEL_8G,
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
// Clock at 8 khz
.Smpl_rate_div_no_dlp = 0,
// with dlp on output rate is 1000Hz
.Smpl_rate_div_dlp = 0,
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU6000_USERCTL_DIS_I2C,
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
.accel_range = PIOS_MPU6000_ACCEL_8G,
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
.filter = PIOS_MPU6000_LOWPASS_256_HZ,
.orientation = PIOS_MPU6000_TOP_0DEG
.orientation = PIOS_MPU6000_TOP_0DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 16,
};
#endif /* PIOS_INCLUDE_MPU6000 */

View File

@ -70,6 +70,9 @@
// #define PIOS_INCLUDE_MS5611
// #define PIOS_INCLUDE_HCSR04
#define PIOS_FLASH_ON_ACCEL /* true for second revo */
#define PIOS_SENSOR_RATE 500.0f
#define FLASH_FREERTOS
/* Com systems to include */
#define PIOS_INCLUDE_COM

View File

@ -531,33 +531,6 @@
<translation>Le nom ne doit pas correspondre à un périphérique MS Windows. (%1).</translation>
</message>
</context>
<context>
<name>Utils::FileSearch</name>
<message numerus="yes">
<location filename="../../../src/libs/utils/filesearch.cpp" line="+46"/>
<source>%1: canceled. %n occurrences found in %2 files.</source>
<translation>
<numerusform>%1 : annulé. %n entrée trouvée dans %2 fichiers.</numerusform>
<numerusform>%1 : annulé. %n entrées trouvées dans %2 fichiers.</numerusform>
</translation>
</message>
<message numerus="yes">
<location line="+8"/>
<source>%1: %n occurrences found in %2 files.</source>
<translation>
<numerusform>%1 : %n occurrence trouvée dans %2 fichiers.</numerusform>
<numerusform>%1 : %n occurrences trouvées dans %2 fichiers.</numerusform>
</translation>
</message>
<message numerus="yes">
<location line="+8"/>
<source>%1: %n occurrences found in %2 of %3 files.</source>
<translation>
<numerusform>%1 : %n occurence trouvée dans %2 de %3 fichiers.</numerusform>
<numerusform>%1 : %n occurences trouvées dans %2 de %3 fichiers.</numerusform>
</translation>
</message>
</context>
<context>
<name>Utils::NewClassWidget</name>
<message>
@ -1475,10 +1448,20 @@ Raison : %3</translation>
<context>
<name>Welcome::WelcomeMode</name>
<message>
<location filename="../../../src/plugins/welcome/welcomemode.cpp" line="+88"/>
<location filename="../../../src/plugins/welcome/welcomemode.cpp" line="+107"/>
<source>Welcome</source>
<translation>Accueil</translation>
</message>
<message>
<location line="+60"/>
<source>Update Available: %1</source>
<translation>Mise à jour disponible : %1</translation>
</message>
<message>
<location filename="../../../src/plugins/welcome/welcomemode.h" line="+73"/>
<source>OpenPilot GCS Version: %1 </source>
<translation>OpenPilot GCS Version : %1 </translation>
</message>
</context>
<context>
<name>Utils::DetailsButton</name>
@ -1803,7 +1786,7 @@ Raison : %3</translation>
<message>
<location/>
<source>BaroAltitude</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -1843,12 +1826,12 @@ Raison : %3</translation>
<message>
<location/>
<source>AttitudeState</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>AirspeedState</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
</context>
<context>
@ -2737,6 +2720,11 @@ p, li { white-space: pre-wrap; }
<source>View Options</source>
<translation>Voir Options</translation>
</message>
<message>
<location/>
<source>This space shows a description of the selected UAVObject.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
<name>UAVObjectBrowserOptionsPage</name>
@ -2766,6 +2754,11 @@ p, li { white-space: pre-wrap; }
<translation>Mettre en évidence les noeuds
uniquement lorsque les valeurs changent</translation>
</message>
<message>
<location/>
<source>Unknown object color:</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
<name>QuaZipFile</name>
@ -3389,7 +3382,7 @@ uniquement lorsque les valeurs changent</translation>
<context>
<name>UAVObjectTreeModel</name>
<message>
<location filename="../../../src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp" line="+70"/>
<location filename="../../../src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp" line="+73"/>
<source>Property</source>
<translation>Propriété</translation>
</message>
@ -3414,12 +3407,12 @@ uniquement lorsque les valeurs changent</translation>
<translation>Objets Données</translation>
</message>
<message>
<location line="+74"/>
<location line="+75"/>
<source>Meta Data</source>
<translation>Métadonnées</translation>
</message>
<message>
<location line="+24"/>
<location line="+25"/>
<source>Instance</source>
<translation type="unfinished">Exemple</translation>
</message>
@ -3487,6 +3480,11 @@ uniquement lorsque les valeurs changent</translation>
<source>boolean</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+0"/>
<source>Metadata modes</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+1"/>
<source>Flight Telemetry Update Period</source>
@ -3500,15 +3498,30 @@ uniquement lorsque les valeurs changent</translation>
<translation></translation>
</message>
<message>
<location line="-1"/>
<location line="-2"/>
<source>This is how often flight side will update telemetry data</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+1"/>
<source>GCS Telemetry Update Period</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+0"/>
<source>This is how often GCS will update telemetry data</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+1"/>
<source>Logging Update Period</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+0"/>
<source>This is how often logging will be updated.</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
<name>TelemetryMonitor</name>
@ -3974,7 +3987,7 @@ Le SNR du satellite est affiché au-dessus (en dBHz)</translation>
<location/>
<source>Error Destination</source>
<translatorcomment>Destination d&apos;Erreur ?</translatorcomment>
<translation type="unfinished">Destination d&apos;Erreur</translation>
<translation>Destination d&apos;Erreur</translation>
</message>
<message>
<location/>
@ -4125,7 +4138,7 @@ under the level where the motor starts to undershoot
its target speed when decelerating.
Do it after accel time is setup.</source>
<translation type="unfinished">Lors du réglage : Augmentez lentement temps de décélération de zéro jusqu&apos;à
<translation>Lors du réglage : Augmentez lentement temps de décélération de zéro jusqu&apos;à
arriver juste en dessous du niveau le moteur commence à dépasser sa vitesse
de consigne lors de la décélération.
@ -4137,7 +4150,7 @@ A faire après avoir configuré la constante de temps d&apos;accélération.</tr
When tuning: Slowly raise accel time from zero to just
under the level where the motor starts to overshoot
its target speed.</source>
<translation type="unfinished">En millisecondes.
<translation>En millisecondes.
Lors du réglage : Augmentez lentement le temps d&apos;accélération de zéro jusqu&apos;à arriver juste
en dessous du niveau le moteur commence à dépasser sa vitesse de consigne.</translation>
@ -4150,13 +4163,13 @@ en dessous du niveau où le moteur commence à dépasser sa vitesse de consigne.
<message>
<location/>
<source>Overall level of feed forward (in percentage).</source>
<translation type="unfinished">Niveau global de Feed Forward (en pourcentage).</translation>
<translation>Niveau global de Feed Forward (en pourcentage).</translation>
</message>
<message>
<location/>
<source>Limits how much the engines can accelerate or decelerate.
In &apos;units per second&apos;, a sound default is 1000.</source>
<translation type="unfinished">Limite de combien les moteurs peuvent accélérer ou ralentir.
<translation>Limite de combien les moteurs peuvent accélérer ou ralentir.
En &apos;unités par seconde&apos;, la valeur par défaut est 1000.</translation>
</message>
<message>
@ -4182,7 +4195,7 @@ p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;Ubuntu&apos;; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Sans&apos;; font-size:10pt;&quot;&gt;Beware! Check &lt;/span&gt;&lt;span style=&quot; font-family:&apos;Sans&apos;; font-size:10pt; font-weight:600;&quot;&gt;all three&lt;/span&gt;&lt;span style=&quot; font-family:&apos;Sans&apos;; font-size:10pt;&quot;&gt; checkboxes to test Feed Forward.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Sans&apos;; font-size:10pt;&quot;&gt;It will run only if your airframe armed.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation type="unfinished">&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;Ubuntu&apos;; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
@ -4220,34 +4233,32 @@ p, li { white-space: pre-wrap; }
<source>Save</source>
<translation>Enregistrer</translation>
</message>
<message>
<location/>
<source>Vehicle name</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>Enter name of vehicle. Max 20 characters.</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;Sans Serif&apos;; font-size:9pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;Ubuntu&apos;; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt;
&lt;tr&gt;
&lt;td style=&quot;border: none;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Ubuntu&apos;; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD REQUIRES CAUTION&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;Ubuntu&apos;; font-size:11pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Ubuntu&apos;; font-size:11pt;&quot;&gt;&lt;br /&gt;&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Ubuntu&apos;; font-size:11pt;&quot;&gt;&lt;br /&gt;&lt;/span&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD REQUIRES CAUTION&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Lucida Grande&apos;; font-size:13pt;&quot;&gt;Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Lucida Grande&apos;; font-size:13pt;&quot;&gt;Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.&lt;/span&gt;&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation type="unfinished">&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt;
&lt;tr&gt;
&lt;td style=&quot;border: none;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Ubuntu&apos;; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;LA MISE EN PLACE DE FEED FORWARD EXIGE DE LA PRUDENCE&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;Ubuntu&apos;; font-size:11pt;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Ubuntu&apos;; font-size:11pt;&quot;&gt;&lt;br /&gt;&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Ubuntu&apos;; font-size:11pt;&quot;&gt;&lt;br /&gt;&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Lucida Grande&apos;; font-size:13pt;&quot;&gt;Attention : L&apos;activation du réglage Feed Forward lancera tous les moteurs à mi-gaz, vous avez é averti !&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;Lucida Grande&apos;; font-size:13pt;&quot;&gt;Dans un premier temps retirez vos hélices, puis pour affiner assurez-vous que le châssis est maintenu bien en place. Portez des lunettes et protégez-vous le visage et le corps.&lt;/span&gt;&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</translation>
<translation type="unfinished"></translation>
</message>
</context>
<context>
@ -4276,7 +4287,7 @@ p, li { white-space: pre-wrap; }
<location/>
<source>Arm switch (Accessory0)</source>
<translatorcomment>Abbrégé ?</translatorcomment>
<translation type="unfinished">Inter Arm. (Accessory0)</translation>
<translation>Inter Arm. (Accessory0)</translation>
</message>
</context>
<context>
@ -4455,22 +4466,22 @@ p, li { white-space: pre-wrap; }
<message>
<location line="+0"/>
<source> Some of the configured features might not be supported by your version of the plugin. You might want to upgrade the plugin.</source>
<translation type="unfinished"> Certaines des fonctionnalités configurées pourraient ne pas être prises en charge par votre version du plugin. Vous pourriez peut-être mettre à jour le plugin.</translation>
<translation> Certaines des fonctionnalités configurées pourraient ne pas être prises en charge par votre version du plugin. Vous pourriez peut-être mettre à jour le plugin.</translation>
</message>
<message>
<location line="+6"/>
<source> Some configuration is missing in the imported config and will be replaced by default settings.</source>
<translation type="unfinished"> Certains paramètres sont manquants dans la configuration importée et seront remplacés par les paramètres par défaut.</translation>
<translation> Certains paramètres sont manquants dans la configuration importée et seront remplacés par les paramètres par défaut.</translation>
</message>
<message>
<location line="+6"/>
<source> Major features can&apos;t be imported by your version of the plugin. You should upgrade the plugin to import these settings.</source>
<translation type="unfinished"> Des paramètres primordiaux ne peuvent être importés par votre version du plugin. Vous devriez mettre à jour le plugin pour importer ces paramètres.</translation>
<translation> Des paramètres primordiaux ne peuvent être importés par votre version du plugin. Vous devriez mettre à jour le plugin pour importer ces paramètres.</translation>
</message>
<message>
<location line="+6"/>
<source> The imported settings are not compatible with this plugin and won&apos;t be imported!</source>
<translation type="unfinished"> Les paramètres importés ne sont pas compatibles avec ce plugin et ne seront pas importés !</translation>
<translation> Les paramètres importés ne sont pas compatibles avec ce plugin et ne seront pas importés !</translation>
</message>
<message>
<location line="-12"/>
@ -4485,7 +4496,7 @@ p, li { white-space: pre-wrap; }
<message>
<location line="+13"/>
<source> Unknown compatibility level: </source>
<translation type="unfinished"> Niveau de compatibilité inconnu : </translation>
<translation> Niveau de compatibilité inconnu : </translation>
</message>
</context>
<context>
@ -5850,32 +5861,32 @@ accéléromètres dans la mémoire Flash de la carte.</translation>
<message>
<location/>
<source>Angle W</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Angle X</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Angle Y</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Angle Z</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Correction Angle</source>
<translation type="unfinished">Angle Correction</translation>
<translation>Angle Correction</translation>
</message>
<message>
<location/>
<source>CCPM Options</source>
<translation type="unfinished">Options CCPM</translation>
<translation>Options CCPM</translation>
</message>
<message>
<location/>
@ -5890,17 +5901,17 @@ accéléromètres dans la mémoire Flash de la carte.</translation>
<message>
<location/>
<source>Link Cyclic/Collective</source>
<translation type="unfinished">Lier Cyclique/Collectif</translation>
<translation>Lier Cyclique/Collectif</translation>
</message>
<message>
<location/>
<source>Swashplate Layout</source>
<translation type="unfinished">Agencement Plateau Cyclique</translation>
<translation>Agencement Plateau Cyclique</translation>
</message>
<message>
<location/>
<source>REVO</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -5915,17 +5926,17 @@ accéléromètres dans la mémoire Flash de la carte.</translation>
<message>
<location/>
<source>CCPM</source>
<translation type="unfinished">CCPM</translation>
<translation>CCPM</translation>
</message>
<message>
<location/>
<source>Collective</source>
<translation type="unfinished">Collectif</translation>
<translation>Collectif</translation>
</message>
<message>
<location/>
<source>Cyclic</source>
<translation type="unfinished">Cyclique</translation>
<translation>Cyclique</translation>
</message>
<message>
<location/>
@ -5940,12 +5951,12 @@ accéléromètres dans la mémoire Flash de la carte.</translation>
<message>
<location/>
<source>Swashplate Levelling</source>
<translation type="unfinished">Niveau Plateau Cyclique</translation>
<translation>Niveau Plateau Cyclique</translation>
</message>
<message>
<location/>
<source>Commands</source>
<translation type="unfinished">Commandes</translation>
<translation>Commandes</translation>
</message>
<message>
<location/>
@ -6000,7 +6011,7 @@ accéléromètres dans la mémoire Flash de la carte.</translation>
<message>
<location/>
<source>Swashplate Adjustment</source>
<translation type="unfinished">Réglage Plateau Cyclique</translation>
<translation>Réglage Plateau Cyclique</translation>
</message>
<message>
<location/>
@ -6333,12 +6344,6 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
<translatorcomment>Typo Need translation in selection list above</translatorcomment>
<translation>Stabilisé 3</translation>
</message>
<message>
<location/>
<source>PID Bank</source>
<translatorcomment>Typo Need translation for &quot;Bank1&quot; &quot;Bank 2&quot;... in selection list below</translatorcomment>
<translation type="unfinished">Banque PID</translation>
</message>
<message>
<location/>
<source>Flight Mode Switch Positions</source>
@ -6433,7 +6438,7 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
<message>
<location/>
<source>Thrust</source>
<translation type="unfinished">Poussée</translation>
<translation>Poussée</translation>
</message>
<message>
<location/>
@ -6453,7 +6458,12 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Avoid &amp;quot;Manual&amp;quot; for multirotors! Never select &amp;quot;Altitude&amp;quot;, &amp;quot;VelocityControl&amp;quot; or &amp;quot;CruiseControl&amp;quot; on a fixed wing!&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation type="unfinished">&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Éviter &amp;quot;Manuel&amp;quot; pour les multirotors ! Ne jamais sélectionner &amp;quot;Altitude&amp;quot;, &amp;quot;VelocityControl&amp;quot; ou &amp;quot;CruiseControl&amp;quot; sur une aile volante !&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Éviter &amp;quot;Manuel&amp;quot; pour les multirotors ! Ne jamais sélectionner &amp;quot;Altitude&amp;quot;, &amp;quot;VelocityControl&amp;quot; ou &amp;quot;CruiseControl&amp;quot; sur une aile volante !&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Settings Bank</source>
<translation>Banque Paramètres</translation>
</message>
</context>
<context>
@ -6528,7 +6538,7 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
<location/>
<source>Linear</source>
<translatorcomment>pas toucher !</translatorcomment>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -6603,13 +6613,6 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
<source>Update rate:</source>
<translation>Fréquence de rafraîchissement :</translation>
</message>
<message>
<location/>
<source>Setup &quot;TurboPWM&quot; here: usual value is 400 Hz for multirotor airframes.
Leave at 50Hz for fixed wing.</source>
<translation>Configurer ici &quot;TurboPWM&quot; : valeur classique pour les multirotors.
Laisser à 50Hz pour une aile volante.</translation>
</message>
<message>
<location/>
<source>50</source>
@ -6703,6 +6706,17 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
<source>Live Testing</source>
<translation>Test en Temps Réel</translation>
</message>
<message>
<location/>
<source>Setup &quot;RapidESC&quot; here: usual value is 500 Hz for multirotor airframes.
</source>
<translation>Configurer ici &quot;TurboPWM&quot; : 500Hz est une valeur classique pour les multirotors.</translation>
</message>
<message>
<location/>
<source>500</source>
<translation>500</translation>
</message>
</context>
<context>
<name>outputChannelForm</name>
@ -7072,17 +7086,17 @@ Une valeur de 0.00 désactive le filtre.</translation>
<message>
<location/>
<source>&lt;temperature&gt;</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>&lt;gradient&gt;</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>&lt;range&gt;</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -7478,22 +7492,12 @@ value as the Kp.</source>
<source>Expert</source>
<translation>Expert</translation>
</message>
<message>
<location/>
<source>Weak Leveling / Axis Lock</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>buttongroup:10</source>
<translatorcomment>pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Weak Leveling Kp </source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>Weak Leveling Rate </source>
@ -7533,34 +7537,6 @@ value as the Kp.</source>
<translatorcomment>pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Integral Limits</source>
<translation>Limites Intégrale</translation>
</message>
<message>
<location/>
<source>buttongroup:13</source>
<translation></translation>
</message>
<message>
<location/>
<source>element:ILimit</source>
<translatorcomment>pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>ILimit Attitude</source>
<translatorcomment>pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>ILimit Rate</source>
<translatorcomment>pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Sensor Tuning</source>
@ -7590,27 +7566,12 @@ value as the Kp.</source>
<translatorcomment>pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>GyroTau</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>AccelKp</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>fieldname:GyroTau</source>
<translatorcomment>pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>AccelKi</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>fieldname:AccelKi</source>
@ -7688,12 +7649,6 @@ Useful if you have accidentally changed some settings.</source>
<source>Responsiveness</source>
<translation>Réactivité</translation>
</message>
<message>
<location/>
<source>QGroupBox{border: 0px;}</source>
<translatorcomment>Pas toucher</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>This thing really can preform, it is a lot more responsive this way</source>
@ -7724,26 +7679,11 @@ Useful if you have accidentally changed some settings.</source>
<source>Insane</source>
<translation>Démentielle</translation>
</message>
<message>
<location/>
<source>Attitude mode</source>
<translation>Mode Attitude</translation>
</message>
<message>
<location/>
<source>Rate mode</source>
<translation>Mode Rate</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;The Attitude Mode slider can be adjusted to value ranges whose responsivness is represented by the Moderate / Snappy / Insane bar&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Le curseur Mode Attitude peut être ajusté dans une plage de valeurs dont la réactivité est représentée par les zones Modérée / Dynamique / Démentielle&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Rate mode yaw</source>
<translation>Mode Rate yaw</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Link roll &amp;amp; pitch sliders to move together, thus giving same value for both roll &amp;amp; pitch when setting up a symetrical vehicle that requires both to be the same&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
@ -7785,16 +7725,6 @@ Useful if you have accidentally changed some settings.</source>
<source>Update flight controller in real time</source>
<translation>Mettre à jour le contrôleur de vol en temps réel</translation>
</message>
<message>
<location/>
<source>Attitude mode response (deg)</source>
<translation>Réponse mode Attitude (deg)</translation>
</message>
<message>
<location/>
<source>Rate mode response (deg/s)</source>
<translation>Vitesse mode Rate (deg/s)</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Link roll &amp;amp; pitch values together, thus giving the same value for each when setting up a symetrical vehicle that requires both to be the same.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
@ -7887,11 +7817,6 @@ Useful if you have accidentally changed some settings.</source>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;The Rate mode Yaw slider can be adjusted to value ranges whose responsiveness is represented by the Moderate / Snappy / Insane bar&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Le curseur Mode Rate yaw peut être ajusté dans une plage de valeurs dont la réactivité est représentée par les zones Modérée / Dynamique / Démentielle&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This adjusts how much stability your vehicle will have when flying tilted (ie forward flight) in Rate mode. A good starting point for Integral is the same as Proportional&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci ajuste le niveau de stabilité que votre véhicule aura en vol incliné (ex. vol en avançant) en mode Rate. Un bon point de départ pour l&apos;Intégrale est la même valeur qu&apos;en Proportionnel&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
@ -7913,11 +7838,6 @@ Useful if you have accidentally changed some settings.</source>
makes the control output respond faster with fast stick movements or external disturbance like wind gusts. It also acts like a dampener, thus allowing higher KP settings. Only affects Rate mode.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci rend la réponse du contrôle de sortie plus rapide lors de mouvements de manches rapides ou de perturbations externes comme des rafales de vent. Il agit également comme un amortisseur, permettant ainsi les paramètres Kp plus élevés. Ne concerne que le mode Rate.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This adjusts how much stability your vehicle will have when flying tilted (ie forward flight) in Rate mode. A good starting point for Integral is the same as Proportional.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci ajuste le niveau de stabilité que votre véhicule aura en vol incliné (ex. vol en avançant) en mode Rate. Un bon point de départ pour l&apos;Intégrale est la même valeur qu&apos;en Proportionnel&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This makes the control output respond faster with fast stick movements or external disturbance like wind gusts. It also acts like a dampener, thus allowing higher KP settings. Only affects Rate mode.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
@ -7933,29 +7853,16 @@ Useful if you have accidentally changed some settings.</source>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This adjusts how much stability your vehicle will have when flying tilted (ie forward flight) in Attitude Mode. Adding Ki in Attitude when Ki is present in Rate is not recommended.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci ajuste le niveau de stabilité que votre véhicule aura en vol incliné (ex. vol en avançant) en mode Attitude. Ajouter une valeur d&apos;intégrale en mode Attitude lorsque une intégrale est présente en mode Rate n&apos;est pas recommandé.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This sets the maximum value of the integral (KP) that is used in Rate mode.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation type="vanished">&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci limite la valeur maximale de l&apos;intégrale (KP) qui est utilisée en mode Rate.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This sets the maximum value of the integral (KP) that is used in AttitudeMode.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation type="vanished">&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci limite la valeur maximale de l&apos;intégrale (KP) qui est utilisée en mode Attitude.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>objname:StabilizationSettingsBankX</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Misc</source>
<translation>Divers</translation>
</message>
<message>
<location/>
<source>Rattitude</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -8011,12 +7918,12 @@ Useful if you have accidentally changed some settings.</source>
<message>
<location/>
<source>Control Coefficients</source>
<translation type="unfinished">Coefficients de Contrôle</translation>
<translation>Coefficients de Contrôle</translation>
</message>
<message>
<location/>
<source>Cruise Control</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -8099,11 +8006,6 @@ Useful if you have accidentally changed some settings.</source>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;How fast the vehicle should adjust its neutral throttle estimation. Altitude assumes that when engaged the throttle is in the range required to hover. If the throttle is a lot higher or lower, it needs to adjust this &amp;quot;throttle trim&amp;quot; Higher values make it do this adjustment faster, but this could lead to ugly oscillations. Leave at default unless you know what you are doing.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Détermine la vitesse à laquelle le véhicule doit ajuster son estimation de gaz au neutre. Le Maintien d&apos;Altitude suppose que lorsque il est activé, il est la plage nécessaire pour se maintenir en l&apos;air. Si les gaz est beaucoup plus élevé ou plus bas, il faut ajuster ce &quot;trim&quot;. Des valeurs plus élevées peuvent lui permettre de faire cet ajustement plus rapidement mais cela pourrait conduire à des oscillations. A laisser par défaut, à moins de savoir ce que vous faites.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Max rate limit (all modes) (deg/s)</source>
<translation>Limitation Rate max (tous modes) (deg/s)</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Percentage of full stick where the transition from Attitude to Rate occurs. This transition always occurs when the aircraft is exactly inverted (bank angle 180 degrees). Small values are dangerous because they cause flips at small stick angles. Values significantly over 100 act like attitude mode and can never flip.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
@ -8115,11 +8017,6 @@ Useful if you have accidentally changed some settings.</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>ModeTransition</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;CP helis can set this to Reversed to automatically reverse the direction of thrust when inverted. Fixed pitch copters, including multicopters, should leave this set at Unreversed. Unreversed direction with Boosted power may be dangerous because it adds power and the thrust direction moves the aircraft towards the ground.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
@ -8234,13 +8131,236 @@ Useful if you have accidentally changed some settings.</source>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This sets the maximum value of the integral (KI) that is used in Rate mode.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci limite la valeur maximale de l&apos;intégrale (KI) qui est utilisée en mode Rate.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
<source>Weak Leveling</source>
<translation></translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This sets the maximum value of the integral (KI) that is used in AttitudeMode.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci limite la valeur maximale de l&apos;intégrale (KI) qui est utilisée en mode Attitude.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
<source>buttongroup:25</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Weak Leveling Gain </source>
<translation>Gain Weak Leveling </translation>
</message>
<message>
<location/>
<source>Axis Lock</source>
<translation></translation>
</message>
<message>
<location/>
<source>buttongroup:31</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Mode Transition</source>
<translation>Changement Mode</translation>
</message>
<message>
<location/>
<source>Accel I</source>
<translation>I Accel</translation>
</message>
<message>
<location/>
<source>Gyro Noise Filtering</source>
<translation>Filtrage Bruit Gyro</translation>
</message>
<message>
<location/>
<source>Accel P</source>
<translation>P Accel</translation>
</message>
<message>
<location/>
<source>Thrust PID Scaling</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>fieldname:EnableThrustPIDScaling</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Source</source>
<translation>Source</translation>
</message>
<message>
<location/>
<source>fieldname:ThrustPIDScaleSource</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Targets</source>
<translation>Cible(s)</translation>
</message>
<message>
<location/>
<source>fieldname:ThrustPIDScaleTarget</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Axis</source>
<translation>Axe(s)</translation>
</message>
<message>
<location/>
<source>fieldname:ThrustPIDScaleAxes</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Rate mode
response (deg/s)</source>
<translation>Réponse mode Rate
(en degrés/seconde)</translation>
</message>
<message>
<location/>
<source>Attitude mode
response (deg)</source>
<translation>Réponse mode Attitude
(en degrés)</translation>
</message>
<message>
<location/>
<source>Max rate limit
(all modes) (deg/s)</source>
<translation>Limitation Vitesse Max
(tous modes, en degrés/seconde)</translation>
</message>
<message>
<location/>
<source>Enable TPS</source>
<translation type="unfinished">Activer TPS</translation>
</message>
<message>
<location/>
<source>Acro+</source>
<translation></translation>
</message>
<message>
<location/>
<source>buttongroup:77</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;The Acro + slider can be adjusted to change the amount of manual control blending.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Le curseur Acro+ peut être ajusté pour modifier la quantité de mixage du contrôle manuel.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>fieldname:AcroInsanityFactor</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>Factor</source>
<translation>Facteur</translation>
</message>
<message>
<location/>
<source>Expo</source>
<translation></translation>
</message>
<message>
<location/>
<source>fieldname:StickExpo</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>buttongroup:66</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This graph shows the Expo curves for all axis. The color of the curves corresponds with the colors of the slider labels below.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ce graphique affiche les courbes d&apos;Expo pour tous les axes. Les couleurs des courbes correspondent aux couleurs des axes ci-dessous.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;The Roll Expo slider can be adjusted to change the amount of Expo to use on Roll axis.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Le curseur Expo Roll peut être ajusté pour modifier la quantité d&apos;exponentiel à utiliser sur la commande de Roll.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;The Yaw Expo slider can be adjusted to change the amount of Expo to use on Yaw axis.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Le curseur Expo Yaw peut être ajusté pour modifier la quantité d&apos;exponentiel à utiliser sur la commande de Yaw.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;The Pitch Expo slider can be adjusted to change the amount of Expo to use on Pitch axis.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Le curseur Expo Pitch peut être ajusté pour modifier la quantité d&apos;exponentiel à utiliser sur la commande de Pitch.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Rate</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>Rate yaw</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>Attitude</source>
<translation>Attitude</translation>
</message>
<message>
<location/>
<source>Pirouette Compensation</source>
<translation>Compensation Pirouette</translation>
</message>
<message>
<location/>
<source>Enable pirouette compensation</source>
<translation>Activer compensation pirouette</translation>
</message>
<message>
<location/>
<source>fieldname:EnablePiroComp</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>buttongroup:55</source>
<translatorcomment>Pas toucher !</translatorcomment>
<translation></translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This adjusts how much stability your vehicle will have when flying tilted (ie forward flight) in Rate mode. A good starting point for Integral is double the Proportional value&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci ajuste le niveau de stabilité que votre véhicule aura en vol incliné (ex. vol en avançant) en mode Rate. Un bon point de départ pour l&apos;Intégrale est le double de la valeur Proportionnel&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This adjusts how much stability your vehicle will have when flying tilted (ie forward flight) in Rate mode. A good starting point for Integral is double the Proportional value&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci ajuste le niveau de stabilité que votre véhicule aura en vol incliné (ex. vol en avançant) en mode Rate. Un bon point de départ pour l&apos;Intégrale est le double de la valeur Proportionnel&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This adjusts how much yaw stability your vehicle will have in Rate mode. A good starting point for Integral is double the Proportional value&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Ceci ajuste le niveau de stabilité en lacet de votre véhicule en mode Rate. Un bon point de départ pour l&apos;Intégrale est le double de la valeur Proportionnel&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
</context>
<context>
@ -8949,12 +9069,12 @@ les données en cache</translation>
<translation>Fermer</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/connectiondiagram.cpp" line="+38"/>
<location filename="../../../src/plugins/setupwizard/connectiondiagram.cpp" line="+41"/>
<source>Connection Diagram</source>
<translation>Diagramme de Connexion</translation>
</message>
<message>
<location line="+156"/>
<location line="+202"/>
<source>Save File</source>
<translation>Enregistrer Fichier</translation>
</message>
@ -8971,35 +9091,6 @@ les données en cache</translation>
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Firmware Update Wizard&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;It is necessary that your firmware and ground control software are the same version.&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;To update your firmware to the correct version now:&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt; - Unplug all batteries and USB from OpenPilot&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt; - Ensure your board is powered down &amp;amp; no LED&apos;s are active.&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;When you are ready you can start the upgrade below by pushing the button and follow the onscreen prompts, it is critical that nothing disturbs the board while the firmware is being written.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Assistant de Mise à Jour Firmware&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Il est nécessaire d&apos;avoir la même version de firmware et de logiciel de station au sol (GCS).&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Pour mettre à jour la version correcte de firmware maintenant :&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt; - Débrancher toutes les batteries et le cordon USB de la carte,&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt; - Vérifier que la carte n&apos;est pas alimentée et qu&apos;aucune LED n&apos;est allumée.&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Lorsque vous êtes prêt vous pouvez démarrer la mise à jour en appuyant sur le bouton ci-dessous et suivre les instructions à l&apos;écran. Il est essentiel que rien ne vienne perturber le fonctionnement de la carte tant que le firmware est en cours d&apos;écriture.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Upgrade now</source>
@ -9060,6 +9151,35 @@ p, li { white-space: pre-wrap; }
<source>Something went wrong, you will have to manually upgrade the board using the uploader plugin.</source>
<translation>Quelque chose s&apos;est mal passé, vous devrez mettre à jour manuellement la carte en utilisant le plugin uploader.</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/autoupdatepage.ui"/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Firmware Update&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;It is necessary that your firmware and ground control software are the same version.&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;To update your firmware to the correct version now:&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt; - Unplug all batteries and USB from OpenPilot&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt; - Ensure your board is powered down &amp;amp; no LED&apos;s are active.&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;When you are ready you can start the upgrade below by pushing the button and follow the onscreen prompts, it is critical that nothing disturbs the board while the firmware is being written.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Mise à jour Firmware&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Il est nécessaire que la version de firmware et la version du logiciel GCS soient identiques.&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Pour mettre à jour votre firmware avec la bonne version :&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt; - Débrancher toutes les batteries et le port USB de la carte OpenPilot,&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt; - Vérifier que la carte n&apos;est pas alimentée et qu&apos;aucune LED ne soit alumée.&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Lorsque vous êtes prêt pour démarrer la mise à jour, appuyez sur le bouton et suivez les instructions à l&apos;écran. Il est essentiel que rien ne vienne perturber le processus durant l&apos;écriture du firmware.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
</context>
<context>
<name>ControllerPage</name>
@ -9068,32 +9188,6 @@ p, li { white-space: pre-wrap; }
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot board identification&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To continue, the wizard needs to determine the configuration required for the type of OpenPilot controller you have. When connected, the wizard will attempt to automatically detect the type of board.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;If the board is already connected and successfully detected, the board type will already be displayed. You can &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;Disconnect&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt; and select another device if you need to detect another board.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;If your board is not connected, please connect the board to a USB port on your computer and select the device from the list below. Then press &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;Connect&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translatorcomment>&apos;moyen de connexion&apos;, à affiner...</translatorcomment>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Identification de la carte OpenPilot&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Pour continuer, l&apos;assistant de configuration doit déterminer la configuration nécessaire au type de carte dont vous disposez. Lorsque vous la branchez, l&apos;assistant essaye de détecter automatiquement le type de carte.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Si la carte est déjà branchée et correctement détectée, le type de carte sera déjà affiché. Vous pouvez &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;Déconnecter&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt; et sélectionner un autre moyen de connexion si vous avez besoin de détecter une autre carte.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Si votre carte n&apos;est pas connectée, branchez- sur un port USB de votre ordinateur et sélectionnez le moyen de connexion dans la liste ci-dessous. Appuyez ensuite sur &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;Connecter&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Connection device:</source>
@ -9106,12 +9200,12 @@ p, li { white-space: pre-wrap; }
</message>
<message>
<location/>
<location filename="../../../src/plugins/setupwizard/pages/controllerpage.cpp" line="+194"/>
<location filename="../../../src/plugins/setupwizard/pages/controllerpage.cpp" line="+198"/>
<source>Connect</source>
<translation>Connecter</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/controllerpage.cpp" line="-69"/>
<location filename="../../../src/plugins/setupwizard/pages/controllerpage.cpp" line="-70"/>
<source>&lt;Unknown&gt;</source>
<translation>&lt;Inconnu&gt;</translation>
</message>
@ -9135,33 +9229,87 @@ p, li { white-space: pre-wrap; }
<source>OpenPilot OPLink Radio Modem</source>
<translation></translation>
</message>
<message>
<location line="+1"/>
<source>OpenPilot DiscoveryF4</source>
<translation></translation>
</message>
<message>
<location line="+50"/>
<source>Disconnect</source>
<translation>Déconnecter</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/controllerpage.ui"/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot Board Identification&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To continue, the wizard needs to determine the configuration required for the type of OpenPilot controller you have. When connected, the wizard will attempt to automatically detect the type of board.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;If the board is already connected and successfully detected, the board type will already be displayed. You can &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;Disconnect&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt; and select another device if you need to detect another board.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;If your board is not connected, please connect the board to a USB port on your computer and select the device from the list below. Then press &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;Connect&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Identification de la Carte OpenPilot&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Avant de continuer l&apos;assistant doit déterminer la configuration nécessaire à la carte OpenPilot que vous possédez. Lors de la connection, l&apos;assistant va essayer de déterminer automatiquement le type de carte.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Si la carte est déjà connectée et détectée avec succès, le type de carte est déjà affiché. Vous pouvez appuyer sur &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;Déconnecter&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt; et sélectionner une autre carte si besoin.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Si votre carte n&apos;est pas connectée, veuillez brancher cotre carte sur le port USB de votre ordinateur e tla sélectionner dans la liste ci-dessous. Appuyez ensuite sur &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;Connecter&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
</context>
<context>
<name>FixedWingPage</name>
<message>
<location filename="../../../src/plugins/setupwizard/pages/fixedwingpage.ui"/>
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
<location filename="../../../src/plugins/setupwizard/pages/fixedwingpage.cpp" line="+51"/>
<source>OpenPilot Fixed-wing Configuration</source>
<translation>Configuration OpenPilot - Voilure fixe</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;The Fixed Wing section of the OpenPilot Setup Wizard is not yet implemented&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;La partie Voilure Fixe de l&apos;Assistant de Configuration OpenPilot n&apos;est pas encore implémentée.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
<location line="+1"/>
<source>This part of the wizard will set up the OpenPilot controller for use with a fixed-wing flying aircraft utilizing servos. The wizard supports the most common types of fixed-wing aircraft, other variants of fixed-wing aircraft can be configured by using custom configuration options in the Configuration plugin in the GCS.
Please select the type of fixed-wing you want to create a configuration for below:</source>
<translation>Cette partie de l&apos;assistant va configurer le contrôleur OpenPilot pour utiliser une voilure fixe avec des servos. L&apos;assistant supporte les types de voilure fixe les plus communs, d&apos;autres variantes de voilures fixes peuvent être configurées dans l&apos;onglet &quot;Véhicule&quot; &gt; &quot;Personnalisé&quot; du plugin de configuration de GCS.
Veuillez sélectionner la configuration de voilure fixe désirée ci-dessous :</translation>
</message>
<message>
<location line="+5"/>
<source>Aileron Dual Servos</source>
<translation>Aileron Deux Servos</translation>
</message>
<message>
<location line="+1"/>
<source>This setup expects a traditional airframe using two independent aileron servos on their own channel (not connected by Y adapter) plus an elevator and a rudder.</source>
<translation>Cette configuration concerne une plateforme volante classique utilisant deux servos d&apos;ailerons indépendants ayant leur propre branchement (pas connectés avec un adaptateur en Y) plus un volet de profondeur et une dérive.</translation>
</message>
<message>
<location line="+5"/>
<source>Aileron Single Servo</source>
<translation>Aileron Servo Unique</translation>
</message>
<message>
<location line="+1"/>
<source>This setup expects a traditional airframe using a single aileron servo or two servos connected by a Y adapter plus an elevator and a rudder.</source>
<translation>Cette configuration concerne une plateforme volante classique utilisant un servo d&apos;ailerons unique ou deux servos branchés avec un cordon Y plus un volet de profondeur et une dérive.</translation>
</message>
<message>
<location line="+5"/>
<source>Elevon</source>
<translation>Elevon</translation>
</message>
<message>
<location line="+1"/>
<source>This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet supported. Setup should include only two elevons, and should explicitly not include a rudder.</source>
<translation>Cette configuration concerne les ailes volantes, la dérive n&apos;est pas encore supportée actuellement. La configuration s&apos;applique à deux servos d&apos;élevons, sans dérive.</translation>
</message>
</context>
<context>
@ -9194,27 +9342,6 @@ p, li { white-space: pre-wrap; }
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot basic input signal configuration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The OpenPilot controller supports many different types of input signals. Please select the type of input that matches your receiver configuration. If you are unsure, just leave the default option selected and continue the wizard.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Some input options require the OpenPilot controller to be rebooted before the changes can take place. If an option that requires a reboot is selected, you will be instructed to do so on the next page of this wizard.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Configuration de base du signal d&apos;entrée&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;La carte contrôleur OpenPilot supporte plusieurs types de signaux d&apos;entrée. Veuillez sélectionner le type d&apos;entrée qui correspond à votre configuration de récepteur. Si vous n&apos;êtes pas certain, laissez juste l&apos;option par défaut sélectionnée et continuez l&apos;assistant.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Quelques options requièrent un redémarrage du contrôleur OpenPilot avant que les changements ne prennent effet. Si une option demandant un redémarrage est sélectionnée, cela vous sera demandé de le faire dans la prochaine page de l&apos;assistant.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>PWM - One cable per channel</source>
@ -9240,11 +9367,6 @@ p, li { white-space: pre-wrap; }
<source>Futaba S-BUS</source>
<translation></translation>
</message>
<message>
<location/>
<source>Futaba</source>
<translation></translation>
</message>
<message>
<location/>
<source>Spektrum Satellite</source>
@ -9252,24 +9374,40 @@ p, li { white-space: pre-wrap; }
</message>
<message>
<location/>
<source>Spektrum</source>
<source>S.Bus</source>
<translation></translation>
</message>
<message>
<location/>
<source>DSM Sat</source>
<translation></translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot Input Signal Configuration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The OpenPilot controller supports many different types of input signals. Please select the type of input that matches your receiver configuration. If you are unsure, just leave the default option selected and continue the wizard.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Some input options require the OpenPilot controller to be rebooted before the changes can take place. If an option that requires a reboot is selected, you will be instructed to do so on the next page of this wizard.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Configuration OpenPilot des Signaux d&apos;Entrée&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Le contrôleur OpenPilot supporte plusieurs types de signaux d&apos;entrée. Veuillez sélectionner le type d&apos;entrée qui correspond à votre configuration de récepteur. Si vous avez un doute, laissez l&apos;option sélectionnée par défaut et continuez l&apos;assistant.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Certaines configurations demandent un redémarrage du contrôleur OpenPilot pour que les changements soient effectifs. Vous serrez informé si un redémarrage est nécessaire à l&apos;écran suivant de cet assistant.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
</context>
<context>
<name>MultiPage</name>
<message>
<location filename="../../../src/plugins/setupwizard/pages/multipage.ui"/>
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>Multirotor type:</source>
<translation>Type de multirotor :</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/multipage.cpp" line="+85"/>
<location filename="../../../src/plugins/setupwizard/pages/multipage.cpp" line="+58"/>
<source>Tricopter</source>
<translation>Tricoptère</translation>
</message>
@ -9279,7 +9417,7 @@ p, li { white-space: pre-wrap; }
<translation>Le tricoptère utilise trois moteurs et un servo. Le servo est utilisé pour permettre au moteur arrière d&apos;agir sur le Yaw (Lacet). Les moteurs de devant tournent dans des sens opposés. Le tricoptère est connu pour son mouvement de balayage en lacet et il est très adapté pour le FPV car les moteurs de devant sont écartés.</translation>
</message>
<message>
<location line="+4"/>
<location line="+6"/>
<source>Quadcopter X</source>
<translation>Quadricoptère X</translation>
</message>
@ -9289,7 +9427,7 @@ p, li { white-space: pre-wrap; }
<translation>Le Quadricoptère X utilise quatre moteurs et c&apos;est la configuration la plus commune en multirotor. Deux des moteurs tournent dans le sens horaire et les deux dans le sens antihoraire. Les moteurs situés en diagonale tournent dans le même sens. Cette configuration est idéale pour le vol sportif et couramment utilisé pour des plates-formes FPV.</translation>
</message>
<message>
<location line="+4"/>
<location line="+6"/>
<source>Quadcopter +</source>
<translation>Quadricoptère +</translation>
</message>
@ -9299,49 +9437,68 @@ p, li { white-space: pre-wrap; }
<translation>Le Quadricoptère (+) utilise quatre moteurs et il est similaire au Quadricoptère X mais la direction de déplacement est décalée de 45 degrés. Les moteurs avant et arrière tournent dans le sens horaire et les moteurs gauche et droit tournent dans le sens antihoraire. Cette configuration a é l&apos;une des premières à être utilisée et est encore utilisée pour le vol sportif. Cette agencement n&apos;est pas bien adapté pour que FPV car le moteur de devant a tendance à être dans le champ de vision de la caméra.</translation>
</message>
<message>
<location line="+5"/>
<location line="+7"/>
<source>Quadcopter H</source>
<translation>Quadricoptère H</translation>
</message>
<message>
<location line="+1"/>
<source>Quadcopter H, Blackout miniH</source>
<translation>Quadricoptère H, blackout miniH</translation>
</message>
<message>
<location line="+4"/>
<source>Hexacopter</source>
<translation>Hexacoptère</translation>
</message>
<message>
<location line="+8"/>
<location line="+1"/>
<source>A multirotor with six motors, one motor in front.</source>
<translation>Un multirotor avec six moteurs, un moteur sur l&apos;avant.</translation>
</message>
<message>
<location line="+5"/>
<source>A multirotor with six motors, two motors in front.</source>
<translation>Un multirotor avec six moteurs, deux moteurs sur l&apos;avant.</translation>
</message>
<message>
<location line="+5"/>
<source>A multirotor with six motors in two rows.</source>
<translation>Un multirotor avec six moteurs alignés sur deux lignes.</translation>
</message>
<message>
<location line="+4"/>
<source>Hexacopter Coax (Y6)</source>
<translation>Hexacoptère Coax (Y6)</translation>
</message>
<message>
<location line="-7"/>
<location line="+1"/>
<source>A multirotor with six motors mounted in a coaxial fashion.</source>
<translation>Un multirotor avec six moteurs montés de manière coaxiale.</translation>
</message>
<message>
<location line="-11"/>
<source>Hexacopter X</source>
<translation>Hexacoptère X</translation>
</message>
<message>
<location line="+2"/>
<location line="+1"/>
<source>Hexacopter H</source>
<translation>Hexacoptère H</translation>
<location line="-38"/>
<source>OpenPilot Multirotor Configuration</source>
<translation>Configuration Multirotor OpenPilot</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/multipage.ui"/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot Multirotor Configuration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;This part of the wizard will set up the OpenPilot controller for use with a flying platform utilizing multiple rotors. The wizard supports the most common types of multirotors. Other variants of multirotors can be configured by using custom configuration options in the Configuration plugin in the GCS.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Please select the type of multirotor you want to create a configuration for below:&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Configuration Multirotor OpenPilot&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Cette partie de l&apos;assistant configure la carte OpenPilot avec une plate-forme de vol utilisant plusieurs rotors. L&apos;assistant reconnaît la plupart des types de multirotors. Les autres variantes de multirotors peuvent-être configurées en utilisant les options de configuration avancées dans l&apos;onglet Configuration de GCS.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Veuillez choisir ci-dessous le type de multirotor souhaité pour créer une configuration :&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
<location line="+1"/>
<source>This part of the wizard will set up the OpenPilot controller for use with a flying platform utilizing multiple rotors. The wizard supports the most common types of multirotors. Other variants of multirotors can be configured by using custom configuration options in the Configuration plugin in the GCS.
Please select the type of multirotor you want to create a configuration for below:</source>
<translation>Cette partie de l&apos;assistant va permettre le configuration du contrôleur OpenPilot pour fonctionner avec des plateformes volantes utilisant plusieurs moteurs. L&apos;assistant supporte les types de configurations les plus courants. D&apos;autres variantes de multirotors peuvent être configurées dans l&apos;onglet &quot;Véhicule&quot; &gt; &quot;Personnalisé&quot; du plugin de configuration de GCS.
Veuillez sélectionner le type de multirotor désiré pour la configuration ci-dessous :</translation>
</message>
<message>
<location line="+42"/>
<source>Hexacopter H</source>
<translation>Hexacoptère H</translation>
</message>
</context>
<context>
@ -9402,38 +9559,19 @@ p, li { white-space: pre-wrap; }
</message>
<message>
<location/>
<location filename="../../../src/plugins/setupwizard/pages/outputcalibrationpage.cpp" line="+267"/>
<location line="+76"/>
<location line="+28"/>
<location line="+19"/>
<location filename="../../../src/plugins/setupwizard/pages/outputcalibrationpage.cpp" line="+376"/>
<location line="+88"/>
<source>Start</source>
<translation>Démarrer</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This step calibrates the center position of the servo. To set the center position for this servo, press the Start button below and slide the slider to center the servo. &lt;/p&gt;&lt;p&gt;When done press button again to stop.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Cette étape calibre la position centrale d&apos;un servo. Pour régler la position centrale pour ce servo, appuyez sur le bouton Démarrer ci-dessous et bougez le curseur pour centrer le servo. &lt;/p&gt;&lt;p&gt;Lorsque c&apos;est fait, appuyez à nouveau sur le bouton pour arrêter.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;To save the servo and other hardware from damage we have to set the max and min angles for the servo. &lt;/p&gt;&lt;p&gt;To set the minimum angle for the servo, press the Start button below and select the top slider and slide it to the left until min angle is reached.&lt;/p&gt;&lt;p&gt;When done press button again to stop.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Pour protéger le servo ou tout autre matériel contre des dommages nous devons régler l&apos;angle maxi et mini pour le servo. &lt;/p&gt;&lt;p&gt;Pour régler l&apos;angle minimum du servo, appuyez sur le bouton Démarrer ci-dessous, sélectionnez le curseur du haut puis bougez-le vers la gauche jusqu&apos;à atteindre l&apos;angle minimum.&lt;/p&gt;&lt;p&gt;Lorsque c&apos;est fait, appuyez à nouveau sur le bouton pour arrêter.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;To set the maximum angle for the servo, press the Start button below and select the top slider and slide it to the right until max angle is reached.&lt;/p&gt;&lt;p&gt;When done press button again to stop.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Pour régler l&apos;angle maximum du servo, appuyez sur le bouton Démarrer ci-dessous, sélectionnez le curseur du haut puis bougez-le vers la droite jusqu&apos;à atteindre l&apos;angle maximum.&lt;/p&gt;&lt;p&gt;Lorsque c&apos;est fait, appuyez à nouveau sur le bouton pour arrêter.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/outputcalibrationpage.cpp" line="-123"/>
<location line="+76"/>
<location line="+28"/>
<location line="+19"/>
<location filename="../../../src/plugins/setupwizard/pages/outputcalibrationpage.cpp" line="-88"/>
<location line="+88"/>
<source>Stop</source>
<translation>Arrêter</translation>
</message>
<message>
<location line="-88"/>
<location line="-41"/>
<source>The actuator module is in an error state.
Please make sure the correct firmware version is used then restart the wizard and try again. If the problem persists please consult the openpilot.org support forum.</source>
@ -9443,61 +9581,33 @@ Soyez certain d&apos;utiliser la bonne version de firmware puis redémarrer l&ap
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/outputcalibrationpage.ui"/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;In this step we will set the neutral rate for the motor highlighted in the illustration to the right. &lt;br/&gt;Please pay attention to the details and in particular the motors position and its rotation direction. Ensure the motors are spinning in the correct direction as shown in the diagram. Swap any 2 motor wires to change the direction of a motor. &lt;/p&gt;&lt;p&gt;To find the neutral rate for this engine, press the Start button below and slide the slider to the right until the engine just starts to spin stable. &lt;br/&gt;&lt;br/&gt;When done press button again to stop.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Dans cette étape nous allons régler le neutre du moteur mis en évidence dans l&apos;illustration de droite. &lt;br/&gt;Veuillez faire attention aux détails, en particulier la position du moteur et son sens de rotation. Soyez certain que les moteurs tournent dans le bon sens comme indiqué sur le diagramme. Permutez deux fils d&apos;un moteur pour changer son sens de rotation.&lt;/p&gt;&lt;p&gt;Pour trouver le neutre pour ce moteur, appuyer sur le bouton Démarrer et déplacez le curseur vers la droite jusqu&apos;à ce que le moteur commence à tourner régulièrement. &lt;br/&gt;&lt;br/&gt;Lorsque c&apos;est fait, appuyez à nouveau sur le bouton pour arrêter.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
</context>
<context>
<name>OutputPage</name>
<message>
<location filename="../../../src/plugins/setupwizard/pages/outputpage.ui"/>
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;In this step we will set the neutral rate for the motor highlighted in the illustration to the right. &lt;br/&gt;Please pay attention to the details and in particular the motors position and its rotation direction. Ensure the motors are spinning in the correct direction as shown in the diagram. Swap any 2 motor wires to change the direction of a motor. &lt;/p&gt;&lt;p&gt;To find &lt;span style=&quot; font-weight:600;&quot;&gt;the neutral rate for this motor&lt;/span&gt;, press the Start button below and slide the slider to the right until the motor just starts to spin stable. &lt;br/&gt;&lt;br/&gt;When done press button again to stop.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;A cette étapes nous allons ajuster le neutre du moteur mis en évidence dans l&apos;illustration à droite. &lt;br/&gt;Veuillez faire attention aux détails et en particulier à la position et au sens de rotation du moteur concerné. Soyez certain que le moteur tourne dans le bon sens comme indiqué sur l&apos;illustration ci-contre. Vous pouvez intervertir deux fils du moteur pour changer son sens de rotation. &lt;/p&gt;&lt;p&gt;Pour trouver &lt;span style=&quot; font-weight:600;&quot;&gt;le neutre de ce moteur&lt;/span&gt;, appuyez sur le bouton &quot;Démarrer&quot; ci-dessous et bougez le curseur vers la droite jusqu&apos;à ce que le moteur démarre et tourne de manière régulière. &lt;br/&gt;&lt;br/&gt;Lorsque c&apos;est réglé, appuyez à nouveau sur le bouton pour arrêter.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;Lucida Grande&apos;; font-size:13pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot basic output signal configuration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;MS Shell Dlg 2&apos;; font-size:12pt; font-weight:600;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;To set an optimal configuration of the output signals powering your motors, the wizard needs to know what type of Electronic Speed Controllers (ESCs) you will use and what their capabilities are.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;Please select one of the options below. If you are unsure about the capabilities of your ESCs, just leave the default option selected and continue the wizard.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;To read more regarding ESC refresh rates, please see &lt;/span&gt;&lt;a href=&quot;http://wiki.openpilot.org/x/HIEu&quot;&gt;&lt;span style=&quot; text-decoration: underline; color:#0000ff;&quot;&gt;this article&lt;/span&gt;&lt;/a&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt; in the OpenPilot Wiki&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;Lucida Grande&apos;; font-size:13pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:12pt; font-weight:600;&quot;&gt;Configuration de base des signaux de sortie OpenPilot&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;MS Shell Dlg 2&apos;; font-size:12pt; font-weight:600;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;Pour régler une configuration optimale des signaux de sortie pilotant vos moteurs, l&apos;assistant doit connaître quel type de variateurs (ESC) vous allez utiliser et quelles sont leur capacités.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;Veuillez sélectionner une des options ci-dessous. Si vous n&apos;êtes pas certain des capacités de vos variateurs laissez juste l&apos;option par défaut sélectionnée et continuez l&apos;assistant.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;Pour en savoir plus à propos des fréquences de rafraîchissement des variateurs, veuillez consulter &lt;/span&gt;&lt;a href=&quot;http://wiki.openpilot.org/x/5IBwAQ&quot;&gt;&lt;span style=&quot; text-decoration: underline; color:#0000ff;&quot;&gt;cet article&lt;/span&gt;&lt;/a&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt; sur le Wiki OpenPilot (en anglais)&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This step calibrates&lt;span style=&quot; font-weight:600;&quot;&gt; the minimum, center and maximum angle of the servo&lt;/span&gt;. To set the angles for this servo, press the Start button below and slide the slider for the angle to set. The servo will follow the sliders position. &lt;br/&gt;When done press button again to stop.&lt;/p&gt;&lt;p&gt;Check Reverse to reverse servo action.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Cette étape va ajuster&lt;span style=&quot; font-weight:600;&quot;&gt; l&apos;angle minimum, centré et maximum du servo&lt;/span&gt;. Pour ajuster les positions de ce servo, appuyez sur &quot;Démarrer&quot; et déplacez les curseurs en fonction de l&apos;angle désiré. Le servo bouge en fonction de la position du curseur en cours.&lt;br/&gt;Lorsque vous avez terminé, appuyez à nouveau sur le bouton pour arrêter.&lt;/p&gt;&lt;p&gt;Cochez &quot;Inverser&quot; pour changer la direction de mouvement du servo.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Standard ESC 50Hz</source>
<translation>Variateur Standard 50Hz</translation>
<source>Reverse</source>
<translation>Inverser</translation>
</message>
<message>
<location/>
<source>Standard ESC</source>
<translation>Variateur Standard</translation>
<source>Min</source>
<translation>Mini</translation>
</message>
<message>
<location/>
<source>Turbo PWM ESC 400Hz</source>
<translation>Variateur Turbo PWM 400Hz</translation>
<source>Center</source>
<translation>Centre</translation>
</message>
<message>
<location/>
<source>Turbo PWM</source>
<translation>Turbo PWM</translation>
<source>Max</source>
<translation>Maxi</translation>
</message>
</context>
<context>
@ -9617,39 +9727,36 @@ Connectez votre carte OpenPilot et essayez à nouveau.</translation>
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot configuration summary&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The first part of this wizard is now complete. All information required to create a basic OpenPilot controller configuration for a specific vehicle has been collected.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Below is a summary of the configuration and a button that links to a diagram illustrating how to connect required hardware and the OpenPilot Controller with the current configuration.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To continue the wizard and go through some basic configuration steps, please continue to the next step of this wizard.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The following steps require that your OpenPilot controller is set up according to the diagram, it is &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;connected to the computer&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt; by USB, and that the vehicle is&lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt; powered by a battery&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Sommaire de configuration OpenPilot&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;La première partie de cet assistant est maintenant terminée. Toutes les informations nécessaires à la création d&apos;une configuration de base du contrôleur OpenPilot pour un véhicule particulier ont é collectées.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Vous trouverez ci-dessous un résumé de la configuration et un bouton vous renvoyant vers un diagramme décrivant comment brancher le matériel nécessaire avec le Contrôleur OpenPilot dans la configuration actuelle.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Pour continuer l&apos;assistant et passer par quelques étapes de configuration de base, veuillez passez à l&apos;étape suivante de l&apos;assistant.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Les étapes suivantes requièrent que votre contrôleur OpenPilot soit mis en œuvre comme sur le diagramme, &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;connecté à l&apos;ordinateur&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt; par le port USB et que le véhicule soit&lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt; alimenté par une batterie&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Show connection diagram for configuration</source>
<translatorcomment>Afficher le diagramme de branchement pour la configuration</translatorcomment>
<translation>Afficher le diagramme de branchement pour la configuration</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;Ubuntu&apos;; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot Configuration Summary&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;MS Shell Dlg 2&apos;; font-size:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;The first part of this wizard is now complete. All information required to create a basic OpenPilot controller configuration for a specific vehicle has been collected.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;Below is a summary of the configuration and a button that links to a diagram illustrating how to connect required hardware and the OpenPilot Controller with the current configuration.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;The following steps require that your OpenPilot controller is connected according to the diagram, remains connected to the computer by USB, and that you have a battery ready but &lt;/span&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt; font-weight:600;&quot;&gt;do not&lt;/span&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt; connect it right now, you will be told when to in later steps of this wizard.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;Ubuntu&apos;; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:12pt; font-weight:600;&quot;&gt;Sommaire Configuration OpenPilot&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;MS Shell Dlg 2&apos;; font-size:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;La première partie de l&apos;assistant est à présent terminée. Toutes les informations nécessaires à une configuration de base du contrôleur OpenPilot pour un appareil spécifique ont é collectées.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;Ci-dessous vous trouverez un résumé de la configuration et un bouton qui permet d&apos;afficher un schéma de câblage représentant les branchements nécessaires entre le matériel et le contrôleur OpenPilot pour la configuration actuelle.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;Les étapes suivantes requièrent que le contrôleur OpenPilot soit branché comme sur le schéma de câblage, actuellement connecté à l&apos;ordinateur en USB et que vous avez une batterie à disposition mais &lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt; font-weight:600;&quot;&gt;pas encore branchée. &lt;/span&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:10pt;&quot;&gt;Il vous sera demandé d&apos;effectuer le branchement lors des étapes suivantes de cet assistant.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
</context>
<context>
<name>SurfacePage</name>
@ -9681,31 +9788,6 @@ p, li { white-space: pre-wrap; }
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Vehicle type selection&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To continue, the wizard needs to know what type of vehicle the OpenPilot controller board is going to be used with. This step is crucial since much of the following configuration is unique per vehicle type.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Go ahead and select the type of vehicle for which you want to create a configuration.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;(The current version only provides functionality for multirotors.)&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Sélection du type de véhicule&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Pour continuer, l&apos;assistant a besoin de connaître sur quel type de véhicule la carte OpenPilot va être utilisée. Cette étape est cruciale car une grande partie de la configuration qui suit est spécifique au type de véhicule.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Allez-y et sélectionnez le type de véhicule pour lequel vous souhaitez créer une configuration.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;(La version actuelle ne fournit des fonctionnalités que pour les multirotors.)&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Tricopter, Quadcopter, Hexacopter</source>
@ -9746,6 +9828,31 @@ p, li { white-space: pre-wrap; }
<source>Surface</source>
<translation></translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Vehicle Type Selection&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To continue, the wizard needs to know what type of vehicle the OpenPilot controller board is going to be used with. This step is crucial since much of the following configuration is unique per vehicle type.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Go ahead and select the type of vehicle for which you want to create a configuration.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The current version only provides functionality for Multirotors and Fixed-wing aircraft.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Sélection Type Véhicule&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Pour continuer, l&apos;assistant doit connaître le type de véhicule utilisé avec la carte contrôleur OpenPilot. Cette étape est cruciale et va déterminer la configuration à mettre en place en fonction du type de véhicule.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Poursuivez et sélectionnez le type de véhicule désiré pour créer la configuration.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;La version actuelle supporte les Multirotors et les Voilures Fixes.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
</context>
<context>
<name>viewoptions</name>
@ -9769,6 +9876,11 @@ p, li { white-space: pre-wrap; }
<source>Show Scientific</source>
<translation>Afficher Scientifique</translation>
</message>
<message>
<location/>
<source>Show Description</source>
<translation>Afficher Description</translation>
</message>
</context>
<context>
<name>ImportSummaryDialog</name>
@ -10233,7 +10345,7 @@ p, li { white-space: pre-wrap; }
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Reboot the board and clear its settings memory.&lt;/p&gt;&lt;p&gt; Useful if the board cannot boot properly.&lt;/p&gt;&lt;p&gt; Blue led starts blinking quick for 20-30 seconds than the board will start normally&lt;/p&gt;&lt;p&gt;&lt;br/&gt;&lt;/p&gt;&lt;p&gt;If telemetry is not running, select the link using the dropdown&lt;/p&gt;&lt;p&gt;menu on the right.&lt;/p&gt;&lt;p&gt;PLEASE NOTE: Supported with bootloader versions 4.0 and later&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation type="unfinished">&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Redémarre la carte et efface ses paramètres en mémoire.&lt;/p&gt;&lt;p&gt; Utile si la carte n&apos;arrive pas à démarrer correctement.&lt;/p&gt;&lt;p&gt; La Led Bleue commence à clignoter rapidement pendant 20-30 secondes puis la carte démarre normalement&lt;/p&gt;&lt;p&gt;&lt;br/&gt;&lt;/p&gt;&lt;p&gt;Si la télémétrie ne fonctionne pas, sélectionnez le lien utilisé avec la liste déroulante située à droite.&lt;/p&gt;&lt;p&gt;VEUILLEZ NOTER : Supporté avec les versions de bootloaders 4.0 et supérieures&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Redémarre la carte et efface ses paramètres en mémoire.&lt;/p&gt;&lt;p&gt; Utile si la carte n&apos;arrive pas à démarrer correctement.&lt;/p&gt;&lt;p&gt; La Led Bleue commence à clignoter rapidement pendant 20-30 secondes puis la carte démarre normalement&lt;/p&gt;&lt;p&gt;&lt;br/&gt;&lt;/p&gt;&lt;p&gt;Si la télémétrie ne fonctionne pas, sélectionnez le lien utilisé avec la liste déroulante située à droite.&lt;/p&gt;&lt;p&gt;VEUILLEZ NOTER : Supporté avec les versions de bootloaders 4.0 et supérieures&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
@ -10266,26 +10378,36 @@ p, li { white-space: pre-wrap; }
<context>
<name>ConfigMultiRotorWidget</name>
<message>
<location filename="../../../src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp" line="+696"/>
<location filename="../../../src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp" line="+152"/>
<source>Input</source>
<translation>Entrée</translation>
</message>
<message>
<location line="+1"/>
<source>Output</source>
<translation>Sortie</translation>
</message>
<message>
<location line="+376"/>
<location line="+24"/>
<location line="+31"/>
<location line="+31"/>
<location line="+25"/>
<location line="+24"/>
<location line="+24"/>
<location line="+41"/>
<location line="+200"/>
<location line="+44"/>
<location line="+207"/>
<location line="+70"/>
<source>Configuration OK</source>
<translation>Configuration OK</translation>
</message>
<message>
<location line="-302"/>
<location line="-312"/>
<source>&lt;font color=&apos;red&apos;&gt;ERROR: Assign a Yaw channel&lt;/font&gt;</source>
<translation>&lt;font color=&apos;red&apos;&gt;ERREUR : Veuillez affecter le canal de Yaw&lt;/font&gt;</translation>
</message>
<message>
<location line="+367"/>
<location line="+383"/>
<source>&lt;font color=&apos;red&apos;&gt;ERROR: Assign all %1 motor channels&lt;/font&gt;</source>
<translation>&lt;font color=&apos;red&apos;&gt;ERREUR : Veuillez affecter tous les %1 canaux moteurs&lt;/font&gt;</translation>
</message>
@ -10357,26 +10479,26 @@ Voulez-vous toujours continuer ?</translation>
<context>
<name>ConfigInputWidget</name>
<message>
<location filename="../../../src/plugins/config/configinputwidget.cpp" line="+366"/>
<location filename="../../../src/plugins/config/configinputwidget.cpp" line="+369"/>
<source>http://wiki.openpilot.org/x/04Cf</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/aIBqAQ</translation>
</message>
<message>
<location line="+7"/>
<location line="+1056"/>
<location line="+1140"/>
<source>Arming Settings are now set to &apos;Always Disarmed&apos; for your safety.</source>
<translatorcomment>Contexte : Onglet &quot;Paramètres d&apos;Armement&quot;</translatorcomment>
<translation>Pour des raisons de sécurité les Paramètres d&apos;Armement ont é modifiés à &apos;Toujours Désarmé&apos;.</translation>
</message>
<message>
<location line="-1055"/>
<location line="-1139"/>
<source>You will have to reconfigure the arming settings manually when the wizard is finished. After the last step of the wizard you will be taken to the Arming Settings screen.</source>
<translatorcomment>redirigé vers / sur ?</translatorcomment>
<translation>Vous devrez reconfigurer manuellement les paramètres d&apos;armement lorsque l&apos;assistant sera terminé. Après la dernière étape de l&apos;assistant, vous serez redirigé vers l&apos;écran des Paramètres d&apos;Armement.</translation>
</message>
<message>
<location line="+172"/>
<location line="+228"/>
<source>Welcome to the inputs configuration wizard.
Please follow the instructions on the screen and only move your controls when asked to.
@ -10496,7 +10618,7 @@ If your FlightMode switch has only two positions, leave it in either position.</
Si votre interrupteur de Mode de Vol a seulement deux positions, laissez-le dans n&apos;importe quelle position.</translation>
</message>
<message>
<location line="+9"/>
<location line="+6"/>
<source>Please move all controls to their maximum extents on both directions.
Press Next when ready.</source>
@ -10505,12 +10627,12 @@ Press Next when ready.</source>
Appuyez sur Suivant lorsque vous êtes prêt.</translation>
</message>
<message>
<location line="+37"/>
<location line="+36"/>
<source>Please check the picture below and correct all the sticks which show an inverted movement. Press Next when ready.</source>
<translation>Veuillez vérifier l&apos;image ci-dessous et corriger les manches qui s&apos;affichent en sens inverse. Appuyer sur Suivant lorsque vous êtes prêt.</translation>
</message>
<message>
<location line="+8"/>
<location line="+7"/>
<source>You have completed this wizard, please check below if the picture mimics your sticks movement.
IMPORTANT: These new settings have not been saved to the board yet. After pressing Next you will go to the Arming Settings tab where you can set your desired arming sequence and save the configuration.</source>
@ -10519,7 +10641,7 @@ IMPORTANT: These new settings have not been saved to the board yet. After pressi
IMPORTANT : Ces nouveaux paramètres ne sont pas encore enregistrés sur la carte. Après avoir appuyé sur Suivant vous serez dirigé vers l&apos;onglet Paramètres d&apos;Armement vous pourrez choisir votre séquence d&apos;armement et enregistrer la configuration.</translation>
</message>
<message>
<location line="+116"/>
<location line="+124"/>
<source>Please enable throttle hold mode.
Move the Collective Pitch stick.</source>
@ -10562,7 +10684,7 @@ Bougez le manche %1.</translation>
<translation> Vous avez la possibilité d&apos;appuyer sur Suivant pour ignorer ce canal.</translation>
</message>
<message>
<location line="+626"/>
<location line="+651"/>
<source>You will have to reconfigure the arming settings manually when the wizard is finished.</source>
<translation>Vous devrez reconfigurer les paramètres d&apos;armement manuellement lorsque l&apos;assistant sera terminé.</translation>
</message>
@ -10673,7 +10795,7 @@ Bougez le manche %1.</translation>
<context>
<name>LoggingThread</name>
<message>
<location line="+162"/>
<location line="+164"/>
<source>Logging: retrieve settings objects from the autopilot (%1 objects)</source>
<translation>Journalisation : récupération des objets de configuration de l&apos;autopilote (%1 objets)</translation>
</message>
@ -10838,7 +10960,7 @@ Bougez le manche %1.</translation>
<message>
<location filename="../../../src/plugins/scope/scopegadgetfactory.cpp" line="+36"/>
<source>Scope</source>
<translation type="unfinished">Graphique</translation>
<translation>Graphique</translation>
</message>
</context>
<context>
@ -10854,12 +10976,12 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<context>
<name>SetupWizard</name>
<message>
<location filename="../../../src/plugins/setupwizard/setupwizard.cpp" line="+57"/>
<location filename="../../../src/plugins/setupwizard/setupwizard.cpp" line="+63"/>
<source>OpenPilot Setup Wizard</source>
<translation>Assistant Configuration OpenPilot</translation>
</message>
<message>
<location line="+106"/>
<location line="+172"/>
<source>Controller type: </source>
<translation>Type de contrôleur : </translation>
</message>
@ -10878,6 +11000,11 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<source>OpenPilot Revolution</source>
<translation></translation>
</message>
<message>
<location line="+3"/>
<source>OpenPilot Nano</source>
<translation></translation>
</message>
<message>
<location line="+3"/>
<source>OpenPilot OPLink Radio Modem</source>
@ -10885,15 +11012,23 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
</message>
<message>
<location line="+3"/>
<location line="+47"/>
<location line="+15"/>
<source>OpenPilot DiscoveryF4 Development Board</source>
<translation></translation>
</message>
<message>
<location line="+3"/>
<location line="+50"/>
<location line="+21"/>
<location line="+12"/>
<location line="+25"/>
<location line="+13"/>
<location line="+15"/>
<location line="+38"/>
<source>Unknown</source>
<translation>Inconnu</translation>
</message>
<message>
<location line="-95"/>
<location line="-169"/>
<source>Vehicle type: </source>
<translation>Type de véhicule : </translation>
</message>
@ -10904,23 +11039,29 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
</message>
<message>
<location line="+3"/>
<location line="+48"/>
<source>Vehicle sub type: </source>
<translation>Sous-type véhicule : </translation>
</message>
<message>
<location line="+3"/>
<location line="-45"/>
<source>Tricopter</source>
<translation>Tricoptère</translation>
</message>
<message>
<location line="+3"/>
<source>Quadcopter X</source>
<translation>Quadricopter X</translation>
<translation>Quadricoptère X</translation>
</message>
<message>
<location line="+3"/>
<source>Quadcopter +</source>
<translation>Quadricopter +</translation>
<translation>Quadricoptère +</translation>
</message>
<message>
<location line="+3"/>
<source>Quadcopter H</source>
<translation>Quadricoptère H</translation>
</message>
<message>
<location line="+3"/>
@ -10935,7 +11076,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<message>
<location line="+3"/>
<source>Hexacopter H</source>
<translation type="unfinished">Hexacoptère H</translation>
<translation>Hexacoptère H</translation>
</message>
<message>
<location line="+3"/>
@ -10967,8 +11108,23 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<source>Fixed wing</source>
<translation>Aile</translation>
</message>
<message>
<location line="+6"/>
<source>Dual Aileron</source>
<translation>Aileron Double</translation>
</message>
<message>
<location line="+3"/>
<source>Aileron</source>
<translation>Aileron</translation>
</message>
<message>
<location line="+3"/>
<source>Elevon</source>
<translation>Elevon</translation>
</message>
<message>
<location line="+9"/>
<source>Helicopter</source>
<translation>Hélicoptère</translation>
</message>
@ -11014,32 +11170,97 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
</message>
<message>
<location line="+7"/>
<source>ESC type: </source>
<translation>Type de variateur : </translation>
<source>Speed Controller (ESC) type: </source>
<translation>Type Contrôleur (Esc) : </translation>
</message>
<message>
<location line="+3"/>
<source>Legacy ESC (50 Hz)</source>
<translation>Variateur Classique (50Hz)</translation>
<source>Standard ESC (50 Hz)</source>
<translation>Contrôleur Standard (50 Hz)</translation>
</message>
<message>
<location line="+3"/>
<source>Rapid ESC (400 Hz)</source>
<translation>Variateur Rapide (400Hz)</translation>
<source>Rapid ESC (500 Hz)</source>
<translation>Contrôleur Rapide (500Hz)</translation>
</message>
<message>
<location line="+9"/>
<source>Servo type: </source>
<translation>Type Servo : </translation>
</message>
<message>
<location line="+3"/>
<source>Analog Servos (50 Hz)</source>
<translation>Servo Analogique (50Hz)</translation>
</message>
<message>
<location line="+3"/>
<source>Digital Servos (333 Hz)</source>
<translation>Servo Digital (333Hz)</translation>
</message>
<message>
<location line="+10"/>
<source>GPS type: </source>
<translation>Type GPS : </translation>
</message>
<message>
<location line="+3"/>
<source>OpenPilot Platinum</source>
<translation></translation>
</message>
<message>
<location line="+3"/>
<source>OpenPilot v8 or Generic UBLOX GPS</source>
<translation>OpenPilot v8 ou GPS Ublox générique</translation>
</message>
<message>
<location line="+3"/>
<source>Generic NMEA GPS</source>
<translation>GPS NMEA générique</translation>
</message>
<message>
<location line="+3"/>
<source>None</source>
<translation>Aucun</translation>
</message>
<message>
<location line="+7"/>
<source>Airspeed Sensor: </source>
<translation>Capteur Vitesse Air : </translation>
</message>
<message>
<location line="+3"/>
<source>Software Estimated</source>
<translation>Estimation Logicielle</translation>
</message>
<message>
<location line="+3"/>
<source>EagleTree on Flexi-Port</source>
<translation>EagleTree sur Flexi-Port</translation>
</message>
<message>
<location line="+3"/>
<source>MS4525 based on Flexi-Port</source>
<translation>MS4525 sur Flexi-Port</translation>
</message>
</context>
<context>
<name>SetupWizardPlugin</name>
<message>
<location filename="../../../src/plugins/setupwizard/setupwizardplugin.cpp" line="+60"/>
<location filename="../../../src/plugins/setupwizard/setupwizardplugin.cpp" line="+61"/>
<source>Vehicle Setup Wizard</source>
<translation>Assistant Configuration Véhicule</translation>
</message>
<message>
<location line="+12"/>
<source>Export Wizard Vehicle Template</source>
<translation>Exporter Modèle Assistant Véhicule</translation>
</message>
</context>
<context>
<name>VehicleConfigurationHelper</name>
<message>
<location filename="../../../src/plugins/setupwizard/vehicleconfigurationhelper.cpp" line="+79"/>
<location filename="../../../src/plugins/setupwizard/vehicleconfigurationhelper.cpp" line="+85"/>
<location line="+12"/>
<source>Done!</source>
<translation>Terminé !</translation>
@ -11051,17 +11272,33 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<translation>Échoué !</translation>
</message>
<message>
<location line="+95"/>
<location line="+130"/>
<source>Writing External Mag sensor settings</source>
<translation>Écriture paramètres Compas Externe</translation>
</message>
<message>
<location line="+9"/>
<source>Writing GPS sensor settings</source>
<translation>Écriture paramètres capteur GPS</translation>
</message>
<message>
<location line="+32"/>
<source>Writing Airspeed sensor settings</source>
<translation type="unfinished">Écriture paramètres capteur Vitesse Air</translation>
</message>
<message>
<location line="+7"/>
<source>Writing hardware settings</source>
<translation>Écriture paramètres matériels</translation>
</message>
<message>
<location line="+113"/>
<location line="+155"/>
<location line="+31"/>
<source>Writing actuator settings</source>
<translation>Écriture paramètres actionneurs</translation>
</message>
<message>
<location line="+55"/>
<location line="+60"/>
<source>Writing flight mode settings 1/2</source>
<translation>Écriture paramètres mode de vol 1/2</translation>
</message>
@ -11087,7 +11324,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<translation>Écriture paramètres de stabilisation</translation>
</message>
<message>
<location line="+29"/>
<location line="+102"/>
<source>Writing mixer settings</source>
<translation>Écriture paramètres mixeur</translation>
</message>
@ -11102,7 +11339,12 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<translation>Écriture contrôles manuels par défaut</translation>
</message>
<message>
<location line="+154"/>
<location line="+13"/>
<source>Writing template settings for %1</source>
<translation>Écriture modèle de configuration pour %1</translation>
</message>
<message>
<location line="+157"/>
<source>Preparing mixer settings</source>
<translation>Préparation des paramètres de mixage</translation>
</message>
@ -11131,7 +11373,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<context>
<name>UAVObjectField</name>
<message>
<location filename="../../../src/plugins/uavobjects/uavobjectfield.cpp" line="+89"/>
<location filename="../../../src/plugins/uavobjects/uavobjectfield.cpp" line="+91"/>
<source>0</source>
<translation></translation>
</message>
@ -11140,6 +11382,36 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<source>1</source>
<translation></translation>
</message>
<message>
<location line="+390"/>
<source>one of</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+13"/>
<source>none of</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+11"/>
<source>more than</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+3"/>
<source>between</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+1"/>
<source> and </source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+2"/>
<source>less than</source>
<translation type="unfinished"></translation>
</message>
</context>
<context>
<name>PopupWidget</name>
@ -11281,12 +11553,12 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
</message>
<message>
<location line="+27"/>
<location line="+380"/>
<location line="+383"/>
<source>Device</source>
<translation>Périphérique</translation>
</message>
<message>
<location line="-305"/>
<location line="-308"/>
<source>http://wiki.openpilot.org/display/Doc/Erase+board+settings</source>
<translatorcomment>Wiki FR - Uploader</translatorcomment>
<translation>http://wiki.openpilot.org/x/SYBqAQ</translation>
@ -11298,14 +11570,14 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
</message>
<message>
<location line="+43"/>
<location line="+161"/>
<location line="+164"/>
<source>Timed out while waiting for all boards to be disconnected!</source>
<translatorcomment>Bof</translatorcomment>
<translation type="unfinished">Expiration du temps d&apos;attente de la déconnexion de toutes les cartes !</translation>
</message>
<message>
<location line="-152"/>
<location line="+167"/>
<location line="-155"/>
<location line="+170"/>
<source>Timed out while waiting for a board to be connected!</source>
<translatorcomment>Bof</translatorcomment>
<translation type="unfinished">Expiration du temps dans l&apos;attente d&apos;une connexion de carte !</translation>
@ -11336,7 +11608,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<message>
<location line="+131"/>
<source>Waiting for all OpenPilot boards to be disconnected from USB.</source>
<translation type="unfinished">Attente de la déconnexion de toutes les cartes connectées en USB.</translation>
<translation>Attente de la déconnexion de toutes les cartes connectées en USB.</translation>
</message>
<message>
<location line="+4"/>
@ -11444,7 +11716,7 @@ La carte sera redémarrée et tous les paramètres effacés.</translation>
<translation>Veuillez vérifier que la carte n&apos;est pas armée et appuyez à nouveau Réinitialiser pour continuer ou allumer/éteindre la carte pour forcer la réinitialisation.</translation>
</message>
<message>
<location line="-317"/>
<location line="-320"/>
<source></source>
<translation>Annuler</translation>
</message>
@ -11575,12 +11847,12 @@ La carte sera redémarrée et tous les paramètres effacés.</translation>
<message>
<location/>
<source>Servo Z</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Servo Y</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -11590,22 +11862,22 @@ La carte sera redémarrée et tous les paramètres effacés.</translation>
<message>
<location/>
<source>Angle W</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Angle X</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Angle Y</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Angle Z</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -11891,106 +12163,46 @@ La carte sera redémarrée et tous les paramètres effacés.</translation>
<source>Form</source>
<translation>Formulaire</translation>
</message>
<message>
<location/>
<source>Airplane type:</source>
<translation>Type d&apos;avion :</translation>
</message>
<message>
<location/>
<source>Output Channel Assignments</source>
<translation>Affectation Canaux de Sortie</translation>
</message>
<message>
<location/>
<source>Engine</source>
<translation>Moteur</translation>
</message>
<message>
<location/>
<source>Select output channel for the engine</source>
<translation>Sélectionner le canal de sortie pour le moteur</translation>
</message>
<message>
<location/>
<source>Aileron 1</source>
<translation>Aileron 1</translation>
</message>
<message>
<location/>
<source>Select output channel for the first aileron (or elevon)</source>
<translation>Sélectionner le canal de sortie pour le premier aileron (ou élevon)</translation>
</message>
<message>
<location/>
<source>Aileron 2</source>
<translation>Aileron 2</translation>
</message>
<message>
<location/>
<source>Select output channel for the second aileron (or elevon)</source>
<translation>Sélectionner le canal de sortie pour le second aileron (ou élevon)</translation>
</message>
<message>
<location/>
<source>Elevator 1</source>
<translation>Profondeur 1</translation>
</message>
<message>
<location/>
<source>Select output channel for the first elevator</source>
<translation>Sélectionner le canal de sortie pour la profondeur principale</translation>
</message>
<message>
<location/>
<source>Elevator 2</source>
<translation>Profondeur 2</translation>
</message>
<message>
<location/>
<source>Select output channel for a secondary elevator</source>
<translation>Sélectionner le canal de sortie pour la profondeur secondaire</translation>
</message>
<message>
<location/>
<source>Rudder 1</source>
<translation>Dérive 1</translation>
</message>
<message>
<location/>
<source>Select output channel for the first rudder</source>
<translation>Sélectionner le canal de sortie pour la dérive principale</translation>
</message>
<message>
<location/>
<source>Rudder 2</source>
<translation>Dérive 2</translation>
</message>
<message>
<location/>
<source>Select output channel for a secondary rudder</source>
<translation>Sélectionner le canal de sortie pour la dérive secondaire</translation>
</message>
<message>
<location/>
<source>Elevon Mix</source>
<translation>Mixage</translation>
</message>
<message>
<location/>
<source>Rudder %</source>
<translation>Dérive %</translation>
</message>
<message>
<location/>
<source>50</source>
<translation></translation>
</message>
<message>
<location/>
<source>Pitch %</source>
<translation>Profondeur %</translation>
</message>
<message>
<location/>
<source>Throttle Curve</source>
@ -12001,6 +12213,56 @@ La carte sera redémarrée et tous les paramètres effacés.</translation>
<source>Mixer OK</source>
<translation></translation>
</message>
<message>
<location/>
<source>Airframe</source>
<translation>Plateforme</translation>
</message>
<message>
<location/>
<source>Mixer</source>
<translation>Mixage</translation>
</message>
<message>
<location/>
<source>Roll</source>
<translation></translation>
</message>
<message>
<location/>
<source>Weight of mixing in percent</source>
<translation>Quantité de mixage en pourcent</translation>
</message>
<message>
<location/>
<source>Pitch</source>
<translation></translation>
</message>
<message>
<location/>
<source>Airframe Type:</source>
<translation>Type Plateforme :</translation>
</message>
<message>
<location/>
<source>Select Fixed-wing type</source>
<translation>Sélectionner le type de voilure fixe</translation>
</message>
<message>
<location/>
<source>Assign your output channel</source>
<translation>Affecter votre canal de sortie</translation>
</message>
<message>
<location/>
<source>Motor</source>
<translation>Moteur</translation>
</message>
<message>
<location/>
<source>Assign your motor output channel</source>
<translation>Affecter votre canal de sortie moteur</translation>
</message>
</context>
<context>
<name>GroundConfigWidget</name>
@ -12132,11 +12394,6 @@ La carte sera redémarrée et tous les paramètres effacés.</translation>
<source>Form</source>
<translation>Formulaire</translation>
</message>
<message>
<location/>
<source>Frame</source>
<translation>Châssis</translation>
</message>
<message>
<location/>
<source>Throttle Curve</source>
@ -12152,13 +12409,6 @@ La carte sera redémarrée et tous les paramètres effacés.</translation>
<source>Roll</source>
<translation></translation>
</message>
<message>
<location/>
<source>Weight of Roll mixing in percent.
Typical values are 100% for + configuration and 50% for X configuration on quads.</source>
<translation>Quantité de mixage Roll en pourcentage.
Les valeurs classiques sont de 100% en configuration + et 50% en configuration X sur les quadricoptères.</translation>
</message>
<message>
<location/>
<source>50</source>
@ -12188,16 +12438,6 @@ Typical value is 50% for + or X configuration on quads.</source>
<translation>Quantité de mixage Yaw en pourcentage.
Les valeurs classiques sont de 50% en configuration + et X sur les quadricoptères.</translation>
</message>
<message>
<location/>
<source>Frame Type:</source>
<translation>Type Châssis :</translation>
</message>
<message>
<location/>
<source>Select the Multirotor frame type here.</source>
<translation>Sélectionner ici le type de châssis de Multirotor.</translation>
</message>
<message>
<location/>
<source>Mixer OK</source>
@ -12268,6 +12508,28 @@ Les valeurs classiques sont de 50% en configuration + et X sur les quadricoptèr
<source>Reverse all motors</source>
<translation>Inverser tous les moteurs</translation>
</message>
<message>
<location/>
<source>Airframe</source>
<translation>Châssis</translation>
</message>
<message>
<location/>
<source>Weight of Roll mixing in percent.
Typical values are 100% for + configuration and 50% for X configuration on quads</source>
<translation>Quantité de mixage Roll en pourcentage.
Les valeurs classiques sont de 100% en configuration + et 50% en configuration X sur les quadricoptères</translation>
</message>
<message>
<location/>
<source>Airframe Type:</source>
<translation>Type Châssis :</translation>
</message>
<message>
<location/>
<source>Select the Multirotor frame type</source>
<translation>Sélectionner ici le type de châssis Multirotor</translation>
</message>
</context>
<context>
<name>RevoHWWidget</name>
@ -12284,7 +12546,7 @@ Les valeurs classiques sont de 50% en configuration + et X sur les quadricoptèr
<message>
<location/>
<source>USB HID Function</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -12294,27 +12556,27 @@ Les valeurs classiques sont de 50% en configuration + et X sur les quadricoptèr
<message>
<location/>
<source>Flexi Port</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Main Port</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Sonar Port</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Receiver Port</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>USB VCP Function</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -12587,7 +12849,7 @@ Méfiez-vous de ne pas vous verrouiller l&apos;accès !</translation>
<message>
<location/>
<source>VCP Port</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -12597,7 +12859,7 @@ Méfiez-vous de ne pas vous verrouiller l&apos;accès !</translation>
<message>
<location/>
<source>Main Port</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -12622,12 +12884,12 @@ Méfiez-vous de ne pas vous verrouiller l&apos;accès !</translation>
<message>
<location/>
<source>FlexiIO Port</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
<source>Flexi Port</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location/>
@ -12783,27 +13045,6 @@ Méfiez-vous de ne pas vous verrouiller l&apos;accès !</translation>
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot sensor calibration procedure&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The wizard needs to get information from the controller to determine in which position the vehicle is normally considered to be level. To be able to successfully perform these measurements, you need to place the vehicle on a surface that is as flat and level as possible. Examples of such surfaces could be a table top or the floor. Be careful to ensure that the vehicle really is level, since this step will affect the accelerometer and gyro bias in the controller software.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To perform the calibration, please push the Calculate button and wait for the process to finish. &lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Procédure d&apos;étalonnage des capteurs OpenPilot&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;L&apos;assistant a besoin de récupérer des informations du contrôleur pour déterminer dans quelle position l&apos;appareil est normalement considéré de niveau. Afin de réaliser avec succès ces mesures, vous devez placer le véhicule sur une surface aussi plane et horizontale que possible. Des exemples de ces surfaces pourraient être un dessus de table ou le sol. Veillez à ce que le véhicule soit vraiment de niveau puisque cette étape aura une incidence sur l&apos;ajustement des accéléromètres et des gyroscopes dans le logiciel du contrôleur.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Pour effectuer l&apos;étalonnage, veuillez appuyer sur le bouton Calculer et attendez la fin du processus. &lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Calculate gyro and accelerometer bias</source>
@ -12831,6 +13072,27 @@ Connectez votre carte OpenPilot et essayez à nouveau.</translation>
<source>&lt;font color=&apos;green&apos;&gt;Done!&lt;/font&gt;</source>
<translation>&lt;font color=&apos;green&apos;&gt;Terminé !&lt;/font&gt;</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/biascalibrationpage.ui"/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot Sensor Calibration Procedure&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The wizard needs to get information from the controller to determine in which position the vehicle is normally considered to be level. To be able to successfully perform these measurements, you need to place the vehicle on a surface that is as flat and level as possible. Examples of such surfaces could be a table top or the floor. Be careful to ensure that the vehicle really is level, since this step will affect the accelerometer and gyro bias in the controller software.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To perform the calibration, please push the Calculate button and wait for the process to finish.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Procédure d&apos;étalonnage des capteurs OpenPilot&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;L&apos;assistant a besoin de récupérer des informations du contrôleur pour déterminer dans quelle position l&apos;appareil est normalement considéré de niveau. Afin de réaliser avec succès ces mesures, vous devez placer le véhicule sur une surface aussi plane et horizontale que possible. Des exemples de ces surfaces pourraient être un dessus de table ou le sol. Veillez à ce que le véhicule soit vraiment de niveau puisque cette étape aura une incidence sur l&apos;ajustement des accéléromètres et des gyroscopes dans le logiciel du contrôleur.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Pour effectuer l&apos;étalonnage, veuillez appuyer sur le bouton Calculer et attendez la fin du processus. &lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
</context>
<context>
<name>RevoCalibrationPage</name>
@ -12845,7 +13107,7 @@ Connectez votre carte OpenPilot et essayez à nouveau.</translation>
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot Revolution controller sensor calibration procedure&lt;/span&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot Revolution Calibration Procedure&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The calibration procedure for the OpenPilot Revolution controller is not yet implemented in this setup wizard. To calibrate your OpenPilot Revolution controller please use the calibration utility found in the configuration plugin after you have finished this wizard.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
@ -12890,17 +13152,17 @@ p, li { white-space: pre-wrap; }
<context>
<name>ConfigOutputWidget</name>
<message>
<location filename="../../../src/plugins/config/configoutputwidget.cpp" line="+140"/>
<location filename="../../../src/plugins/config/configoutputwidget.cpp" line="+144"/>
<source>The actuator module is in an error state. This can also occur because there are no inputs. Please fix these before testing outputs.</source>
<translation>Le module actionneur est en erreur. Cela peut aussi arriver lorsque il n&apos;y a pas d&apos;entrées (Rx radiocommande). Veuillez corriger cela avant de tester les sorties.</translation>
</message>
<message>
<location line="+14"/>
<source>This option will start your motors by the amount selected on the sliders regardless of transmitter. It is recommended to remove any blades from motors. Are you sure you want to do this?</source>
<location line="+15"/>
<source>This option will start your motors by the amount selected on the sliders regardless of transmitter.It is recommended to remove any blades from motors. Are you sure you want to do this?</source>
<translation>Cette option démarre vos moteurs avec la valeur sélectionnée sur les curseurs, indépendamment de l&apos;émetteur. Il est recommandé d&apos;enlever les hélices des moteurs. Êtes-vous sûr de vouloir faire ça ?</translation>
</message>
<message>
<location line="+249"/>
<location line="+253"/>
<source>http://wiki.openpilot.org/x/WIGf</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/aoBqAQ</translation>
@ -12909,12 +13171,12 @@ p, li { white-space: pre-wrap; }
<context>
<name>ConfigRevoHWWidget</name>
<message>
<location filename="../../../src/plugins/config/configrevohwwidget.cpp" line="+92"/>
<location filename="../../../src/plugins/config/configrevohwwidget.cpp" line="+94"/>
<source>Disabled</source>
<translation>Désactivé</translation>
</message>
<message>
<location line="+201"/>
<location line="+226"/>
<source>http://wiki.openpilot.org/x/GgDBAQ</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/TYRNAQ</translation>
@ -13018,7 +13280,7 @@ p, li { white-space: pre-wrap; }
<translation>Révision Matériel :</translation>
</message>
<message>
<location line="+31"/>
<location line="+34"/>
<source>Flash access: </source>
<translation>Accès flash : </translation>
</message>
@ -13213,12 +13475,12 @@ Veuillez sélectionner une zone de la carte à télécharger avec &lt;CTRL&gt;+C
<context>
<name>AboutDialog</name>
<message>
<location filename="../../../src/plugins/coreplugin/qml/AboutDialog.qml" line="+75"/>
<location filename="../../../src/plugins/coreplugin/qml/AboutDialog.qml" line="+86"/>
<source>OpenPilot Ground Control Station</source>
<translation>Station de Contrôle au Sol OpenPilot (GCS)</translation>
</message>
<message>
<location line="+18"/>
<location line="+26"/>
<source>This program is free software; you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation; either version 3 of the License, or (at your option) any later version.
The program is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.</source>
<translation>Ce programme est un logiciel libre ; vous pouvez le redistribuer et/ou le modifier dans le cadre des termes de la licence GNU General Public Licence publiée par la Free Software Foundation; soit à la version 3 de la Licence, ou (en option) à une version ultérieure. Le programme est fourni EN L&apos;ÉTAT sans AUCUNE GARANTIE D&apos;UN QUELCONQUE TYPE, COMPRENANT LA GARANTIE DE DESIGN, DE COMMERCIALISATION ET D&apos;ERGONOMIE POUR UN USAGE PARTICULIER.</translation>
@ -13302,16 +13564,18 @@ Configuration n&apos;est pas chargé dans l&apos;espace de travail actuel.</tran
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Welcome to the OpenPilot Setup Wizard&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;This wizard will guide you through the basic steps required to setup your OpenPilot controller for the first time. You will be asked questions about your platform (multirotor/heli/fixed-wing) which this wizard will use to configure your controller for its first flight. &lt;/span&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Welcome to the OpenPilot Setup Wizard&lt;/span&gt;&lt;img src=&quot;:/setupwizard/resources/wizard.png&quot; style=&quot;float: right;&quot; /&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p align=&quot;right&quot; style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;This wizard will guide you through the basic steps required to setup your OpenPilot controller for the first time. You will be asked questions about your platform (multirotor/heli/fixed-wing) which this wizard will use to configure your controller for its first flight.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;This wizard does not configure all of the advanced settings available in the GCS Configuration. All basic and advanced configuration parameters can be modified later by using the GCS Configuration plugin.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600; color:#ff0000;&quot;&gt;WARNING: YOU MUST REMOVE ALL PROPELLERS &lt;/span&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600; color:#ff0000;&quot;&gt;FROM THE VEHICLE BEFORE PROCEEDING!&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:&apos;Lucida Grande&apos;; font-size:13pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Disregarding this warning puts you at&lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600; color:#000000;&quot;&gt; risk of very serious injury&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;!&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Disregarding this warning puts you at&lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600; color:#000000;&quot;&gt; risk of injury&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;!&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Now that your props are removed we can get started. Ready?&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
@ -13454,10 +13718,10 @@ p, li { white-space: pre-wrap; }
<message>
<location line="+1"/>
<source>UAVO</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location line="+1"/>
<location line="+2"/>
<source>Unknown</source>
<translation>Inconnu</translation>
</message>
@ -13467,17 +13731,7 @@ p, li { white-space: pre-wrap; }
<translation>Données</translation>
</message>
<message>
<location line="+13"/>
<source>Flights recorded: </source>
<translation>Vols enregistrés : </translation>
</message>
<message>
<location line="+4"/>
<source>Entries logged (free): </source>
<translation>Vols enregistrés (libres) : </translation>
</message>
<message>
<location line="+25"/>
<location line="+46"/>
<source>Flight to download:</source>
<translation>Vols à télécharger :</translation>
</message>
@ -13492,7 +13746,27 @@ p, li { white-space: pre-wrap; }
<translation>Ajuster horodatage</translation>
</message>
<message>
<location line="+47"/>
<location line="-39"/>
<source>UAVO(P)</source>
<translation></translation>
</message>
<message>
<location line="+22"/>
<source>Flights recorded:</source>
<translation>Vols enregistrés :</translation>
</message>
<message>
<location line="+4"/>
<source>Slots used/free:</source>
<translation>Emplacements utilisés/disponibles :</translation>
</message>
<message>
<location line="+5"/>
<source>Entries downloaded:</source>
<translation>Entrées téléchargées :</translation>
</message>
<message>
<location line="+55"/>
<source>Clear all logs</source>
<translation>Effacer tous les logs</translation>
</message>
@ -13515,7 +13789,7 @@ p, li { white-space: pre-wrap; }
<message>
<location line="+107"/>
<source>UAVObject</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location line="+21"/>
@ -13593,15 +13867,11 @@ p, li { white-space: pre-wrap; }
<source>OK</source>
<translation>OK</translation>
</message>
<message>
<source>Manage flight side logs</source>
<translation type="vanished">Gérer les logs de vol</translation>
</message>
</context>
<context>
<name>FlightLogManager</name>
<message>
<location filename="../../../src/plugins/flightlog/flightlogmanager.cpp" line="+274"/>
<location filename="../../../src/plugins/flightlog/flightlogmanager.cpp" line="+300"/>
<source>_flight-%1</source>
<translation>_vol-%1</translation>
</message>
@ -13625,12 +13895,12 @@ p, li { white-space: pre-wrap; }
<message>
<location line="-90"/>
<source>Save Log Entries</source>
<translation type="unfinished">Enregistre Entrées Log</translation>
<translation>Enregistre Entrées Log</translation>
</message>
<message>
<location line="+33"/>
<source>Load Log Settings</source>
<translation type="unfinished">Charger Paramètres Log</translation>
<translation>Charger Paramètres Log</translation>
</message>
<message>
<location line="+15"/>
@ -13694,7 +13964,7 @@ Veuillez vérifier le fichier.
<message>
<location line="+0"/>
<source>Throttled</source>
<translation type="unfinished">Modifié + Ralenti</translation>
<translation>Modifié + Ralenti</translation>
</message>
<message>
<location line="+5"/>
@ -13722,7 +13992,7 @@ Veuillez vérifier le fichier.
<message>
<location line="+20"/>
<source>Manage flight side logs</source>
<translation type="unfinished">Gérer les logs de vol</translation>
<translation>Gérer les logs de vol</translation>
</message>
</context>
<context>
@ -13778,64 +14048,82 @@ Veuillez vérifier le fichier.
<location line="+0"/>
<source>To apply the changes when binding/unbinding the board must be rebooted or power cycled.</source>
<translatorcomment>détachement ou dissociation ~ unbinding ? tr Bof</translatorcomment>
<translation type="unfinished">Pour appliquer les changements d&apos;association/dissociation la carte doit être redémarrée ou débranchée/rebranchée.</translation>
<translation>Pour appliquer les changements d&apos;association/dissociation la carte doit être redémarrée ou débranchée/rebranchée.</translation>
</message>
</context>
<context>
<name>ConfigStabilizationWidget</name>
<message>
<location filename="../../../src/plugins/config/configstabilizationwidget.cpp" line="+63"/>
<source>PID Bank %1</source>
<translation>Banque PID %1</translation>
<location filename="../../../src/plugins/config/configstabilizationwidget.cpp" line="+69"/>
<source>Settings Bank %1</source>
<translation>Banque Paramètres %1</translation>
</message>
<message>
<location line="+70"/>
<source>Thrust</source>
<translation>Poussée</translation>
</message>
<message>
<location line="+1"/>
<source>Scaling factor</source>
<translation>Facteur d&apos;ajustement</translation>
</message>
<message>
<location line="+95"/>
<source>Input %</source>
<translation>Entrée %</translation>
</message>
<message>
<location line="+5"/>
<source>Output %</source>
<translation>Sortie %</translation>
</message>
</context>
<context>
<name>ModelUavoProxy</name>
<message>
<location filename="../../../src/plugins/opmap/modeluavoproxy.cpp" line="+80"/>
<source>Path Plan Upload Successful</source>
<translation>Téléversement Réussi du Projet de Trajet</translation>
</message>
<message>
<location line="+0"/>
<source>Path plan upload was successful.</source>
<translation>Le téléversement du projet de trajet est réussi.</translation>
</message>
<message>
<location line="+2"/>
<location line="+238"/>
<location filename="../../../src/plugins/opmap/modeluavoproxy.cpp" line="+358"/>
<source>Path Plan Upload Failed</source>
<translation>Échec Téléversement Projet de Trajet</translation>
</message>
<message>
<location line="-238"/>
<source>Failed to upload the path plan !</source>
<translation>Échec du téléversement du projet de trajet !</translation>
</message>
<message>
<location line="+37"/>
<source>Path Plan Download Successful</source>
<translation>Téléchargement Projet de Trajet Réussi</translation>
</message>
<message>
<location line="+0"/>
<source>Path plan download was successful.</source>
<translation>Le téléchargement du projet de trajet est réussi.</translation>
</message>
<message>
<location line="+3"/>
<location line="+190"/>
<location line="-8"/>
<location line="+4"/>
<source>Path Plan Download Failed</source>
<translation>Échec Téléchargement Projet de Trajet</translation>
</message>
<message>
<location line="-194"/>
<source>Failed to download the path plan !</source>
<translation>Échec du téléchargement du projet de trajet !</translation>
<location line="-301"/>
<source>Sending the path plan to the board... </source>
<translation>Envoi du projet de trajet vers la carte... </translation>
</message>
<message>
<location line="+190"/>
<location line="+39"/>
<source>Sending Path Plan Failed!</source>
<translation>Échec Envoi Projet Trajet !</translation>
</message>
<message>
<location line="+0"/>
<source>Failed to send the path plan to the board.</source>
<translation>Échec de l&apos;envoi du projet de trajet.</translation>
</message>
<message>
<location line="+8"/>
<source>Receiving the path plan from the board... </source>
<translation>Réception du projet de trajet depuis la carte... </translation>
</message>
<message>
<location line="+59"/>
<source>Receiving Path Plan Failed!</source>
<translation>Échec Réception Projet Trajet !</translation>
</message>
<message>
<location line="+0"/>
<source>Failed to receive the path plan from the board.</source>
<translation>Échec de la réception du projet de trajet depuis la carte.</translation>
</message>
<message>
<location line="+191"/>
<source>Path plan way point count error !</source>
<translation>Erreur sur le nombre de waypoints dans le projet de trajet !</translation>
</message>
@ -13971,14 +14259,14 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<context>
<name>ConfigVehicleTypeWidget</name>
<message>
<location filename="../../../src/plugins/config/configvehicletypewidget.cpp" line="+130"/>
<location filename="../../../src/plugins/config/configvehicletypewidget.cpp" line="+138"/>
<source>Multirotor</source>
<translation>Multirotor</translation>
</message>
<message>
<location line="+1"/>
<source>Fixed Wing</source>
<translation type="unfinished">Aile</translation>
<translation>Voilure Fixe</translation>
</message>
<message>
<location line="+1"/>
@ -13988,15 +14276,15 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location line="+1"/>
<source>Ground</source>
<translation type="unfinished">Voiture</translation>
<translation>Voiture</translation>
</message>
<message>
<location line="+1"/>
<source>Custom</source>
<translation type="unfinished">Personnalisé</translation>
<translation>Personnalisé</translation>
</message>
<message>
<location line="+273"/>
<location line="+315"/>
<source>http://wiki.openpilot.org/x/44Cf</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/IIBqAQ</translation>
@ -14041,7 +14329,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<context>
<name>OpenPilot::SixPointCalibrationModel</name>
<message>
<location filename="../../../src/plugins/config/calibration/sixpointcalibrationmodel.cpp" line="+59"/>
<location filename="../../../src/plugins/config/calibration/sixpointcalibrationmodel.cpp" line="+60"/>
<source>Place horizontally, nose pointing north and press Save Position...</source>
<translation>Positionner horizontalement, le nez en direction du nord et cliquer sur le bouton Enregistrer Position...</translation>
</message>
@ -14071,7 +14359,7 @@ et même conduire au crash. A utiliser avec prudence.</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"/>
<location line="+19"/>
<source>Place horizontally and press Save Position...</source>
<translation>Positionner horizontalement et cliquer sur le bouton Enregistrer Position...</translation>
</message>
@ -14101,7 +14389,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<translation>Positionner le flanc gauche vers le bas et cliquer sur le bouton Enregistrer Position...</translation>
</message>
<message>
<location line="+44"/>
<location line="+50"/>
<source>Home location not set, please set your home location and retry.</source>
<translation>Position Home non définie, veuillez régler votre position Home et essayez à nouveau.</translation>
</message>
@ -14111,12 +14399,12 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<translation>Étalonnage abandonné !</translation>
</message>
<message>
<location line="+120"/>
<location line="+152"/>
<source>Hold...</source>
<translation>Maintenir en position...</translation>
</message>
<message>
<location line="+214"/>
<location line="+224"/>
<source>Magnetometer calibration completed successfully.</source>
<translation>Étalonnage du magnétomètre terminé avec succès.</translation>
</message>
@ -14276,7 +14564,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<context>
<name>ConfigRevoWidget</name>
<message>
<location filename="../../../src/plugins/config/configrevowidget.cpp" line="+328"/>
<location filename="../../../src/plugins/config/configrevowidget.cpp" line="+329"/>
<source>Temperature: %1°C</source>
<translation>Température : %1°C</translation>
</message>
@ -14291,4 +14579,765 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<translation>Plage d&apos;échantillonnage : %1°C</translation>
</message>
</context>
<context>
<name>AirframeInitialTuningPage</name>
<message>
<location filename="../../../src/plugins/setupwizard/pages/airframeinitialtuningpage.ui"/>
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Initial Tuning&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2,sans-serif&apos;;&quot;&gt;This section of the OpenPilot Wizard allows you to select a set of initial tunning parameters for your airframe. Presented below is a list of common airframe types, select the one that matches your airframe the closest, if unsure select the generic variant.&lt;/span&gt; &lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Réglages de Départ&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2,sans-serif&apos;;&quot;&gt;Cette partie de l&apos;assistant de configuration vous permet de sélectionner des paramètres prédéfinis pour votre appareil. Vous trouverez ci-dessous une liste d&apos;appareils couramment utilisés, sélectionnez-en un qui correspond le mieux à votre appareil ou un modèle générique si vous avez un doute.&lt;/span&gt; &lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Information about the Vehicle in short.</source>
<translation>Résumé d&apos;informations sur le Véhicule.</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp" line="+119"/>
<source>Name of Vehicle: </source>
<translation>Nom du Véhicule : </translation>
</message>
<message>
<location line="+1"/>
<source>Name of Owner: </source>
<translation>Nom du Propriétaire : </translation>
</message>
<message>
<location line="+5"/>
<source>Size: </source>
<translation>Taille : </translation>
</message>
<message>
<location line="+1"/>
<source>Weight: </source>
<translation>Masse : </translation>
</message>
<message>
<location line="+1"/>
<source>Motor(s): </source>
<translation>Moteur(s) : </translation>
</message>
<message>
<location line="+1"/>
<source>ESC(s): </source>
<translation>Esc(s) : </translation>
</message>
<message>
<location line="+1"/>
<source>Servo(s): </source>
<translation>Servo(s) : </translation>
</message>
<message>
<location line="+1"/>
<source>Battery: </source>
<translation>Batterie : </translation>
</message>
<message>
<location line="+1"/>
<source>Propellers(s): </source>
<translation>Hélice(s) : </translation>
</message>
<message>
<location line="+1"/>
<source>Controller: </source>
<translation>Carte Contrôleur : </translation>
</message>
<message>
<location line="+1"/>
<source>Comments: </source>
<translation>Commentaires : </translation>
</message>
<message>
<location line="+3"/>
<source>No vehicle selected!</source>
<translation>Pas de véhicule sélectionné !</translation>
</message>
<message>
<location line="+48"/>
<source>None</source>
<translation>Aucun</translation>
</message>
</context>
<context>
<name>EscPage</name>
<message>
<location filename="../../../src/plugins/setupwizard/pages/escpage.ui"/>
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot Output Signal Configuration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To set an optimal configuration of the output signals powering your motors, the wizard needs to know what type of Electronic Speed Controllers (ESCs) you will use and what their capabilities are.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Please select one of the options below. If you are unsure about the capabilities of your ESCs, just leave the default option selected and continue the wizard.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Configuration OpenPilot des Signaux de Sortie&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Afin de régler de manière optimale la configuration des signaux de sortie qui pilotent vos moteurs, l&apos;assistant doit connaître le type de contrôleur de vitesse (ESC) utilisé et leurs capacités.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Veuillez sélectionner une des options ci-dessous. En cas de doute sur les possibilités de vos ESC, laissez l&apos;option sélectionnée par défaut et continuez l&apos;assistant.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Standard ESC 50Hz</source>
<translation>Variateur Standard 50Hz</translation>
</message>
<message>
<location/>
<source>Standard ESC</source>
<translation>Variateur Standard</translation>
</message>
<message>
<location/>
<source>Turbo PWM ESC 400Hz</source>
<translatorcomment>or 500Hz ?</translatorcomment>
<translation type="unfinished">Variateur Turbo PWM 400Hz</translation>
</message>
<message>
<location/>
<source>Rapid ESC</source>
<translation>ESC Rapide</translation>
</message>
</context>
<context>
<name>SelectionPage</name>
<message>
<location filename="../../../src/plugins/setupwizard/pages/selectionpage.ui"/>
<source>WizardPage</source>
<translation type="unfinished">Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>placeholder_text</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>TextLabel</source>
<translation type="unfinished"></translation>
</message>
<message>
<location/>
<source>Select:</source>
<translation type="unfinished">Sélectionner :</translation>
</message>
</context>
<context>
<name>ServoPage</name>
<message>
<location filename="../../../src/plugins/setupwizard/pages/servopage.ui"/>
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<source>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot Output Signal Configuration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To set an optimal configuration of the output signals powering your servos, the wizard needs to know what type of servos you will use and what their capabilities are.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Please select one of the options below. If you are unsure about the capabilities of your servos, just leave the default option selected and continue the wizard.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Configuration OpenPilot des Signaux de Sortie&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Afin de régler de manière optimale la configuration des signaux de sortie qui pilotent vos servos, l&apos;assistant doit connaître le type de servo utilisé et leurs capacités.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Veuillez sélectionner une des options ci-dessous. En cas de doute sur les possibilités de vos servos, laissez l&apos;option sélectionnée par défaut et continuez l&apos;assistant.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>Analog Servo 50Hz</source>
<translation>Servo Analogique 50Hz</translation>
</message>
<message>
<location/>
<source>Analog Servos</source>
<translation>Servo Analogique</translation>
</message>
<message>
<location/>
<source>Digital Servo 333Hz</source>
<translation>Servo Digital 333Hz</translation>
</message>
<message>
<location/>
<source>Digital Servos</source>
<translation>Servo Digital</translation>
</message>
</context>
<context>
<name>VehicleTemplateExportDialog</name>
<message>
<location filename="../../../src/plugins/setupwizard/vehicletemplateexportdialog.ui"/>
<source>Vehicle Template Export</source>
<translation>Exportation Modèle Véhicule</translation>
</message>
<message>
<location/>
<source>Weight:</source>
<translation>Masse :</translation>
</message>
<message>
<location/>
<source>Size and angle</source>
<translation>Taille et pas</translation>
</message>
<message>
<location/>
<source>Battery:</source>
<translation>Batterie :</translation>
</message>
<message>
<location/>
<source>Size of the vehicle in mm</source>
<translation>Taille du véhicule en mm</translation>
</message>
<message>
<location/>
<source>Motor:</source>
<translation>Moteur :</translation>
</message>
<message>
<location/>
<source>Name:</source>
<translation>Nom :</translation>
</message>
<message>
<location/>
<source>Servo:</source>
<translation>Servo :</translation>
</message>
<message>
<location/>
<source>Brand and name</source>
<translation>Nom et marque</translation>
</message>
<message>
<location/>
<source>Your name</source>
<translation>Votre nom</translation>
</message>
<message>
<location/>
<source>Propeller:</source>
<translation>Hélice :</translation>
</message>
<message>
<location/>
<source>Forum name:</source>
<translation>Pseudo :</translation>
</message>
<message>
<location/>
<source>The name of the vehicle, brand etc</source>
<translation>Nom du véhicule, marque, etc</translation>
</message>
<message>
<location/>
<source>Owner:</source>
<translation>Propriétaire :</translation>
</message>
<message>
<location/>
<source>Brand, size and Kv</source>
<translation>Marque, taille et Kv</translation>
</message>
<message>
<location/>
<source>Size:</source>
<translation>Taille :</translation>
</message>
<message>
<location/>
<source>How many cells etc?</source>
<translation>Nb cellules, capacité ?</translation>
</message>
<message>
<location/>
<source>Controller:</source>
<translation>Carte Contrôleur :</translation>
</message>
<message>
<location/>
<source>ESC:</source>
<translation>ESC :</translation>
</message>
<message>
<location/>
<source>None</source>
<translation>Aucun</translation>
</message>
<message>
<location/>
<source>CC</source>
<translation></translation>
</message>
<message>
<location/>
<source>CC3D</source>
<translation></translation>
</message>
<message>
<location/>
<source>Atom</source>
<translation></translation>
</message>
<message>
<location/>
<source>Revolution</source>
<translation></translation>
</message>
<message>
<location/>
<source>Nano</source>
<translation></translation>
</message>
<message>
<location/>
<source>Type:</source>
<translation>Type :</translation>
</message>
<message>
<location/>
<source>Forum nickname</source>
<translation>Nom sur le forum</translation>
</message>
<message>
<location/>
<source>Weight in grams</source>
<translation>Masse en grammes</translation>
</message>
<message>
<location/>
<source>Comment:</source>
<translation>Commentaire :</translation>
</message>
<message>
<location/>
<source>Put comments here that doesn&apos;t fit in the categories above</source>
<translation>Indiquez ici les commentaires ne correspondant pas aux catégories ci-dessus</translation>
</message>
<message>
<location/>
<source>Photo:</source>
<translation>Photo :</translation>
</message>
<message>
<location/>
<source>Photo will be scaled to 500x500px</source>
<translation>La photo sera ajustée à une taille de 500x500 pixels</translation>
</message>
<message>
<location/>
<source>Select Image...</source>
<translation>Sélectionner image...</translation>
</message>
<message>
<location/>
<source>Cancel</source>
<translation>Annuler</translation>
</message>
<message>
<location/>
<source>Ok</source>
<translation></translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/vehicletemplateexportdialog.cpp" line="+87"/>
<source>Fixed Wing - Aileron</source>
<translation>Voilure Fixe - Aileron</translation>
</message>
<message>
<location line="+5"/>
<source>Fixed Wing - Elevon</source>
<translation>Voilure Fixe - Elevon</translation>
</message>
<message>
<location line="+5"/>
<source>Fixed Wing - V-Tail</source>
<translation>Voilure Fixe - V-Tail</translation>
</message>
<message>
<location line="+5"/>
<source>Helicopter</source>
<translation>Hélicoptère</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Tricopter</source>
<translation>Multirotor - Tricoptère</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Quadrocopter X</source>
<translation>Multirotor - Quadricoptère X</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Quadrocopter +</source>
<translation>Multirotor - Quadricoptère +</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Octocopter V</source>
<translation>Multirotor - Octocoptère V</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Octocopter X8X</source>
<translation>Multirotor - Octocoptère X8X</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Octocopter X8+</source>
<translation>Multirotor - Octocoptère X8+</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Octocopter +</source>
<translation>Multirotor - Octocoptère +</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Octocopter X</source>
<translation>Multirotor - Octocoptère X</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Hexacopter X</source>
<translation>Multirotor - Hexacoptère X</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Hexacopter Y6</source>
<translation>Multirotor - Hexacoptère Y6</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Hexacopter +</source>
<translation>Multirotor - Hexacoptère +</translation>
</message>
<message>
<location line="+4"/>
<source>Unsupported</source>
<translation>Non Supporté</translation>
</message>
<message>
<location line="+65"/>
<source>Settings were exported to
%1</source>
<translation>Les paramètres ont é exportés vers
%1</translation>
</message>
<message>
<location line="+2"/>
<source>Settings could not be exported to
%1.
Please try again.</source>
<translation>Les paramètres n&apos;ont pas é exportés vers
%1.
Veuillez essayer à nouveau.</translation>
</message>
<message>
<location line="+8"/>
<source>Import Image</source>
<translation>Importer Image</translation>
</message>
<message>
<location line="+0"/>
<source>Images (*.png *.jpg)</source>
<translation></translation>
</message>
</context>
<context>
<name>AirSpeedPage</name>
<message>
<location filename="../../../src/plugins/setupwizard/pages/airspeedpage.cpp" line="+65"/>
<source>OpenPilot Airspeed Sensor Selection</source>
<translation>Sélection Capteur Vitesse Air OpenPilot</translation>
</message>
<message>
<location line="+1"/>
<source>This part of the wizard will help you select and configure a way to obtain airspeed data. OpenPilot support three methods to achieve this, one is a software estimation technique and the other two utilize hardware sensors.
Note: if previously selected input combinations use the Flexi-port for input, only estimated airspeed will be available.
</source>
<translation>Cette partie de l&apos;assistant va vous aider à sélectionner et configurer une solution pour obtenir les données de vitesse air. OpenPilot supporte trois méthodes pour l&apos;obtenir, une par estimation logicielle et deux à partir de capteurs externes.
A Noter : Si vous avez précédemment sélectionné une entrée par le Flexi-port, seule l&apos;estimation logicelle sera disponnible.</translation>
</message>
<message>
<location line="+5"/>
<source>Estimated</source>
<translation>Estimée</translation>
</message>
<message>
<location line="+1"/>
<source>This option uses an intelligent estimation algorithm which utilizes the OpenPilot INS/GPS to estimate wind speed and subtract it from ground speed obtained from the GPS.
This solution is highly accurate in normal level flight with the drawback of being less accurate in rapid altitude changes.
</source>
<translation>Cette option utilise un algorithme d&apos;estimation intelligent basé sur OpenPilot INS/GPS pour estimer la vitesse du vent et soustrait la vitesse sol obtenue par le GPS.
Cette solution est très précise en vol normal avec l&apos;inconvénient d&apos;être moins précis lors de changements rapides d&apos;altitude.
</translation>
</message>
<message>
<location line="+7"/>
<source>EagleTree</source>
<translation>EagleTree</translation>
</message>
<message>
<location line="+1"/>
<source>Select this option to use the Airspeed MicroSensor V3 from EagleTree, this is an accurate airspeed sensor that includes on-board Temperature Compensation.
Selecting this option will set your board&apos;s Flexi-Port in to I2C mode.</source>
<translation>Sélectionner cette option pour utiliser le capteur de vitesse air v3 de chez EagleTree, c&apos;est une capteur précis qui inclut une compensation en température.
Le choix de cette option va paramétrer le Flexi-Port de votre carte en mode I2C.</translation>
</message>
<message>
<location line="+6"/>
<source>MS4525 Based</source>
<translation>Basé sur MS4525</translation>
</message>
<message>
<location line="+1"/>
<source>Select this option to use an airspeed sensor based on the MS4525DO pressure transducer from Measurement Specialties. This includes the PixHawk sensor and their clones.
Selecting this option will set your board&apos;s Flexi-Port in to I2C mode.</source>
<translation>Sléectionnez cette option pour utiliser un capteur basé sur le transducteur de pression MS4525DO de &quot;Measurement Specialties&quot;. Cette option inclut le capteur PixHawk et ses clones.
Le choix de cette option va paramétrer le Flexi-Port de votre carte en mode I2C.</translation>
</message>
</context>
<context>
<name>GpsPage</name>
<message>
<location filename="../../../src/plugins/setupwizard/pages/gpspage.cpp" line="+54"/>
<source>OpenPilot GPS Selection</source>
<translation>Sélection GPS OpenPilot</translation>
</message>
<message>
<location line="+1"/>
<source>Please select the type of GPS you wish to use. As well as OpenPilot hardware, 3rd party GPSs are supported also, although please note that performance could be less than optimal as not all GPSs are created equal.
Note: NMEA only GPSs perform poorly on VTOL aircraft and are not recommended for Helis and MultiRotors.
Please select your GPS type data below:</source>
<translation>Veuillez sélectionner le type de GPS que vous souhaitez utiliser. Aussi bien que le matériel OpenPilot, d&apos;autres GPS sont également supportés mais vous remarquerez que les performances peuvent-être moindres car tous les GPS ne sont fabriqués de la même manière.
A noter : Les GPS NMEA donnent des performances réduites sur des appreils VTOL et ne sont pas recommandés sur des Multirotors ou Hélicoptères.
Veuillez sélectionner votre type de GPS ci-dessous :</translation>
</message>
<message>
<location line="+6"/>
<source>Disabled</source>
<translation>Désactivé</translation>
</message>
<message>
<location line="+1"/>
<source>GPS Features are not to be enabled</source>
<translation>Les possibilités GPS ne seront pas activées</translation>
</message>
<message>
<location line="+4"/>
<source>OpenPilot Platinum</source>
<translation></translation>
</message>
<message>
<location line="+1"/>
<source>Select this option to use the OpenPilot Platinum GPS with integrated Magnetometer and Microcontroller connected to the Main Port of your controller.
Note: for the OpenPilot v8 GPS please select the U-Blox option.</source>
<translation>Sélectionnez cette option pour utiliser le GPS OpenPilot Platinum avec Magnétomètre et Microcontrôleur intégré connecté sur le Main Port de votre contrôleur.
A noter : Pour le GPS OpenPilot v8, veuillez choisir l&apos;option GPS U-Blox.</translation>
</message>
<message>
<location line="+6"/>
<source>U-Blox Based</source>
<translation>Basé sur U-Blox</translation>
</message>
<message>
<location line="+1"/>
<source>Select this option for the OpenPilot V8 GPS or generic U-Blox chipset GPSs connectedto the Main Port of your controller.</source>
<translation>Sélectionnez cette option pour utiliser le GPS OpenPilot v8 ou un GPS U-Blox générique connecté sur le Main Port de votre contrôleur.</translation>
</message>
<message>
<location line="+5"/>
<source>NMEA Based</source>
<translation>Basé sur NMEA</translation>
</message>
<message>
<location line="+1"/>
<source>Select this option for a generic NMEA based GPS connected to the Main Port of yourcontroller.</source>
<translation>Sélectionnez cette option pour utiliser un GPS NMEA générique connecté sur le Main Port de votre contrôleur.</translation>
</message>
</context>
<context>
<name>EscCalibrationPage</name>
<message>
<location filename="../../../src/plugins/setupwizard/pages/esccalibrationpage.ui"/>
<source>WizardPage</source>
<translation>Page d&apos;Assistant</translation>
</message>
<message>
<location/>
<location filename="../../../src/plugins/setupwizard/pages/esccalibrationpage.cpp" line="+113"/>
<source>Start</source>
<translation>Démarrer</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/esccalibrationpage.cpp" line="-12"/>
<source>Stop</source>
<translation>Arrêter</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/esccalibrationpage.ui"/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p align=&quot;center&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot ESC Calibration Procedure&lt;/span&gt;&lt;/p&gt;&lt;p&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;As you have selected to use a MultiRotor and Fast / Flashed ESCs, we need to calibrate the endpoints of these ESCs so they can see the full throttle range sent from the flight controller. &lt;/span&gt;&lt;/p&gt;&lt;p&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;This part of the wizard will tell you to connect the battery to your aircraft, before doing so you absolutely &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600; color:#f30f1d;&quot;&gt;must remove the propellers from all motors&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;. &lt;/span&gt;&lt;/p&gt;&lt;p&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The steps to perform this calibration are as follows:&lt;/span&gt;&lt;/p&gt;&lt;p&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;1. Confirm all safety questions&lt;br/&gt;2. Press the Start button when it becomes enabled&lt;br/&gt;3. Connect the battery to your airframe&lt;br/&gt;4. Wait for ESC calibration beep(s)&lt;br/&gt;5. Press the Stop button&lt;br/&gt;6. Wait for ESC confirmation beep(s)&lt;br/&gt;7. Disconnect battery&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p align=&quot;center&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;Procédure OpenPilot Calibration ESC&lt;/span&gt;&lt;/p&gt;&lt;p&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Comme vous avez choisi d&apos;utiliser un MultiRotor avec des ESC rapides / ESC flashés, il faut à présent définir les limites maxi/mini de ces ESC pour qu&apos;ils puissent interpréter correctement les signaux de gaz envoyés par la carte contrôleur. &lt;/span&gt;&lt;/p&gt;&lt;p&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Cette partie de l&apos;assistant vous demandera de connecter la batterie sur votre appareil mais avant de le faire vous devez &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600; color:#f30f1d;&quot;&gt;impérativement retirer toutes les hélices de tous les moteurs&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;. &lt;/span&gt;&lt;/p&gt;&lt;p&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Les étapes pour effectuer cet étalonnage sont les suivantes :&lt;/span&gt;&lt;/p&gt;&lt;p&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;1. Valider les questions de sécurité,&lt;br/&gt;2. Appuyer sur le bouton Démarrer lorsqu&apos;il devient actif,&lt;br/&gt;3. Connecter la batterie sur l&apos;appareil,&lt;br/&gt;4. Attendre le(s) bip(s) de calibration de l&apos;ESC,&lt;br/&gt;5. Appuyer sur le bouton Arrêter,&lt;br/&gt;6. Attendre le(s) bip(s) de confirmation de l&apos;ESC,&lt;br/&gt;7. Débrancher la batterie.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>I have removed ALL propellers from ALL motors of my vehicle.</source>
<translation>J&apos;ai enlevé TOUTES les hélices de TOUS les moteurs de mon appareil.</translation>
</message>
<message>
<location/>
<source>The vehicle is NOT powered by any external power source but USB</source>
<translation>L&apos;appareil N&apos;EST PAS BRANCHE sur une source d&apos;alimentation externe
mais uniquement sur port USB</translation>
</message>
<message>
<location/>
<source>I confirm I have read and understood the above instructions in full</source>
<translation>Je confirme avoir lu et compris les instructions ci-dessus en totalité</translation>
</message>
</context>
<context>
<name>UAVObjectBrowserWidget</name>
<message>
<location filename="../../../src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp" line="+294"/>
<location line="+17"/>
<source>Name</source>
<translation>Nom</translation>
</message>
<message>
<location line="-15"/>
<source>Category</source>
<translation>Catégorie</translation>
</message>
<message>
<location line="+2"/>
<location line="+15"/>
<source>Type</source>
<translation>Type</translation>
</message>
<message>
<location line="-14"/>
<source>Metadata</source>
<translation>Métadonnées</translation>
</message>
<message>
<location line="+0"/>
<source>Setting</source>
<translation>Paramètres</translation>
</message>
<message>
<location line="+0"/>
<source>Data</source>
<translation>Données</translation>
</message>
<message>
<location line="+1"/>
<source>Size</source>
<translation>Taille</translation>
</message>
<message>
<location line="+2"/>
<location line="+55"/>
<source>Description</source>
<translation>Description</translation>
</message>
<message>
<location line="-53"/>
<source>Multi</source>
<translation type="unfinished"></translation>
</message>
<message>
<location line="+1"/>
<source>No</source>
<translation>Non</translation>
</message>
<message>
<location line="+0"/>
<source>Yes</source>
<translation>Oui</translation>
</message>
<message>
<location line="+1"/>
<source>Fields</source>
<translation>Champs</translation>
</message>
<message>
<location line="+11"/>
<source>Unit</source>
<translation>Unité</translation>
</message>
<message>
<location line="+4"/>
<source>Options</source>
<translation>Options</translation>
</message>
<message>
<location line="+14"/>
<source>Elements</source>
<translation type="unfinished">Eléments</translation>
</message>
<message>
<location line="+17"/>
<source>Limits</source>
<translation type="unfinished">Limites</translation>
</message>
</context>
</TS>

View File

@ -0,0 +1,559 @@
/*
Copyright 2012, Robert Knight
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
*/
#include "mustache.h"
#include <QtCore/QDebug>
#include <QtCore/QFile>
#include <QtCore/QStringList>
#include <QtCore/QTextStream>
using namespace Mustache;
QString Mustache::renderTemplate(const QString & templateString, const QVariantHash & args)
{
Mustache::QtVariantContext context(args);
Mustache::Renderer renderer;
return renderer.render(templateString, &context);
}
QString escapeHtml(const QString & input)
{
QString escaped(input);
for (int i = 0; i < escaped.count();) {
const char *replacement = 0;
ushort ch = escaped.at(i).unicode();
if (ch == '&') {
replacement = "&amp;";
} else if (ch == '<') {
replacement = "&lt;";
} else if (ch == '>') {
replacement = "&gt;";
} else if (ch == '"') {
replacement = "&quot;";
}
if (replacement) {
escaped.replace(i, 1, QLatin1String(replacement));
i += strlen(replacement);
} else {
++i;
}
}
return escaped;
}
QString unescapeHtml(const QString & escaped)
{
QString unescaped(escaped);
unescaped.replace(QLatin1String("&lt;"), QLatin1String("<"));
unescaped.replace(QLatin1String("&gt;"), QLatin1String(">"));
unescaped.replace(QLatin1String("&amp;"), QLatin1String("&"));
unescaped.replace(QLatin1String("&quot;"), QLatin1String("\""));
return unescaped;
}
Context::Context(PartialResolver *resolver)
: m_partialResolver(resolver)
{}
PartialResolver *Context::partialResolver() const
{
return m_partialResolver;
}
QString Context::partialValue(const QString & key) const
{
if (!m_partialResolver) {
return QString();
}
return m_partialResolver->getPartial(key);
}
bool Context::canEval(const QString &) const
{
return false;
}
QString Context::eval(const QString & key, const QString & _template, Renderer *renderer)
{
Q_UNUSED(key);
Q_UNUSED(_template);
Q_UNUSED(renderer);
return QString();
}
QtVariantContext::QtVariantContext(const QVariant & root, PartialResolver *resolver)
: Context(resolver)
{
m_contextStack << root;
}
QVariant variantMapValue(const QVariant & value, const QString & key)
{
if (value.userType() == QVariant::Map) {
return value.toMap().value(key);
} else {
return value.toHash().value(key);
}
}
QVariant variantMapValueForKeyPath(const QVariant & value, const QStringList keyPath)
{
if (keyPath.count() > 1) {
QVariant firstValue = variantMapValue(value, keyPath.first());
return firstValue.isNull() ? QVariant() : variantMapValueForKeyPath(firstValue, keyPath.mid(1));
} else if (!keyPath.isEmpty()) {
return variantMapValue(value, keyPath.first());
}
return QVariant();
}
QVariant QtVariantContext::value(const QString & key) const
{
if (key == "." && !m_contextStack.isEmpty()) {
return m_contextStack.last();
}
QStringList keyPath = key.split(".");
for (int i = m_contextStack.count() - 1; i >= 0; i--) {
QVariant value = variantMapValueForKeyPath(m_contextStack.at(i), keyPath);
if (!value.isNull()) {
return value;
}
}
return QVariant();
}
bool QtVariantContext::isFalse(const QString & key) const
{
QVariant value = this->value(key);
switch (value.userType()) {
case QVariant::Bool:
return !value.toBool();
case QVariant::List:
return value.toList().isEmpty();
case QVariant::Hash:
return value.toHash().isEmpty();
case QVariant::Map:
return value.toMap().isEmpty();
default:
return value.toString().isEmpty();
}
}
QString QtVariantContext::stringValue(const QString & key) const
{
if (isFalse(key)) {
return QString();
}
return value(key).toString();
}
void QtVariantContext::push(const QString & key, int index)
{
QVariant mapItem = value(key);
if (index == -1) {
m_contextStack << mapItem;
} else {
QVariantList list = mapItem.toList();
m_contextStack << list.value(index, QVariant());
}
}
void QtVariantContext::pop()
{
m_contextStack.pop();
}
int QtVariantContext::listCount(const QString & key) const
{
if (value(key).userType() == QVariant::List) {
return value(key).toList().count();
}
return 0;
}
bool QtVariantContext::canEval(const QString & key) const
{
return value(key).canConvert<fn_t>();
}
QString QtVariantContext::eval(const QString & key, const QString & _template, Renderer *renderer)
{
QVariant fn = value(key);
if (fn.isNull()) {
return QString();
}
return fn.value<fn_t>() (_template, renderer, this);
}
PartialMap::PartialMap(const QHash<QString, QString> & partials)
: m_partials(partials)
{}
QString PartialMap::getPartial(const QString & name)
{
return m_partials.value(name);
}
PartialFileLoader::PartialFileLoader(const QString & basePath)
: m_basePath(basePath)
{}
QString PartialFileLoader::getPartial(const QString & name)
{
if (!m_cache.contains(name)) {
QString path = m_basePath + '/' + name + ".mustache";
QFile file(path);
if (file.open(QIODevice::ReadOnly)) {
QTextStream stream(&file);
m_cache.insert(name, stream.readAll());
}
}
return m_cache.value(name);
}
Renderer::Renderer()
: m_errorPos(-1)
, m_defaultTagStartMarker("{{")
, m_defaultTagEndMarker("}}")
{}
QString Renderer::error() const
{
return m_error;
}
int Renderer::errorPos() const
{
return m_errorPos;
}
QString Renderer::errorPartial() const
{
return m_errorPartial;
}
QString Renderer::render(const QString & _template, Context *context)
{
m_error.clear();
m_errorPos = -1;
m_errorPartial.clear();
m_tagStartMarker = m_defaultTagStartMarker;
m_tagEndMarker = m_defaultTagEndMarker;
return render(_template, 0, _template.length(), context);
}
QString Renderer::render(const QString & _template, int startPos, int endPos, Context *context)
{
QString output;
int lastTagEnd = startPos;
while (m_errorPos == -1) {
Tag tag = findTag(_template, lastTagEnd, endPos);
if (tag.type == Tag::Null) {
output += _template.midRef(lastTagEnd, endPos - lastTagEnd);
break;
}
output += _template.midRef(lastTagEnd, tag.start - lastTagEnd);
switch (tag.type) {
case Tag::Value:
{
QString value = context->stringValue(tag.key);
if (tag.escapeMode == Tag::Escape) {
value = escapeHtml(value);
} else if (tag.escapeMode == Tag::Unescape) {
value = unescapeHtml(value);
}
output += value;
lastTagEnd = tag.end;
}
break;
case Tag::SectionStart:
{
Tag endTag = findEndTag(_template, tag, endPos);
if (endTag.type == Tag::Null) {
if (m_errorPos == -1) {
setError("No matching end tag found for section", tag.start);
}
} else {
int listCount = context->listCount(tag.key);
if (listCount > 0) {
for (int i = 0; i < listCount; i++) {
context->push(tag.key, i);
output += render(_template, tag.end, endTag.start, context);
context->pop();
}
} else if (context->canEval(tag.key)) {
output += context->eval(tag.key, _template.mid(tag.end, endTag.start - tag.end), this);
} else if (!context->isFalse(tag.key)) {
context->push(tag.key);
output += render(_template, tag.end, endTag.start, context);
context->pop();
}
lastTagEnd = endTag.end;
}
}
break;
case Tag::InvertedSectionStart:
{
Tag endTag = findEndTag(_template, tag, endPos);
if (endTag.type == Tag::Null) {
if (m_errorPos == -1) {
setError("No matching end tag found for inverted section", tag.start);
}
} else {
if (context->isFalse(tag.key)) {
output += render(_template, tag.end, endTag.start, context);
}
lastTagEnd = endTag.end;
}
}
break;
case Tag::SectionEnd:
setError("Unexpected end tag", tag.start);
lastTagEnd = tag.end;
break;
case Tag::Partial:
{
QString tagStartMarker = m_tagStartMarker;
QString tagEndMarker = m_tagEndMarker;
m_tagStartMarker = m_defaultTagStartMarker;
m_tagEndMarker = m_defaultTagEndMarker;
m_partialStack.push(tag.key);
QString partial = context->partialValue(tag.key);
output += render(partial, 0, partial.length(), context);
lastTagEnd = tag.end;
m_partialStack.pop();
m_tagStartMarker = tagStartMarker;
m_tagEndMarker = tagEndMarker;
}
break;
case Tag::SetDelimiter:
lastTagEnd = tag.end;
break;
case Tag::Comment:
lastTagEnd = tag.end;
break;
case Tag::Null:
break;
}
}
return output;
}
void Renderer::setError(const QString & error, int pos)
{
Q_ASSERT(!error.isEmpty());
Q_ASSERT(pos >= 0);
m_error = error;
m_errorPos = pos;
if (!m_partialStack.isEmpty()) {
m_errorPartial = m_partialStack.top();
}
}
Tag Renderer::findTag(const QString & content, int pos, int endPos)
{
int tagStartPos = content.indexOf(m_tagStartMarker, pos);
if (tagStartPos == -1 || tagStartPos >= endPos) {
return Tag();
}
int tagEndPos = content.indexOf(m_tagEndMarker, tagStartPos + m_tagStartMarker.length());
if (tagEndPos == -1) {
return Tag();
}
tagEndPos += m_tagEndMarker.length();
Tag tag;
tag.type = Tag::Value;
tag.start = tagStartPos;
tag.end = tagEndPos;
pos = tagStartPos + m_tagStartMarker.length();
endPos = tagEndPos - m_tagEndMarker.length();
QChar typeChar = content.at(pos);
if (typeChar == '#') {
tag.type = Tag::SectionStart;
tag.key = readTagName(content, pos + 1, endPos);
} else if (typeChar == '^') {
tag.type = Tag::InvertedSectionStart;
tag.key = readTagName(content, pos + 1, endPos);
} else if (typeChar == '/') {
tag.type = Tag::SectionEnd;
tag.key = readTagName(content, pos + 1, endPos);
} else if (typeChar == '!') {
tag.type = Tag::Comment;
} else if (typeChar == '>') {
tag.type = Tag::Partial;
tag.key = readTagName(content, pos + 1, endPos);
} else if (typeChar == '=') {
tag.type = Tag::SetDelimiter;
readSetDelimiter(content, pos + 1, tagEndPos - m_tagEndMarker.length());
} else {
if (typeChar == '&') {
tag.escapeMode = Tag::Unescape;
++pos;
} else if (typeChar == '{') {
tag.escapeMode = Tag::Raw;
++pos;
int endTache = content.indexOf('}', pos);
if (endTache == tag.end - m_tagEndMarker.length()) {
++tag.end;
} else {
endPos = endTache;
}
}
tag.type = Tag::Value;
tag.key = readTagName(content, pos, endPos);
}
if (tag.type != Tag::Value) {
expandTag(tag, content);
}
return tag;
}
QString Renderer::readTagName(const QString & content, int pos, int endPos)
{
QString name;
name.reserve(endPos - pos);
while (content.at(pos).isSpace()) {
++pos;
}
while (!content.at(pos).isSpace() && pos < endPos) {
name += content.at(pos);
++pos;
}
return name;
}
void Renderer::readSetDelimiter(const QString & content, int pos, int endPos)
{
QString startMarker;
QString endMarker;
while (content.at(pos).isSpace() && pos < endPos) {
++pos;
}
while (!content.at(pos).isSpace() && pos < endPos) {
if (content.at(pos) == '=') {
setError("Custom delimiters may not contain '='.", pos);
return;
}
startMarker += content.at(pos);
++pos;
}
while (content.at(pos).isSpace() && pos < endPos) {
++pos;
}
while (!content.at(pos).isSpace() && pos < endPos - 1) {
if (content.at(pos) == '=') {
setError("Custom delimiters may not contain '='.", pos);
return;
}
endMarker += content.at(pos);
++pos;
}
m_tagStartMarker = startMarker;
m_tagEndMarker = endMarker;
}
Tag Renderer::findEndTag(const QString & content, const Tag & startTag, int endPos)
{
int tagDepth = 1;
int pos = startTag.end;
while (true) {
Tag nextTag = findTag(content, pos, endPos);
if (nextTag.type == Tag::Null) {
return nextTag;
} else if (nextTag.type == Tag::SectionStart || nextTag.type == Tag::InvertedSectionStart) {
++tagDepth;
} else if (nextTag.type == Tag::SectionEnd) {
--tagDepth;
if (tagDepth == 0) {
if (nextTag.key != startTag.key) {
setError("Tag start/end key mismatch", nextTag.start);
return Tag();
}
return nextTag;
}
}
pos = nextTag.end;
}
return Tag();
}
void Renderer::setTagMarkers(const QString & startMarker, const QString & endMarker)
{
m_defaultTagStartMarker = startMarker;
m_defaultTagEndMarker = endMarker;
}
void Renderer::expandTag(Tag & tag, const QString & content)
{
int start = tag.start;
int end = tag.end;
// Move start to beginning of line.
while (start > 0 && content.at(start - 1) != QLatin1Char('\n')) {
--start;
if (!content.at(start).isSpace()) {
return; // Not standalone.
}
}
// Move end to one past end of line.
while (end <= content.size() && content.at(end - 1) != QLatin1Char('\n')) {
if (end < content.size() && !content.at(end).isSpace()) {
return; // Not standalone.
}
++end;
}
tag.start = start;
tag.end = end;
}

View File

@ -0,0 +1,266 @@
/*
Copyright 2012, Robert Knight
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
*/
#pragma once
#include <QtCore/QStack>
#include <QtCore/QString>
#include <QtCore/QVariant>
#include "utils_global.h"
#if __cplusplus >= 201103L
#include <functional> /* for std::function */
#endif
namespace Mustache {
class PartialResolver;
class Renderer;
/** Context is an interface that Mustache::Renderer::render() uses to
* fetch substitutions for template tags.
*/
class QTCREATOR_UTILS_EXPORT Context {
public:
/** Create a context. @p resolver is used to fetch the expansions for any {{>partial}} tags
* which appear in a template.
*/
explicit Context(PartialResolver *resolver = 0);
virtual ~Context() {}
/** Returns a string representation of the value for @p key in the current context.
* This is used to replace a Mustache value tag.
*/
virtual QString stringValue(const QString & key) const = 0;
/** Returns true if the value for @p key is 'false' or an empty list.
* 'False' values typically include empty strings, the boolean value false etc.
*
* When processing a section Mustache tag, the section is not rendered if the key
* is false, or for an inverted section tag, the section is only rendered if the key
* is false.
*/
virtual bool isFalse(const QString & key) const = 0;
/** Returns the number of items in the list value for @p key or 0 if
* the value for @p key is not a list.
*/
virtual int listCount(const QString & key) const = 0;
/** Set the current context to the value for @p key.
* If index is >= 0, set the current context to the @p index'th value
* in the list value for @p key.
*/
virtual void push(const QString & key, int index = -1) = 0;
/** Exit the current context. */
virtual void pop() = 0;
/** Returns the partial template for a given @p key. */
QString partialValue(const QString & key) const;
/** Returns the partial resolver passed to the constructor. */
PartialResolver *partialResolver() const;
/** Returns true if eval() should be used to render section tags using @p key.
* If canEval() returns true for a key, the renderer will pass the literal, unrendered
* block of text for the section to eval() and replace the section with the result.
*
* canEval() and eval() are equivalents for callable objects (eg. lambdas) in other
* Mustache implementations.
*
* The default implementation always returns false.
*/
virtual bool canEval(const QString & key) const;
/** Callback used to render a template section with the given @p key.
* @p renderer will substitute the original section tag with the result of eval().
*
* The default implementation returns an empty string.
*/
virtual QString eval(const QString & key, const QString & _template, Renderer *renderer);
private:
PartialResolver *m_partialResolver;
};
/** A context implementation which wraps a QVariantHash or QVariantMap. */
class QTCREATOR_UTILS_EXPORT QtVariantContext : public Context {
public:
/** Construct a QtVariantContext which wraps a dictionary in a QVariantHash
* or a QVariantMap.
*/
#if __cplusplus >= 201103L
typedef std::function<QString(const QString &, Mustache::Renderer *, Mustache::Context *)> fn_t;
#else
typedef QString (*fn_t)(const QString &, Mustache::Renderer *, Mustache::Context *);
#endif
explicit QtVariantContext(const QVariant & root, PartialResolver *resolver = 0);
virtual QString stringValue(const QString & key) const;
virtual bool isFalse(const QString & key) const;
virtual int listCount(const QString & key) const;
virtual void push(const QString & key, int index = -1);
virtual void pop();
virtual bool canEval(const QString & key) const;
virtual QString eval(const QString & key, const QString & _template, Mustache::Renderer *renderer);
private:
QVariant value(const QString & key) const;
QStack<QVariant> m_contextStack;
};
/** Interface for fetching template partials. */
class QTCREATOR_UTILS_EXPORT PartialResolver {
public:
virtual ~PartialResolver() {}
/** Returns the partial template with a given @p name. */
virtual QString getPartial(const QString & name) = 0;
};
/** A simple partial fetcher which returns templates from a map of (partial name -> template)
*/
class QTCREATOR_UTILS_EXPORT PartialMap : public PartialResolver {
public:
explicit PartialMap(const QHash<QString, QString> & partials);
virtual QString getPartial(const QString & name);
private:
QHash<QString, QString> m_partials;
};
/** A partial fetcher when loads templates from '<name>.mustache' files
* in a given directory.
*
* Once a partial has been loaded, it is cached for future use.
*/
class QTCREATOR_UTILS_EXPORT PartialFileLoader : public PartialResolver {
public:
explicit PartialFileLoader(const QString & basePath);
virtual QString getPartial(const QString & name);
private:
QString m_basePath;
QHash<QString, QString> m_cache;
};
/** Holds properties of a tag in a mustache template. */
struct Tag {
enum Type {
Null,
Value, /// A {{key}} or {{{key}}} tag
SectionStart, /// A {{#section}} tag
InvertedSectionStart, /// An {{^inverted-section}} tag
SectionEnd, /// A {{/section}} tag
Partial, /// A {{^partial}} tag
Comment, /// A {{! comment }} tag
SetDelimiter /// A {{=<% %>=}} tag
};
enum EscapeMode {
Escape,
Unescape,
Raw
};
Tag()
: type(Null)
, start(0)
, end(0)
, escapeMode(Escape)
{}
Type type;
QString key;
int start;
int end;
EscapeMode escapeMode;
};
/** Renders Mustache templates, replacing mustache tags with
* values from a provided context.
*/
class QTCREATOR_UTILS_EXPORT Renderer {
public:
Renderer();
/** Render a Mustache template, using @p context to fetch
* the values used to replace Mustache tags.
*/
QString render(const QString & _template, Context *context);
/** Returns a message describing the last error encountered by the previous
* render() call.
*/
QString error() const;
/** Returns the position in the template where the last error occurred
* when rendering the template or -1 if no error occurred.
*
* If the error occurred in a partial template, the returned position is the offset
* in the partial template.
*/
int errorPos() const;
/** Returns the name of the partial where the error occurred, or an empty string
* if the error occurred in the main template.
*/
QString errorPartial() const;
/** Sets the default tag start and end markers.
* This can be overridden within a template.
*/
void setTagMarkers(const QString & startMarker, const QString & endMarker);
private:
QString render(const QString & _template, int startPos, int endPos, Context *context);
Tag findTag(const QString & content, int pos, int endPos);
Tag findEndTag(const QString & content, const Tag & startTag, int endPos);
void setError(const QString & error, int pos);
void readSetDelimiter(const QString & content, int pos, int endPos);
static QString readTagName(const QString & content, int pos, int endPos);
/** Expands @p tag to fill the line, but only if it is standalone.
*
* The start position is moved to the beginning of the line. The end position is
* moved to one past the end of the line. If @p tag is not standalone, it is
* left unmodified.
*
* A tag is standalone if it is the only non-whitespace token on the the line.
*/
static void expandTag(Tag & tag, const QString & content);
QStack<QString> m_partialStack;
QString m_error;
int m_errorPos;
QString m_errorPartial;
QString m_tagStartMarker;
QString m_tagEndMarker;
QString m_defaultTagStartMarker;
QString m_defaultTagEndMarker;
};
/** A convenience function which renders a template using the given data. */
QString renderTemplate(const QString & templateString, const QVariantHash & args);
};
Q_DECLARE_METATYPE(Mustache::QtVariantContext::fn_t)

View File

@ -56,7 +56,8 @@ SOURCES += reloadpromptutils.cpp \
svgimageprovider.cpp \
hostosinfo.cpp \
logfile.cpp \
crc.cpp
crc.cpp \
mustache.cpp
SOURCES += xmlconfig.cpp
@ -115,7 +116,8 @@ HEADERS += utils_global.h \
svgimageprovider.h \
hostosinfo.h \
logfile.h \
crc.h
crc.h \
mustache.h
HEADERS += xmlconfig.h

View File

@ -17,6 +17,89 @@
<property name="spacing">
<number>0</number>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>9</number>
</property>
<item>
<widget class="QLabel" name="label">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Vehicle name</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>6</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item alignment="Qt::AlignLeft">
<widget class="QLineEdit" name="nameEdit">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>300</width>
<height>0</height>
</size>
</property>
<property name="inputMask">
<string/>
</property>
<property name="maxLength">
<number>20</number>
</property>
<property name="placeholderText">
<string>Enter name of vehicle. Max 20 characters.</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<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>
<item>
<widget class="QTabBar" name="aircraftType" native="true"/>
</item>
@ -26,7 +109,7 @@
<enum>Qt::LeftToRight</enum>
</property>
<property name="autoFillBackground">
<bool>true</bool>
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">#vehicleTypeFrame{
@ -159,7 +242,7 @@
<x>0</x>
<y>0</y>
<width>820</width>
<height>478</height>
<height>435</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
@ -306,8 +389,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>271</width>
<height>307</height>
<width>838</width>
<height>445</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_18">
@ -717,14 +800,14 @@ p, li { white-space: pre-wrap; }
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Sans Serif'; font-size:9pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt;
&lt;tr&gt;
&lt;td style=&quot;border: none;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD REQUIRES CAUTION&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;&lt;br /&gt;&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;&lt;br /&gt;&lt;/span&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD REQUIRES CAUTION&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.&lt;/span&gt;&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>

View File

@ -473,8 +473,8 @@ void SixPointCalibrationModel::compute()
revoCalibrationData.MagBiasNullingRate = memento.revoCalibrationData.MagBiasNullingRate;;
// Check the mag calibration is good
bool good_calibration = true;
bool good_aux_calibration = true;
bool good_calibration = true;
// bool good_aux_calibration = true;
if (calibratingMag) {
good_calibration &= !IS_NAN(revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R0C0]);
good_calibration &= !IS_NAN(revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R0C1]);
@ -581,7 +581,7 @@ void SixPointCalibrationModel::save()
if (calibratingMag) {
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
for (int i = 0; i < RevoCalibration::MAG_TRANSFORM_NUMELEM; i++) {
for (uint i = 0; i < RevoCalibration::MAG_TRANSFORM_NUMELEM; i++) {
revoCalibrationData.mag_transform[i] = result.revoCalibrationData.mag_transform[i];
}
for (int i = 0; i < 3; i++) {
@ -592,7 +592,7 @@ void SixPointCalibrationModel::save()
if (calibratingAuxMag) {
AuxMagSettings::DataFields auxCalibrationData = auxMagSettings->getData();
// Note that Revo/AuxMag MAG_TRANSFORM_RxCx are interchangeable, an assertion at initialization enforces the structs are equal
for (int i = 0; i < RevoCalibration::MAG_TRANSFORM_NUMELEM; i++) {
for (uint i = 0; i < RevoCalibration::MAG_TRANSFORM_NUMELEM; i++) {
auxCalibrationData.mag_transform[i] = result.auxMagSettingsData.mag_transform[i];
}
for (int i = 0; i < 3; i++) {

View File

@ -7,3 +7,4 @@ include(../../plugins/uavobjectutil/uavobjectutil.pri)
include(../../plugins/uavsettingsimportexport/uavsettingsimportexport.pri)
include(../../plugins/uavobjectwidgetutils/uavobjectwidgetutils.pri)
include(../../libs/version_info/version_info.pri)
include(../../libs/qwt/qwt.pri)

View File

@ -65,6 +65,8 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed);
// Add Gps protocol configuration
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
@ -95,6 +97,7 @@ void ConfigRevoHWWidget::setupCustomCombos()
connect(m_ui->cbFlexi, SIGNAL(currentIndexChanged(int)), this, SLOT(flexiPortChanged(int)));
connect(m_ui->cbMain, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged(int)));
connect(m_ui->cbRcvr, SIGNAL(currentIndexChanged(int)), this, SLOT(rcvrPortChanged(int)));
}
void ConfigRevoHWWidget::refreshWidgetsValues(UAVObject *obj)
@ -105,6 +108,7 @@ void ConfigRevoHWWidget::refreshWidgetsValues(UAVObject *obj)
usbVCPPortChanged(0);
mainPortChanged(0);
flexiPortChanged(0);
rcvrPortChanged(0);
m_refreshing = false;
}
@ -196,6 +200,10 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_TELEMETRY) {
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
}
if (m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_PPMTELEMETRY
|| m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_TELEMETRY) {
m_ui->cbRcvr->setCurrentIndex(HwSettings::RM_RCVRPORT_DISABLED);
}
break;
case HwSettings::RM_FLEXIPORT_GPS:
// Add Gps protocol configuration
@ -247,6 +255,10 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
}
if (m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_PPMTELEMETRY
|| m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_TELEMETRY) {
m_ui->cbRcvr->setCurrentIndex(HwSettings::RM_RCVRPORT_DISABLED);
}
break;
case HwSettings::RM_MAINPORT_GPS:
// Add Gps protocol configuration
@ -279,6 +291,30 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
}
}
void ConfigRevoHWWidget::rcvrPortChanged(int index)
{
Q_UNUSED(index);
switch (m_ui->cbRcvr->currentIndex()) {
case HwSettings::RM_RCVRPORT_TELEMETRY:
case HwSettings::RM_RCVRPORT_PPMTELEMETRY:
m_ui->lblRcvrSpeed->setVisible(true);
m_ui->cbRcvrTelemSpeed->setVisible(true);
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
}
if (m_ui->cbMain->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
m_ui->cbMain->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
}
break;
default:
m_ui->lblRcvrSpeed->setVisible(false);
m_ui->cbRcvrTelemSpeed->setVisible(false);
break;
}
}
void ConfigRevoHWWidget::openHelp()
{
QDesktopServices::openUrl(QUrl(tr("http://wiki.openpilot.org/x/GgDBAQ"), QUrl::StrictMode));

View File

@ -57,6 +57,7 @@ private slots:
void usbHIDPortChanged(int index);
void flexiPortChanged(int index);
void mainPortChanged(int index);
void rcvrPortChanged(int index);
void openHelp();
};

View File

@ -121,9 +121,9 @@
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>810</width>
<height>665</height>
<y>-87</y>
<width>789</width>
<height>847</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout_3">
@ -139,6 +139,45 @@
<property name="bottomMargin">
<number>12</number>
</property>
<item row="3" column="2">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="0">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="3">
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_6">
<property name="sizePolicy">
@ -192,81 +231,100 @@
</property>
</spacer>
</item>
<item row="2" column="0">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="3">
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="3" column="2">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="2">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
<item row="5" column="0">
<widget class="QLabel" name="label_4">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
<item row="22" column="1">
<widget class="QLabel" name="lbFlexiGPSProtocol">
<property name="text">
<string>USB HID Function</string>
<string>Protocol</string>
</property>
<property name="textFormat">
<enum>Qt::PlainText</enum>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="24" column="3">
<widget class="QComboBox" name="cbMainGPSProtocol"/>
</item>
<item row="24" column="1">
<widget class="QComboBox" name="cbFlexiGPSProtocol"/>
</item>
<item row="25" column="2">
<spacer name="horizontalSpacer_10">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>80</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="20" column="3">
<widget class="QLabel" name="lblMainSpeed">
<property name="text">
<string>Speed</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="12" column="4">
<spacer name="horizontalSpacer_2">
<item row="14" column="5">
<spacer name="verticalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>50</width>
<height>10</height>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="19" column="1">
<spacer name="horizontalSpacer_7">
<item row="17" column="5">
<spacer name="verticalSpacer_9">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>13</height>
</size>
</property>
</spacer>
</item>
<item row="15" column="5">
<spacer name="verticalSpacer_5">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>13</height>
</size>
</property>
</spacer>
</item>
<item row="25" column="3">
<spacer name="horizontalSpacer_9">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
@ -281,17 +339,201 @@
</property>
</spacer>
</item>
<item row="16" column="3">
<widget class="QLabel" name="lbMainGPSProtocol">
<item row="13" column="5">
<spacer name="verticalSpacer_8">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>13</height>
</size>
</property>
</spacer>
</item>
<item row="21" column="3">
<layout class="QVBoxLayout" name="verticalLayout_6">
<property name="spacing">
<number>0</number>
</property>
<item>
<widget class="QComboBox" name="cbMainTelemSpeed">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="cbMainGPSSpeed"/>
</item>
<item>
<widget class="QComboBox" name="cbMainComSpeed"/>
</item>
</layout>
</item>
<item row="3" column="0">
<widget class="QComboBox" name="cbRcvr"/>
</item>
<item row="1" column="0">
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>90</height>
</size>
</property>
</spacer>
</item>
<item row="18" column="0">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>120</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_7">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Protocol</string>
<string>Receiver Port</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="1" column="1" rowspan="11" colspan="4" alignment="Qt::AlignHCenter|Qt::AlignVCenter">
<item row="11" column="5">
<widget class="QLabel" name="label_9">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Sonar Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="20" column="1">
<widget class="QLabel" name="lblFlexiSpeed">
<property name="text">
<string>Speed</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="18" column="5">
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>120</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="19" column="3">
<widget class="QComboBox" name="cbMain"/>
</item>
<item row="12" column="5">
<widget class="QComboBox" name="cbSonar">
<property name="enabled">
<bool>false</bool>
</property>
</widget>
</item>
<item row="25" column="4">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>70</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="16" column="5">
<spacer name="verticalSpacer_6">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="18" column="3">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Main Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="19" column="1">
<widget class="QComboBox" name="cbFlexi"/>
</item>
<item row="18" column="1">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Flexi Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="1" column="1" rowspan="17" colspan="4" alignment="Qt::AlignHCenter|Qt::AlignVCenter">
<widget class="QLabel" name="label_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
@ -322,28 +564,12 @@
</property>
</widget>
</item>
<item row="10" column="5">
<spacer name="verticalSpacer_6">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="15" column="1">
<item row="21" column="1">
<layout class="QVBoxLayout" name="verticalLayout_5">
<property name="spacing">
<number>0</number>
</property>
<item alignment="Qt::AlignTop">
<item>
<widget class="QComboBox" name="cbFlexiTelemSpeed">
<property name="enabled">
<bool>true</bool>
@ -358,64 +584,8 @@
</item>
</layout>
</item>
<item row="13" column="1">
<widget class="QComboBox" name="cbFlexi"/>
</item>
<item row="19" column="4">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>70</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="12" column="1">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Flexi Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="6" column="5">
<widget class="QComboBox" name="cbSonar">
<property name="enabled">
<bool>false</bool>
</property>
</widget>
</item>
<item row="13" column="3">
<widget class="QComboBox" name="cbMain"/>
</item>
<item row="12" column="3">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Main Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QComboBox" name="cbUSBVCPSpeed">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
<item row="12" column="5">
<spacer name="horizontalSpacer_6">
<item row="25" column="1">
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
@ -430,13 +600,80 @@
</property>
</spacer>
</item>
<item row="8" column="0">
<widget class="QComboBox" name="cbUSBVCPFunction"/>
<item row="22" column="3">
<widget class="QLabel" name="lbMainGPSProtocol">
<property name="text">
<string>Protocol</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QComboBox" name="cbUSBHIDFunction"/>
<item row="18" column="4">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>50</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="9" column="0">
<item row="4" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_4">
<item>
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<widget class="QLabel" name="lblRcvrSpeed">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Speed</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="cbRcvrTelemSpeed"/>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_11">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>50</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item row="15" column="0">
<widget class="QComboBox" name="cbUSBVCPSpeed">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
<item row="14" column="0">
<widget class="QLabel" name="lblUSBVCPSpeed">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -452,71 +689,10 @@
</property>
</widget>
</item>
<item row="5" column="5">
<widget class="QLabel" name="label_9">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Sonar Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_7">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Receiver Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="4" column="0">
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>25</height>
</size>
</property>
</spacer>
<item row="13" column="0">
<widget class="QComboBox" name="cbUSBVCPFunction"/>
</item>
<item row="12" column="0">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>120</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="7" column="0">
<widget class="QLabel" name="label_8">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -532,177 +708,25 @@
</property>
</widget>
</item>
<item row="1" column="0">
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>120</height>
</size>
</property>
</spacer>
<item row="11" column="0">
<widget class="QComboBox" name="cbUSBHIDFunction"/>
</item>
<item row="14" column="1">
<widget class="QLabel" name="lblFlexiSpeed">
<item row="10" column="0">
<widget class="QLabel" name="label_4">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Speed</string>
<string>USB HID Function</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="15" column="3">
<layout class="QVBoxLayout" name="verticalLayout_6">
<property name="spacing">
<number>0</number>
</property>
<item>
<widget class="QComboBox" name="cbMainTelemSpeed">
<property name="enabled">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="cbMainGPSSpeed"/>
</item>
<item>
<widget class="QComboBox" name="cbMainComSpeed"/>
</item>
</layout>
</item>
<item row="3" column="0">
<widget class="QComboBox" name="cbRcvr"/>
</item>
<item row="19" column="3">
<spacer name="horizontalSpacer_9">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>120</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="7" column="5">
<spacer name="verticalSpacer_8">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>13</height>
</size>
</property>
</spacer>
</item>
<item row="8" column="5">
<spacer name="verticalSpacer_7">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="9" column="5">
<spacer name="verticalSpacer_5">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>13</height>
</size>
</property>
</spacer>
</item>
<item row="11" column="5">
<spacer name="verticalSpacer_9">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>13</height>
</size>
</property>
</spacer>
</item>
<item row="19" column="2">
<spacer name="horizontalSpacer_10">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>80</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="14" column="3">
<widget class="QLabel" name="lblMainSpeed">
<property name="text">
<string>Speed</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
</property>
</widget>
</item>
<item row="16" column="1">
<widget class="QLabel" name="lbFlexiGPSProtocol">
<property name="text">
<string>Protocol</string>
</property>
<property name="textFormat">
<enum>Qt::PlainText</enum>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="18" column="3">
<widget class="QComboBox" name="cbMainGPSProtocol"/>
</item>
<item row="18" column="1">
<widget class="QComboBox" name="cbFlexiGPSProtocol"/>
</item>
</layout>
</item>
</layout>
@ -908,8 +932,8 @@ Beware of not locking yourself out!</string>
</layout>
</widget>
<resources>
<include location="configgadget.qrc"/>
<include location="../coreplugin/core.qrc"/>
<include location="configgadget.qrc"/>
</resources>
<connections/>
</ui>

View File

@ -43,12 +43,19 @@
#include "altitudeholdsettings.h"
#include "stabilizationsettings.h"
#include "qwt/src/qwt.h"
#include "qwt/src/qwt_plot.h"
#include "qwt/src/qwt_plot_canvas.h"
#include "qwt/src/qwt_scale_widget.h"
ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent),
boardModel(0), m_pidBankCount(0), m_currentPIDBank(0)
{
ui = new Ui_StabilizationWidget();
ui->setupUi(this);
setupExpoPlot();
StabilizationSettings *stabSettings = qobject_cast<StabilizationSettings *>(getObject("StabilizationSettings"));
Q_ASSERT(stabSettings);
@ -59,7 +66,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
m_pidTabBars.append(ui->advancedPIDBankTabBar);
foreach(QTabBar * tabBar, m_pidTabBars) {
for (int i = 0; i < m_pidBankCount; i++) {
tabBar->addTab(tr("PID Bank %1").arg(i + 1));
tabBar->addTab(tr("Settings Bank %1").arg(i + 1));
tabBar->setTabData(i, QString("StabilizationSettingsBank%1").arg(i + 1));
}
tabBar->setExpanding(false);
@ -144,6 +151,11 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
connect(this, SIGNAL(autoPilotConnected()), this, SLOT(onBoardConnected()));
addWidget(ui->expoPlot);
connect(ui->expoSpinnerRoll, SIGNAL(valueChanged(int)), this, SLOT(replotExpoRoll(int)));
connect(ui->expoSpinnerPitch, SIGNAL(valueChanged(int)), this, SLOT(replotExpoPitch(int)));
connect(ui->expoSpinnerYaw, SIGNAL(valueChanged(int)), this, SLOT(replotExpoYaw(int)));
disableMouseWheelEvents();
updateEnableControls();
}
@ -175,14 +187,12 @@ void ConfigStabilizationWidget::updateThrottleCurveFromObject()
UAVObject *stabBank = getObjectManager()->getObject(QString(m_pidTabBars.at(0)->tabData(m_currentPIDBank).toString()));
Q_ASSERT(stabBank);
qDebug() << "updatingCurveFromObject" << stabBank->getName();
UAVObjectField *field = stabBank->getField("ThrustPIDScaleCurve");
Q_ASSERT(field);
QList<double> curve;
for (quint32 i = 0; i < field->getNumElements(); i++) {
qDebug() << field->getName() << field->getElementNames().at(i) << "=>" << field->getValue(i);
curve.append(field->getValue(i).toDouble());
}
@ -202,7 +212,6 @@ void ConfigStabilizationWidget::updateObjectFromThrottleCurve()
UAVObject *stabBank = getObjectManager()->getObject(QString(m_pidTabBars.at(0)->tabData(m_currentPIDBank).toString()));
Q_ASSERT(stabBank);
qDebug() << "updatingObjectFromCurve" << stabBank->getName();
UAVObjectField *field = stabBank->getField("ThrustPIDScaleCurve");
Q_ASSERT(field);
@ -210,7 +219,6 @@ void ConfigStabilizationWidget::updateObjectFromThrottleCurve()
QList<double> curve = ui->thrustPIDScalingCurve->getCurve();
for (quint32 i = 0; i < field->getNumElements(); i++) {
field->setValue(curve.at(i), i);
qDebug() << field->getName() << field->getElementNames().at(i) << "<=" << curve.at(i);
}
field = stabBank->getField("EnableThrustPIDScaling");
@ -218,6 +226,55 @@ void ConfigStabilizationWidget::updateObjectFromThrottleCurve()
field->setValue(ui->enableThrustPIDScalingCheckBox->isChecked() ? "TRUE" : "FALSE");
}
void ConfigStabilizationWidget::setupExpoPlot()
{
ui->expoPlot->setMouseTracking(false);
ui->expoPlot->setAxisScale(QwtPlot::xBottom, 0, 100, 25);
QwtText title;
title.setText(tr("Input %"));
title.setFont(ui->expoPlot->axisFont(QwtPlot::xBottom));
ui->expoPlot->setAxisTitle(QwtPlot::xBottom, title);
ui->expoPlot->setAxisScale(QwtPlot::yLeft, 0, 100, 25);
title.setText(tr("Output %"));
title.setFont(ui->expoPlot->axisFont(QwtPlot::yLeft));
ui->expoPlot->setAxisTitle(QwtPlot::yLeft, title);
ui->expoPlot->canvas()->setFrameShape(QFrame::NoFrame);
ui->expoPlot->canvas()->setCursor(QCursor());
m_plotGrid.setMajPen(QColor(Qt::gray));
m_plotGrid.setMinPen(QColor(Qt::lightGray));
m_plotGrid.enableXMin(false);
m_plotGrid.enableYMin(false);
m_plotGrid.attach(ui->expoPlot);
m_expoPlotCurveRoll.setRenderHint(QwtPlotCurve::RenderAntialiased);
QColor rollColor(Qt::red);
rollColor.setAlpha(180);
m_expoPlotCurveRoll.setPen(QPen(rollColor, 2));
m_expoPlotCurveRoll.attach(ui->expoPlot);
replotExpoRoll(ui->expoSpinnerRoll->value());
m_expoPlotCurveRoll.show();
QColor pitchColor(Qt::green);
pitchColor.setAlpha(180);
m_expoPlotCurvePitch.setRenderHint(QwtPlotCurve::RenderAntialiased);
m_expoPlotCurvePitch.setPen(QPen(pitchColor, 2));
m_expoPlotCurvePitch.attach(ui->expoPlot);
replotExpoPitch(ui->expoSpinnerPitch->value());
m_expoPlotCurvePitch.show();
QColor yawColor(Qt::blue);
yawColor.setAlpha(180);
m_expoPlotCurveYaw.setRenderHint(QwtPlotCurve::RenderAntialiased);
m_expoPlotCurveYaw.setPen(QPen(yawColor, 2));
m_expoPlotCurveYaw.attach(ui->expoPlot);
replotExpoYaw(ui->expoSpinnerYaw->value());
m_expoPlotCurveYaw.show();
}
void ConfigStabilizationWidget::resetThrottleCurveToDefault()
{
UAVDataObject *defaultStabBank = (UAVDataObject *)getObjectManager()->getObject(QString(m_pidTabBars.at(0)->tabData(m_currentPIDBank).toString()));
@ -250,6 +307,37 @@ void ConfigStabilizationWidget::throttleCurveUpdated()
setDirty(true);
}
void ConfigStabilizationWidget::replotExpo(int value, QwtPlotCurve &curve)
{
double x[EXPO_CURVE_POINTS_COUNT] = { 0 };
double y[EXPO_CURVE_POINTS_COUNT] = { 0 };
double factor = pow(EXPO_CURVE_CONSTANT, value);
double step = 1.0 / (EXPO_CURVE_POINTS_COUNT - 1);
for (int i = 0; i < EXPO_CURVE_POINTS_COUNT; i++) {
double val = i * step;
x[i] = val * 100.0;
y[i] = pow(val, factor) * 100.0;
}
curve.setSamples(x, y, EXPO_CURVE_POINTS_COUNT);
ui->expoPlot->replot();
}
void ConfigStabilizationWidget::replotExpoRoll(int value)
{
replotExpo(value, m_expoPlotCurveRoll);
}
void ConfigStabilizationWidget::replotExpoPitch(int value)
{
replotExpo(value, m_expoPlotCurvePitch);
}
void ConfigStabilizationWidget::replotExpoYaw(int value)
{
replotExpo(value, m_expoPlotCurveYaw);
}
void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value)
{
ui->realTimeUpdates_6->setChecked(value);
@ -259,10 +347,8 @@ void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value)
if (value && !realtimeUpdates->isActive()) {
realtimeUpdates->start(AUTOMATIC_UPDATE_RATE);
qDebug() << "Instant Update timer started.";
} else if (!value && realtimeUpdates->isActive()) {
realtimeUpdates->stop();
qDebug() << "Instant Update timer stopped.";
}
}
@ -359,7 +445,6 @@ void ConfigStabilizationWidget::pidBankChanged(int index)
setWidgetBindingObjectEnabled(m_pidTabBars.at(0)->tabData(index).toString(), true);
m_currentPIDBank = index;
qDebug() << "current bank:" << m_currentPIDBank;
updateThrottleCurveFromObject();
setDirty(dirty);
}

View File

@ -35,7 +35,8 @@
#include "stabilizationsettings.h"
#include <QWidget>
#include <QTimer>
#include "qwt/src/qwt_plot_curve.h"
#include "qwt/src/qwt_plot_grid.h"
class ConfigStabilizationWidget : public ConfigTaskWidget {
Q_OBJECT
@ -52,14 +53,23 @@ private:
QString m_stabilizationObjectsString;
// Milliseconds between automatic 'Instant Updates'
static const int AUTOMATIC_UPDATE_RATE = 500;
static const int AUTOMATIC_UPDATE_RATE = 500;
static const int EXPO_CURVE_POINTS_COUNT = 100;
static const double EXPO_CURVE_CONSTANT = 1.00695;
int boardModel;
int m_pidBankCount;
int m_currentPIDBank;
QwtPlotCurve m_expoPlotCurveRoll;
QwtPlotCurve m_expoPlotCurvePitch;
QwtPlotCurve m_expoPlotCurveYaw;
QwtPlotGrid m_plotGrid;
void updateThrottleCurveFromObject();
void updateObjectFromThrottleCurve();
void setupExpoPlot();
protected:
QString mapObjectName(const QString objectName);
@ -75,5 +85,9 @@ private slots:
void pidBankChanged(int index);
void resetThrottleCurveToDefault();
void throttleCurveUpdated();
void replotExpo(int value, QwtPlotCurve &curve);
void replotExpoRoll(int value);
void replotExpoPitch(int value);
void replotExpoYaw(int value);
};
#endif // ConfigStabilizationWidget_H

View File

@ -145,6 +145,25 @@ static bool isAttitudeOption(int pidOption)
}
}
static bool isExpoOption(int pidOption)
{
switch (pidOption) {
case TxPIDSettings::PIDS_ROLLEXPO:
case TxPIDSettings::PIDS_PITCHEXPO:
case TxPIDSettings::PIDS_ROLLPITCHEXPO:
case TxPIDSettings::PIDS_YAWEXPO:
return true;
default:
return false;
}
}
static bool isAcroPlusFactorOption(int pidOption)
{
return pidOption == TxPIDSettings::PIDS_ACROPLUSFACTOR;
}
template <class StabilizationSettingsBankX>
static float defaultValueForPidOption(const StabilizationSettingsBankX *bank, int pidOption)
{
@ -260,6 +279,18 @@ static float defaultValueForPidOption(const StabilizationSettingsBankX *bank, in
case TxPIDSettings::PIDS_YAWATTITUDERESP:
return bank->getYawMax();
case TxPIDSettings::PIDS_ROLLEXPO:
return bank->getStickExpo_Roll();
case TxPIDSettings::PIDS_PITCHEXPO:
return bank->getStickExpo_Pitch();
case TxPIDSettings::PIDS_ROLLPITCHEXPO:
return bank->getStickExpo_Roll();
case TxPIDSettings::PIDS_YAWEXPO:
return bank->getStickExpo_Yaw();
case -1: // The PID Option field was uninitialized.
return 0.0f;
@ -337,6 +368,20 @@ void ConfigTxPIDWidget::updateSpinBoxProperties(int selectedPidOption)
maxPID->setSingleStep(1);
minPID->setDecimals(0);
maxPID->setDecimals(0);
} else if (isExpoOption(selectedPidOption)) {
minPID->setRange(-100, 100);
maxPID->setRange(-100, 100);
minPID->setSingleStep(1);
maxPID->setSingleStep(1);
minPID->setDecimals(0);
maxPID->setDecimals(0);
} else if (isAcroPlusFactorOption(selectedPidOption)) {
minPID->setRange(0, 1);
maxPID->setRange(0, 1);
minPID->setSingleStep(0.01);
maxPID->setSingleStep(0.01);
minPID->setDecimals(2);
maxPID->setDecimals(2);
} else {
minPID->setRange(0, 99.99);
maxPID->setRange(0, 99.99);

View File

@ -121,6 +121,10 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
m_aircraft->saveAircraftToRAM->setVisible(false);
}
SystemSettings *syssettings = SystemSettings::GetInstance(getObjectManager());
Q_ASSERT(syssettings);
m_aircraft->nameEdit->setMaxLength(syssettings->VEHICLENAME_NUMELEM);
addApplySaveButtons(m_aircraft->saveAircraftToRAM, m_aircraft->saveAircraftToSD);
addUAVObject("SystemSettings");
@ -158,6 +162,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
addWidget(m_aircraft->ffTestBox1);
addWidget(m_aircraft->ffTestBox2);
addWidget(m_aircraft->ffTestBox3);
addWidget(m_aircraft->nameEdit);
disableMouseWheelEvents();
updateEnableControls();
@ -174,6 +179,7 @@ ConfigVehicleTypeWidget::~ConfigVehicleTypeWidget()
void ConfigVehicleTypeWidget::switchAirframeType(int index)
{
m_aircraft->airframesWidget->setCurrentWidget(getVehicleConfigWidget(index));
m_aircraft->tabWidget->setTabEnabled(1, index != 1);
}
/**
@ -224,6 +230,19 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *o)
}
}
field = system->getField(QString("VehicleName"));
Q_ASSERT(field);
QString name;
for (uint i = 0; i < field->getNumElements(); ++i) {
QChar chr = field->getValue(i).toChar();
if (chr != 0) {
name.append(chr);
} else {
break;
}
}
m_aircraft->nameEdit->setText(name);
updateFeedForwardUI();
setDirty(dirty);
@ -270,6 +289,17 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
vconfig->setMixerValue(mixer, "DecelTime", m_aircraft->decelTime->value());
vconfig->setMixerValue(mixer, "MaxAccel", m_aircraft->maxAccelSlider->value());
field = system->getField(QString("VehicleName"));
Q_ASSERT(field);
QString name = m_aircraft->nameEdit->text();
for (uint i = 0; i < field->getNumElements(); ++i) {
if (i < (uint)name.length()) {
field->setValue(name.at(i).toLatin1(), i);
} else {
field->setValue(0, i);
}
}
// call refreshWidgetsValues() to reflect actual saved values
refreshWidgetsValues();
updateFeedForwardUI();

View File

@ -116,8 +116,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>772</width>
<height>514</height>
<width>774</width>
<height>505</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout">
@ -542,8 +542,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>724</width>
<height>497</height>
<width>758</width>
<height>542</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0,0">
@ -1228,7 +1228,7 @@ margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>PID Bank</string>
<string>Settings Bank</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
@ -2044,8 +2044,8 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
<rect>
<x>0</x>
<y>0</y>
<width>407</width>
<height>138</height>
<width>565</width>
<height>159</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">

File diff suppressed because it is too large Load Diff

View File

@ -47,8 +47,8 @@ MagicWaypointGadgetWidget::MagicWaypointGadgetWidget(QWidget *parent) : QLabel(p
m_magicwaypoint->setupUi(this);
// Connect object updated event from UAVObject to also update check boxes
connect(getPathDesired(), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(positionObjectChanged(UAVObject *)));
connect(getPositionState(), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(positionObjectChanged(UAVObject *)));
connect(getPathDesired(), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(positionStateChanged(UAVObject *)));
connect(getPositionState(), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(positionStateChanged(UAVObject *)));
// Connect updates from the position widget to this widget
connect(m_magicwaypoint->widgetPosition, SIGNAL(positionClicked(double, double)), this, SLOT(positionSelected(double, double)));

View File

@ -61,7 +61,7 @@ void FixedWingPage::setupSelection(Selection *selection)
SetupWizard::FIXED_WING_DUAL_AILERON);
selection->addItem(tr("Aileron Single Servo"),
tr("This setup expects a traditional airframe using a single alieron servo or two servos "
tr("This setup expects a traditional airframe using a single aileron servo or two servos "
"connected by a Y adapter plus an elevator and a rudder."),
"aileron-single",
SetupWizard::FIXED_WING_AILERON);

View File

@ -1,4 +1,4 @@
html>
<html>
<head>
<title></title>
<meta content="">

View File

@ -52,11 +52,13 @@ class FieldTreeItem : public TreeItem {
Q_OBJECT
public:
FieldTreeItem(int index, const QList<QVariant> &data, TreeItem *parent = 0) :
TreeItem(data, parent), m_index(index) {}
FieldTreeItem(int index, const QList<QVariant> &data, UAVObjectField *field, TreeItem *parent = 0) :
TreeItem(data, parent), m_index(index), m_field(field)
{}
FieldTreeItem(int index, const QVariant &data, TreeItem *parent = 0) :
TreeItem(data, parent), m_index(index) {}
FieldTreeItem(int index, const QVariant &data, UAVObjectField *field, TreeItem *parent = 0) :
TreeItem(data, parent), m_index(index), m_field(field)
{}
bool isEditable()
{
@ -67,19 +69,27 @@ public:
virtual QVariant getEditorValue(QWidget *editor) = 0;
virtual void setEditorValue(QWidget *editor, QVariant value) = 0;
virtual void apply() {}
virtual bool isKnown()
{
return parent()->isKnown();
}
protected:
int m_index;
UAVObjectField *m_field;
};
class EnumFieldTreeItem : public FieldTreeItem {
Q_OBJECT
public:
EnumFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_enumOptions(field->getOptions()), m_field(field) {}
FieldTreeItem(index, data, field, parent), m_enumOptions(field->getOptions())
{}
EnumFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_enumOptions(field->getOptions()), m_field(field) {}
FieldTreeItem(index, data, field, parent), m_enumOptions(field->getOptions())
{}
void setData(QVariant value, int column)
{
@ -148,20 +158,19 @@ public:
private:
QStringList m_enumOptions;
UAVObjectField *m_field;
};
class IntFieldTreeItem : public FieldTreeItem {
Q_OBJECT
public:
IntFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field)
FieldTreeItem(index, data, field, parent)
{
setMinMaxValues();
}
IntFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field)
FieldTreeItem(index, data, field, parent)
{
setMinMaxValues();
}
@ -246,7 +255,6 @@ public:
}
private:
UAVObjectField *m_field;
int m_minValue;
int m_maxValue;
};
@ -255,10 +263,10 @@ class FloatFieldTreeItem : public FieldTreeItem {
Q_OBJECT
public:
FloatFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, bool scientific = false, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field), m_useScientificNotation(scientific) {}
FieldTreeItem(index, data, field, parent), m_useScientificNotation(scientific) {}
FloatFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, bool scientific = false, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field), m_useScientificNotation(scientific) {}
FieldTreeItem(index, data, field, parent), m_useScientificNotation(scientific) {}
void setData(QVariant value, int column)
{
@ -324,7 +332,6 @@ public:
}
private:
UAVObjectField *m_field;
bool m_useScientificNotation;
};
@ -332,11 +339,11 @@ class HexFieldTreeItem : public FieldTreeItem {
Q_OBJECT
public:
HexFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field)
FieldTreeItem(index, data, field, parent)
{}
HexFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field)
FieldTreeItem(index, data, field, parent)
{}
QWidget *createEditor(QWidget *parent)
@ -385,8 +392,6 @@ public:
}
private:
UAVObjectField *m_field;
QVariant toHexString(QVariant value)
{
QString str;
@ -407,11 +412,11 @@ class CharFieldTreeItem : public FieldTreeItem {
Q_OBJECT
public:
CharFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field)
FieldTreeItem(index, data, field, parent)
{}
CharFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field)
FieldTreeItem(index, data, field, parent)
{}
QWidget *createEditor(QWidget *parent)
@ -460,8 +465,6 @@ public:
}
private:
UAVObjectField *m_field;
QVariant toChar(QVariant value)
{
return value.toChar();
@ -471,7 +474,6 @@ private:
{
return QVariant(str.toString().at(0).toLatin1());
}
};
#endif // FIELDTREEITEM_H

View File

@ -0,0 +1,62 @@
<html>
<head></head>
<body style="font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;">
<table width='100%' cellpadding="5">
<tr bgcolor='#308BC6'>
<td rowspan='1' colspan='4'><b>{{OBJECT_NAME_TITLE}}:&nbsp;</b>{{OBJECT_NAME}}</td>
</tr>
<tr>
<td colspan='1'><b>{{CATEGORY_TITLE}}:&nbsp;</b>{{CATEGORY}}</td>
<td colspan='1'><b>{{TYPE_TITLE}}:&nbsp;</b>{{TYPE}}</td>
<td colspan='1'><b>{{SIZE_TITLE}}:&nbsp;</b>{{SIZE}}&nbsp;bytes</td>
<td colspan='1'><b>{{MULTI_INSTANCE_TITLE}}:&nbsp;</b>{{MULTI_INSTANCE}}</td>
</tr>
<tr>
<td colspan='4' rowspan='1' valign='top'><b>{{DESCRIPTION_TITLE}}:&nbsp;</b>{{DESCRIPTION}}</td>
<tr bgcolor='#51A0D3'>
<td rowspan='1' colspan='4'><b>{{FIELDS_NAME_TITLE}}</td>
</tr>
{{#FIELDS}}
<tr>
<td colspan='4'>
<table width='100%' cellpadding="5">
<tr bgcolor='#7DBAE2'>
<td rowspan='1' colspan='4'><b>{{FIELD_NAME_TITLE}}:&nbsp;</b>{{FIELD_NAME}}</td>
</tr>
<tr>
<td rowspan='1' colspan='1'><b>{{FIELD_TYPE_TITLE}}:&nbsp;</b>{{FIELD_TYPE}}</td>
{{#FIELD_UNIT_TITLE}}
<td rowspan='1' colspan='2'><b>{{FIELD_UNIT_TITLE}}:&nbsp;</b>{{FIELD_UNIT}}</td>
{{/FIELD_UNIT_TITLE}}
</tr>
{{#FIELD_OPTIONS_TITLE}}
<tr>
<td rowspan='1' colspan='2'><b>{{FIELD_OPTIONS_TITLE}}:&nbsp;
</b>{{#FIELD_OPTIONS}}{{FIELD_OPTION_DELIM}}{{FIELD_OPTION}}{{/FIELD_OPTIONS}}</td>
</tr>
{{/FIELD_OPTIONS_TITLE}}
{{#FIELD_ELEMENTS_TITLE}}
<tr>
<td rowspan='1' colspan='2'><b>{{FIELD_ELEMENTS_TITLE}}:&nbsp;
</b>{{#FIELD_ELEMENTS}}{{FIELD_ELEMENT_DELIM}}{{FIELD_ELEMENT}}{{FIELD_ELEMENT_LIMIT}}{{/FIELD_ELEMENTS}}</td>
</tr>
{{/FIELD_ELEMENTS_TITLE}}
{{^FIELD_ELEMENTS_TITLE}}
{{#FIELD_LIMIT_TITLE}}
<tr>
<td rowspan='1' colspan='2'><b>{{FIELD_LIMIT_TITLE}}:&nbsp;</b>{{FIELD_LIMIT}}</td>
</tr>
{{/FIELD_LIMIT_TITLE}}
{{/FIELD_ELEMENTS_TITLE}}
{{#FIELD_DESCRIPTION_TITLE}}
<tr>
<td rowspan='1' colspan='2'><b>{{FIELD_DESCRIPTION_TITLE}}:&nbsp;</b>{{FIELD_DESCRIPTION}}</td>
</tr>
{{/FIELD_DESCRIPTION_TITLE}}
</table>
</td>
</tr>
{{/FIELDS}}
</table>
</body>
</html>

View File

@ -250,7 +250,7 @@ QVariant ArrayFieldTreeItem::data(int column) const
.arg(m_field->getValue(i).toUInt(&ok), TreeItem::maxHexStringLength(m_field->getType()),
16, QChar('0')).toUpper());
}
QString data = QString("{%1}").arg(dataString);
QString data = QString("{%1}").arg(dataString);
return data;
} else {
return QVariant();

View File

@ -88,6 +88,9 @@ private:
class TreeItem : public QObject {
Q_OBJECT
public:
static const int TITLE_COLUMN = 0;
static const int DATA_COLUMN = 1;
TreeItem(const QList<QVariant> &data, TreeItem *parent = 0);
TreeItem(const QVariant &data, TreeItem *parent = 0);
virtual ~TreeItem();
@ -184,29 +187,52 @@ public:
switch (type) {
case UAVObjectField::INT8:
return 2;
case UAVObjectField::INT16:
return 4;
case UAVObjectField::INT32:
return 8;
case UAVObjectField::UINT8:
return 2;
case UAVObjectField::UINT16:
return 4;
case UAVObjectField::UINT32:
return 8;
default:
Q_ASSERT(false);
}
return 0;
}
void updateIsKnown(bool isKnown)
{
if (isKnown != this->isKnown()) {
m_changed = false;
foreach(TreeItem * child, m_children) {
child->updateIsKnown(isKnown);
}
emit updateIsKnown(this);
}
}
virtual bool isKnown()
{
return true;
}
signals:
void updateHighlight(TreeItem *);
void updateHighlight(TreeItem *item);
void updateIsKnown(TreeItem *item);
private slots:
private:
static int m_highlightTimeMs;
QList<TreeItem *> m_children;
// m_data contains: [0] property name, [1] value, [2] unit
QList<QVariant> m_data;
QString m_description;
@ -215,9 +241,6 @@ private:
bool m_changed;
QTime m_highlightExpires;
HighLightManager *m_highlightManager;
static int m_highlightTimeMs;
public:
static const int dataColumn = 1;
};
class DataObjectTreeItem;
@ -259,18 +282,25 @@ private:
class ObjectTreeItem : public TreeItem {
Q_OBJECT
public:
ObjectTreeItem(const QList<QVariant> &data, TreeItem *parent = 0) :
TreeItem(data, parent), m_obj(0) {}
ObjectTreeItem(const QVariant &data, TreeItem *parent = 0) :
TreeItem(data, parent), m_obj(0) {}
void setObject(UAVObject *obj)
ObjectTreeItem(const QList<QVariant> &data, UAVObject *object, TreeItem *parent = 0) :
TreeItem(data, parent), m_obj(object)
{
m_obj = obj; setDescription(obj->getDescription());
setDescription(m_obj->getDescription());
}
ObjectTreeItem(const QVariant &data, UAVObject *object, TreeItem *parent = 0) :
TreeItem(data, parent), m_obj(object)
{
setDescription(m_obj->getDescription());
}
inline UAVObject *object()
{
return m_obj;
}
bool isKnown()
{
return !m_obj->isSettingsObject() || m_obj->isKnown();
}
private:
UAVObject *m_obj;
};
@ -278,25 +308,27 @@ private:
class MetaObjectTreeItem : public ObjectTreeItem {
Q_OBJECT
public:
MetaObjectTreeItem(UAVObject *obj, const QList<QVariant> &data, TreeItem *parent = 0) :
ObjectTreeItem(data, parent)
MetaObjectTreeItem(UAVObject *object, const QList<QVariant> &data, TreeItem *parent = 0) :
ObjectTreeItem(data, object, parent)
{}
MetaObjectTreeItem(UAVObject *object, const QVariant &data, TreeItem *parent = 0) :
ObjectTreeItem(data, object, parent)
{}
bool isKnown()
{
setObject(obj);
}
MetaObjectTreeItem(UAVObject *obj, const QVariant &data, TreeItem *parent = 0) :
ObjectTreeItem(data, parent)
{
setObject(obj);
return parent()->isKnown();
}
};
class DataObjectTreeItem : public ObjectTreeItem {
Q_OBJECT
public:
DataObjectTreeItem(const QList<QVariant> &data, TreeItem *parent = 0) :
ObjectTreeItem(data, parent) {}
DataObjectTreeItem(const QVariant &data, TreeItem *parent = 0) :
ObjectTreeItem(data, parent) {}
DataObjectTreeItem(const QList<QVariant> &data, UAVObject *object, TreeItem *parent = 0) :
ObjectTreeItem(data, object, parent) {}
DataObjectTreeItem(const QVariant &data, UAVObject *object, TreeItem *parent = 0) :
ObjectTreeItem(data, object, parent) {}
virtual void apply()
{
foreach(TreeItem * child, treeChildren()) {
@ -322,16 +354,12 @@ public:
class InstanceTreeItem : public DataObjectTreeItem {
Q_OBJECT
public:
InstanceTreeItem(UAVObject *obj, const QList<QVariant> &data, TreeItem *parent = 0) :
DataObjectTreeItem(data, parent)
{
setObject(obj);
}
InstanceTreeItem(UAVObject *obj, const QVariant &data, TreeItem *parent = 0) :
DataObjectTreeItem(data, parent)
{
setObject(obj);
}
InstanceTreeItem(UAVObject *object, const QList<QVariant> &data, TreeItem *parent = 0) :
DataObjectTreeItem(data, object, parent)
{}
InstanceTreeItem(UAVObject *object, const QVariant &data, TreeItem *parent = 0) :
DataObjectTreeItem(data, object, parent)
{}
virtual void apply()
{
TreeItem::apply();
@ -350,9 +378,13 @@ public:
ArrayFieldTreeItem(UAVObjectField *field, const QVariant &data, TreeItem *parent = 0) : TreeItem(data, parent), m_field(field)
{}
QVariant data(int column) const;
bool isKnown()
{
return parent()->isKnown();
}
private:
UAVObjectField*m_field;
UAVObjectField *m_field;
};
#endif // TREEITEM_H

View File

@ -32,7 +32,8 @@ UAVObjectBrowser::UAVObjectBrowser(QString classId, UAVObjectBrowserWidget *widg
m_widget(widget),
m_config(NULL)
{
connect(m_widget, SIGNAL(viewOptionsChanged(bool, bool, bool)), this, SLOT(viewOptionsChangedSlot(bool, bool, bool)));
connect(m_widget, SIGNAL(viewOptionsChanged(bool, bool, bool, bool)), this, SLOT(viewOptionsChangedSlot(bool, bool, bool, bool)));
connect(m_widget, SIGNAL(splitterChanged(QByteArray)), this, SLOT(splitterChanged(QByteArray)));
}
UAVObjectBrowser::~UAVObjectBrowser()
@ -45,18 +46,28 @@ void UAVObjectBrowser::loadConfiguration(IUAVGadgetConfiguration *config)
UAVObjectBrowserConfiguration *m = qobject_cast<UAVObjectBrowserConfiguration *>(config);
m_config = m;
m_widget->setUnknownObjectColor(m->unknownObjectColor());
m_widget->setRecentlyUpdatedColor(m->recentlyUpdatedColor());
m_widget->setManuallyChangedColor(m->manuallyChangedColor());
m_widget->setRecentlyUpdatedTimeout(m->recentlyUpdatedTimeout());
m_widget->setOnlyHilightChangedValues(m->onlyHighlightChangedValues());
m_widget->setViewOptions(m->categorizedView(), m->scientificView(), m->showMetaData());
m_widget->setViewOptions(m->categorizedView(), m->scientificView(), m->showMetaData(), m->showDescription());
m_widget->setSplitterState(m->splitterState());
}
void UAVObjectBrowser::viewOptionsChangedSlot(bool categorized, bool scientific, bool metadata)
void UAVObjectBrowser::viewOptionsChangedSlot(bool categorized, bool scientific, bool metadata, bool description)
{
if (m_config) {
m_config->setCategorizedView(categorized);
m_config->setScientificView(scientific);
m_config->setShowMetaData(metadata);
m_config->setShowDescription(description);
}
}
void UAVObjectBrowser::splitterChanged(QByteArray state)
{
if (m_config) {
m_config->setSplitterState(state);
}
}

View File

@ -50,8 +50,11 @@ public:
return m_widget;
}
void loadConfiguration(IUAVGadgetConfiguration *config);
private slots:
void viewOptionsChangedSlot(bool categorized, bool scientific, bool metadata);
void viewOptionsChangedSlot(bool categorized, bool scientific, bool metadata, bool description);
void splitterChanged(QByteArray state);
private:
UAVObjectBrowserWidget *m_widget;
UAVObjectBrowserConfiguration *m_config;

View File

@ -6,5 +6,6 @@
<file>images/up_alt.png</file>
<file>images/trash.png</file>
<file>images/1343241276_eye.png</file>
<file>resources/uavodescription.mustache</file>
</qresource>
</RCC>

View File

@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>786</width>
<height>300</height>
<height>462</height>
</rect>
</property>
<property name="windowTitle">
@ -220,7 +220,63 @@
</layout>
</item>
<item>
<widget class="QTreeView" name="treeView"/>
<widget class="QWidget" name="widget" native="true">
<layout class="QVBoxLayout" name="verticalLayout_3">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QSplitter" name="splitter">
<property name="lineWidth">
<number>0</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<widget class="QTreeView" name="treeView">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
</widget>
<widget class="QTextEdit" name="descriptionText">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>150</height>
</size>
</property>
<property name="horizontalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
<property name="textInteractionFlags">
<set>Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse</set>
</property>
<property name="placeholderText">
<string>This space shows a description of the selected UAVObject.</string>
</property>
</widget>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>

View File

@ -29,28 +29,28 @@
UAVObjectBrowserConfiguration::UAVObjectBrowserConfiguration(QString classId, QSettings *qSettings, QObject *parent) :
IUAVGadgetConfiguration(classId, parent),
m_unknownObjectColor(QColor(Qt::gray)),
m_recentlyUpdatedColor(QColor(255, 230, 230)),
m_manuallyChangedColor(QColor(230, 230, 255)),
m_onlyHilightChangedValues(false),
m_recentlyUpdatedTimeout(500),
m_useCategorizedView(false),
m_useScientificView(false),
m_showMetaData(false)
m_showMetaData(false),
m_showDescription(false)
{
// if a saved configuration exists load it
if (qSettings != 0) {
QColor recent = qSettings->value("recentlyUpdatedColor").value<QColor>();
QColor manual = qSettings->value("manuallyChangedColor").value<QColor>();
int timeout = qSettings->value("recentlyUpdatedTimeout").toInt();
bool hilight = qSettings->value("onlyHilightChangedValues").toBool();
m_unknownObjectColor = qSettings->value("unknownObjectColor", QVariant(QColor(Qt::gray))).value<QColor>();
m_useCategorizedView = qSettings->value("CategorizedView").toBool();
m_useScientificView = qSettings->value("ScientificView").toBool();
m_showMetaData = qSettings->value("showMetaData").toBool();
m_recentlyUpdatedColor = recent;
m_manuallyChangedColor = manual;
m_recentlyUpdatedTimeout = timeout;
m_onlyHilightChangedValues = hilight;
m_showDescription = qSettings->value("showDescription").toBool();
m_splitterState = qSettings->value("splitterState").toByteArray();
m_recentlyUpdatedColor = qSettings->value("recentlyUpdatedColor").value<QColor>();
m_manuallyChangedColor = qSettings->value("manuallyChangedColor").value<QColor>();
m_recentlyUpdatedTimeout = qSettings->value("recentlyUpdatedTimeout").toInt();
m_onlyHilightChangedValues = qSettings->value("onlyHilightChangedValues").toBool();
}
}
@ -64,7 +64,10 @@ IUAVGadgetConfiguration *UAVObjectBrowserConfiguration::clone()
m->m_onlyHilightChangedValues = m_onlyHilightChangedValues;
m->m_useCategorizedView = m_useCategorizedView;
m->m_useScientificView = m_useScientificView;
m->m_splitterState = m_splitterState;
m->m_showMetaData = m_showMetaData;
m->m_unknownObjectColor = m_unknownObjectColor;
m->m_showDescription = m_showDescription;
return m;
}
@ -74,6 +77,7 @@ IUAVGadgetConfiguration *UAVObjectBrowserConfiguration::clone()
*/
void UAVObjectBrowserConfiguration::saveConfig(QSettings *qSettings) const
{
qSettings->setValue("unknownObjectColor", m_unknownObjectColor);
qSettings->setValue("recentlyUpdatedColor", m_recentlyUpdatedColor);
qSettings->setValue("manuallyChangedColor", m_manuallyChangedColor);
qSettings->setValue("recentlyUpdatedTimeout", m_recentlyUpdatedTimeout);
@ -81,4 +85,6 @@ void UAVObjectBrowserConfiguration::saveConfig(QSettings *qSettings) const
qSettings->setValue("CategorizedView", m_useCategorizedView);
qSettings->setValue("ScientificView", m_useScientificView);
qSettings->setValue("showMetaData", m_showMetaData);
qSettings->setValue("showDescription", m_showDescription);
qSettings->setValue("splitterState", m_splitterState);
}

View File

@ -34,19 +34,26 @@
using namespace Core;
class UAVObjectBrowserConfiguration : public IUAVGadgetConfiguration {
Q_OBJECT Q_PROPERTY(QColor m_recentlyUpdatedColor READ recentlyUpdatedColor WRITE setRecentlyUpdatedColor)
Q_OBJECT Q_PROPERTY(QColor m_unknownObjectColor READ unknownObjectColor WRITE setUnknownObjectColor)
Q_PROPERTY(QColor m_recentlyUpdatedColor READ recentlyUpdatedColor WRITE setRecentlyUpdatedColor)
Q_PROPERTY(QColor m_manuallyChangedColor READ manuallyChangedColor WRITE setManuallyChangedColor)
Q_PROPERTY(int m_recentlyUpdatedTimeout READ recentlyUpdatedTimeout WRITE setRecentlyUpdatedTimeout)
Q_PROPERTY(bool m_onlyHilightChangedValues READ onlyHighlightChangedValues WRITE setOnlyHighlightChangedValues)
Q_PROPERTY(bool m_useCategorizedView READ categorizedView WRITE setCategorizedView)
Q_PROPERTY(bool m_useScientificView READ scientificView WRITE setScientificView)
Q_PROPERTY(bool m_showDescription READ showDescription WRITE setShowDescription)
Q_PROPERTY(bool m_showMetaData READ showMetaData WRITE setShowMetaData)
Q_PROPERTY(QByteArray m_splitterState READ splitterState WRITE setSplitterState)
public:
explicit UAVObjectBrowserConfiguration(QString classId, QSettings *qSettings = 0, QObject *parent = 0);
void saveConfig(QSettings *settings) const;
IUAVGadgetConfiguration *clone();
QColor unknownObjectColor() const
{
return m_unknownObjectColor;
}
QColor recentlyUpdatedColor() const
{
return m_recentlyUpdatedColor;
@ -75,10 +82,23 @@ public:
{
return m_showMetaData;
}
bool showDescription() const
{
return m_showDescription;
}
QByteArray splitterState() const
{
return m_splitterState;
}
signals:
public slots:
void setUnknownObjectColor(QColor color)
{
m_unknownObjectColor = color;
}
void setRecentlyUpdatedColor(QColor color)
{
m_recentlyUpdatedColor = color;
@ -107,8 +127,18 @@ public slots:
{
m_showMetaData = value;
}
void setShowDescription(bool value)
{
m_showDescription = value;
}
void setSplitterState(QByteArray arg)
{
m_splitterState = arg;
}
private:
QColor m_unknownObjectColor;
QColor m_recentlyUpdatedColor;
QColor m_manuallyChangedColor;
bool m_onlyHilightChangedValues;
@ -116,6 +146,8 @@ private:
bool m_useCategorizedView;
bool m_useScientificView;
bool m_showMetaData;
bool m_showDescription;
QByteArray m_splitterState;
};
#endif // UAVOBJECTBROWSERCONFIGURATION_H

View File

@ -50,6 +50,7 @@ QWidget *UAVObjectBrowserOptionsPage::createPage(QWidget *parent)
m_page->recentlyUpdatedButton->setColor(m_config->recentlyUpdatedColor());
m_page->manuallyChangedButton->setColor(m_config->manuallyChangedColor());
m_page->unknownButton->setColor(m_config->unknownObjectColor());
m_page->recentlyUpdatedTimeoutSpinBox->setValue(m_config->recentlyUpdatedTimeout());
m_page->hilightBox->setChecked(m_config->onlyHighlightChangedValues());
@ -58,6 +59,7 @@ QWidget *UAVObjectBrowserOptionsPage::createPage(QWidget *parent)
void UAVObjectBrowserOptionsPage::apply()
{
m_config->setUnknownObjectColor(m_page->unknownButton->color());
m_config->setRecentlyUpdatedColor(m_page->recentlyUpdatedButton->color());
m_config->setManuallyChangedColor(m_page->manuallyChangedButton->color());
m_config->setRecentlyUpdatedTimeout(m_page->recentlyUpdatedTimeoutSpinBox->value());

View File

@ -14,7 +14,16 @@
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
@ -33,12 +42,21 @@
<rect>
<x>0</x>
<y>0</y>
<width>482</width>
<height>194</height>
<width>507</width>
<height>178</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout">
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item row="0" column="0">
@ -48,6 +66,32 @@
</property>
</widget>
</item>
<item row="6" column="2">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="2">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="1">
<widget class="Utils::QtColorButton" name="recentlyUpdatedButton">
<property name="sizePolicy">
@ -67,10 +111,33 @@
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_2">
<item row="4" column="0">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Manually changed color:</string>
<string>Recently updated timeout (ms):</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QCheckBox" name="hilightBox">
<property name="text">
<string>Only highlight nodes when value actually changes</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QSpinBox" name="recentlyUpdatedTimeoutSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximum">
<number>100000000</number>
</property>
<property name="singleStep">
<number>100</number>
</property>
</widget>
</item>
@ -93,61 +160,38 @@
</property>
</widget>
</item>
<item row="1" column="2">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_3">
<item row="1" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Recently updated timeout (ms):</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QSpinBox" name="recentlyUpdatedTimeoutSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximum">
<number>100000000</number>
</property>
<property name="singleStep">
<number>100</number>
<string>Manually changed color:</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QCheckBox" name="hilightBox">
<widget class="QLabel" name="label_4">
<property name="text">
<string>Only highlight nodes when value actually changes</string>
<string>Unknown object color:</string>
</property>
</widget>
</item>
<item row="4" column="2">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
<item row="3" column="1">
<widget class="Utils::QtColorButton" name="unknownButton">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="sizeHint" stdset="0">
<property name="minimumSize">
<size>
<width>20</width>
<height>40</height>
<width>64</width>
<height>0</height>
</size>
</property>
</spacer>
<property name="text">
<string/>
</property>
</widget>
</item>
</layout>
</widget>
@ -162,6 +206,14 @@
<header>utils/qtcolorbutton.h</header>
</customwidget>
</customwidgets>
<tabstops>
<tabstop>scrollArea</tabstop>
<tabstop>recentlyUpdatedButton</tabstop>
<tabstop>manuallyChangedButton</tabstop>
<tabstop>unknownButton</tabstop>
<tabstop>recentlyUpdatedTimeoutSpinBox</tabstop>
<tabstop>hilightBox</tabstop>
</tabstops>
<resources/>
<connections/>
</ui>

View File

@ -39,6 +39,7 @@
#include <QtCore/QDebug>
#include <QItemEditorFactory>
#include "extensionsystem/pluginmanager.h"
#include "utils/mustache.h"
UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent)
{
@ -50,15 +51,19 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent
m_model = new UAVObjectTreeModel();
m_browser->treeView->setModel(m_model);
m_browser->treeView->setColumnWidth(0, 300);
// m_browser->treeView->expandAll();
BrowserItemDelegate *m_delegate = new BrowserItemDelegate();
m_browser->treeView->setItemDelegate(m_delegate);
m_browser->treeView->setEditTriggers(QAbstractItemView::AllEditTriggers);
m_browser->treeView->setSelectionBehavior(QAbstractItemView::SelectItems);
m_mustacheTemplate = loadFileIntoString(QString(":/uavobjectbrowser/resources/uavodescription.mustache"));
showMetaData(m_viewoptions->cbMetaData->isChecked());
connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)), this, SLOT(currentChanged(QModelIndex, QModelIndex)), Qt::UniqueConnection);
showDescription(m_viewoptions->cbDescription->isChecked());
connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)),
this, SLOT(currentChanged(QModelIndex, QModelIndex)), Qt::UniqueConnection);
connect(m_viewoptions->cbMetaData, SIGNAL(toggled(bool)), this, SLOT(showMetaData(bool)));
connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(categorize(bool)));
connect(m_viewoptions->cbDescription, SIGNAL(toggled(bool)), this, SLOT(showDescription(bool)));
connect(m_browser->saveSDButton, SIGNAL(clicked()), this, SLOT(saveObject()));
connect(m_browser->readSDButton, SIGNAL(clicked()), this, SLOT(loadObject()));
connect(m_browser->eraseSDButton, SIGNAL(clicked()), this, SLOT(eraseObject()));
@ -69,6 +74,8 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent
connect(m_viewoptions->cbScientific, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot()));
connect(m_viewoptions->cbMetaData, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot()));
connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot()));
connect(m_viewoptions->cbDescription, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot()));
connect(m_browser->splitter, SIGNAL(splitterMoved(int, int)), this, SLOT(splitterMoved()));
enableSendRequest(false);
}
@ -77,11 +84,17 @@ UAVObjectBrowserWidget::~UAVObjectBrowserWidget()
delete m_browser;
}
void UAVObjectBrowserWidget::setViewOptions(bool categorized, bool scientific, bool metadata)
void UAVObjectBrowserWidget::setViewOptions(bool categorized, bool scientific, bool metadata, bool description)
{
m_viewoptions->cbCategorized->setChecked(categorized);
m_viewoptions->cbMetaData->setChecked(metadata);
m_viewoptions->cbScientific->setChecked(scientific);
m_viewoptions->cbDescription->setChecked(description);
}
void UAVObjectBrowserWidget::setSplitterState(QByteArray state)
{
m_browser->splitter->restoreState(state);
}
void UAVObjectBrowserWidget::showMetaData(bool show)
@ -92,6 +105,11 @@ void UAVObjectBrowserWidget::showMetaData(bool show)
}
}
void UAVObjectBrowserWidget::showDescription(bool show)
{
m_browser->descriptionText->setVisible(show);
}
void UAVObjectBrowserWidget::categorize(bool categorize)
{
UAVObjectTreeModel *tmpModel = m_model;
@ -101,6 +119,7 @@ void UAVObjectBrowserWidget::categorize(bool categorize)
m_model->setManuallyChangedColor(m_manuallyChangedColor);
m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout);
m_model->setOnlyHilightChangedValues(m_onlyHilightChangedValues);
m_model->setUnknowObjectColor(m_unknownObjectColor);
m_browser->treeView->setModel(m_model);
showMetaData(m_viewoptions->cbMetaData->isChecked());
connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)), this, SLOT(currentChanged(QModelIndex, QModelIndex)), Qt::UniqueConnection);
@ -116,6 +135,7 @@ void UAVObjectBrowserWidget::useScientificNotation(bool scientific)
m_model->setRecentlyUpdatedColor(m_recentlyUpdatedColor);
m_model->setManuallyChangedColor(m_manuallyChangedColor);
m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout);
m_model->setUnknowObjectColor(m_unknownObjectColor);
m_browser->treeView->setModel(m_model);
showMetaData(m_viewoptions->cbMetaData->isChecked());
connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)), this, SLOT(currentChanged(QModelIndex, QModelIndex)), Qt::UniqueConnection);
@ -160,6 +180,17 @@ ObjectTreeItem *UAVObjectBrowserWidget::findCurrentObjectTreeItem()
return objItem;
}
QString UAVObjectBrowserWidget::loadFileIntoString(QString fileName)
{
QFile file(fileName);
file.open(QIODevice::ReadOnly);
QTextStream stream(&file);
QString line = stream.readAll();
file.close();
return line;
}
void UAVObjectBrowserWidget::saveObject()
{
this->setFocus();
@ -228,6 +259,7 @@ void UAVObjectBrowserWidget::currentChanged(const QModelIndex &current, const QM
enable = false;
}
enableSendRequest(enable);
updateDescription();
}
void UAVObjectBrowserWidget::viewSlot()
@ -244,7 +276,94 @@ void UAVObjectBrowserWidget::viewSlot()
void UAVObjectBrowserWidget::viewOptionsChangedSlot()
{
emit viewOptionsChanged(m_viewoptions->cbCategorized->isChecked(), m_viewoptions->cbScientific->isChecked(), m_viewoptions->cbMetaData->isChecked());
emit viewOptionsChanged(m_viewoptions->cbCategorized->isChecked(), m_viewoptions->cbScientific->isChecked(),
m_viewoptions->cbMetaData->isChecked(), m_viewoptions->cbDescription->isChecked());
}
void UAVObjectBrowserWidget::splitterMoved()
{
emit splitterChanged(m_browser->splitter->saveState());
}
QString UAVObjectBrowserWidget::createObjectDescription(UAVObject *object)
{
QString mustache(m_mustacheTemplate);
QVariantHash uavoHash;
uavoHash["OBJECT_NAME_TITLE"] = tr("Name");
uavoHash["OBJECT_NAME"] = object->getName();
uavoHash["CATEGORY_TITLE"] = tr("Category");
uavoHash["CATEGORY"] = object->getCategory();
uavoHash["TYPE_TITLE"] = tr("Type");
uavoHash["TYPE"] = object->isMetaDataObject() ? tr("Metadata") : object->isSettingsObject() ? tr("Setting") : tr("Data");
uavoHash["SIZE_TITLE"] = tr("Size");
uavoHash["SIZE"] = object->getNumBytes();
uavoHash["DESCRIPTION_TITLE"] = tr("Description");
uavoHash["DESCRIPTION"] = object->getDescription().replace("@ref", "");
uavoHash["MULTI_INSTANCE_TITLE"] = tr("Multi");
uavoHash["MULTI_INSTANCE"] = object->isSingleInstance() ? tr("No") : tr("Yes");
uavoHash["FIELDS_NAME_TITLE"] = tr("Fields");
QVariantList fields;
foreach(UAVObjectField * field, object->getFields()) {
QVariantHash fieldHash;
fieldHash["FIELD_NAME_TITLE"] = tr("Name");
fieldHash["FIELD_NAME"] = field->getName();
fieldHash["FIELD_TYPE_TITLE"] = tr("Type");
fieldHash["FIELD_TYPE"] = QString("%1%2").arg(field->getTypeAsString(),
(field->getNumElements() > 1 ? QString("[%1]").arg(field->getNumElements()) : QString()));
if (!field->getUnits().isEmpty()) {
fieldHash["FIELD_UNIT_TITLE"] = tr("Unit");
fieldHash["FIELD_UNIT"] = field->getUnits();
}
if (!field->getOptions().isEmpty()) {
fieldHash["FIELD_OPTIONS_TITLE"] = tr("Options");
QVariantList options;
foreach(QString option, field->getOptions()) {
QVariantHash optionHash;
optionHash["FIELD_OPTION"] = option;
if (!options.isEmpty()) {
optionHash["FIELD_OPTION_DELIM"] = ", ";
}
options.append(optionHash);
}
fieldHash["FIELD_OPTIONS"] = options;
}
if (field->getElementNames().count() > 1) {
fieldHash["FIELD_ELEMENTS_TITLE"] = tr("Elements");
QVariantList elements;
for (int i = 0; i < field->getElementNames().count(); i++) {
QString element = field->getElementNames().at(i);
QVariantHash elementHash;
elementHash["FIELD_ELEMENT"] = element;
QString limitsString = field->getLimitsAsString(i);
if (!limitsString.isEmpty()) {
elementHash["FIELD_ELEMENT_LIMIT"] = limitsString.prepend(" (").append(")");
}
if (!elements.isEmpty()) {
elementHash["FIELD_ELEMENT_DELIM"] = ", ";
}
elements.append(elementHash);
}
fieldHash["FIELD_ELEMENTS"] = elements;
} else if (!field->getLimitsAsString(0).isEmpty()) {
fieldHash["FIELD_LIMIT_TITLE"] = tr("Limits");
fieldHash["FIELD_LIMIT"] = field->getLimitsAsString(0);
}
if (!field->getDescription().isEmpty()) {
fieldHash["FIELD_DESCRIPTION_TITLE"] = tr("Description");
fieldHash["FIELD_DESCRIPTION"] = field->getDescription();
}
fields.append(fieldHash);
}
uavoHash["FIELDS"] = fields;
Mustache::QtVariantContext context(uavoHash);
Mustache::Renderer renderer;
return renderer.render(mustache, &context);
}
void UAVObjectBrowserWidget::enableSendRequest(bool enable)
@ -255,3 +374,17 @@ void UAVObjectBrowserWidget::enableSendRequest(bool enable)
m_browser->readSDButton->setEnabled(enable);
m_browser->eraseSDButton->setEnabled(enable);
}
void UAVObjectBrowserWidget::updateDescription()
{
ObjectTreeItem *objItem = findCurrentObjectTreeItem();
if (objItem) {
UAVObject *obj = objItem->object();
if (obj) {
m_browser->descriptionText->setText(createObjectDescription(obj));
return;
}
}
m_browser->descriptionText->setText("");
}

View File

@ -44,25 +44,37 @@ class UAVObjectBrowserWidget : public QWidget {
public:
UAVObjectBrowserWidget(QWidget *parent = 0);
~UAVObjectBrowserWidget();
void setUnknownObjectColor(QColor color)
{
m_unknownObjectColor = color;
m_model->setUnknowObjectColor(color);
}
void setRecentlyUpdatedColor(QColor color)
{
m_recentlyUpdatedColor = color; m_model->setRecentlyUpdatedColor(color);
m_recentlyUpdatedColor = color;
m_model->setRecentlyUpdatedColor(color);
}
void setManuallyChangedColor(QColor color)
{
m_manuallyChangedColor = color; m_model->setManuallyChangedColor(color);
m_manuallyChangedColor = color;
m_model->setManuallyChangedColor(color);
}
void setRecentlyUpdatedTimeout(int timeout)
{
m_recentlyUpdatedTimeout = timeout; m_model->setRecentlyUpdatedTimeout(timeout);
m_recentlyUpdatedTimeout = timeout;
m_model->setRecentlyUpdatedTimeout(timeout);
}
void setOnlyHilightChangedValues(bool hilight)
{
m_onlyHilightChangedValues = hilight; m_model->setOnlyHilightChangedValues(hilight);
m_onlyHilightChangedValues = hilight;
m_model->setOnlyHilightChangedValues(hilight);
}
void setViewOptions(bool categorized, bool scientific, bool metadata);
void setViewOptions(bool categorized, bool scientific, bool metadata, bool description);
void setSplitterState(QByteArray state);
public slots:
void showMetaData(bool show);
void showDescription(bool show);
void categorize(bool categorize);
void useScientificNotation(bool scientific);
@ -75,8 +87,11 @@ private slots:
void currentChanged(const QModelIndex &current, const QModelIndex &previous);
void viewSlot();
void viewOptionsChangedSlot();
void splitterMoved();
QString createObjectDescription(UAVObject *object);
signals:
void viewOptionsChanged(bool categorized, bool scientific, bool metadata);
void viewOptionsChanged(bool categorized, bool scientific, bool metadata, bool description);
void splitterChanged(QByteArray state);
private:
QPushButton *m_requestUpdate;
QPushButton *m_sendUpdate;
@ -86,13 +101,17 @@ private:
UAVObjectTreeModel *m_model;
int m_recentlyUpdatedTimeout;
QColor m_unknownObjectColor;
QColor m_recentlyUpdatedColor;
QColor m_manuallyChangedColor;
bool m_onlyHilightChangedValues;
QString m_mustacheTemplate;
void updateObjectPersistance(ObjectPersistence::OperationOptions op, UAVObject *obj);
void enableSendRequest(bool enable);
void updateDescription();
ObjectTreeItem *findCurrentObjectTreeItem();
QString loadFileIntoString(QString fileName);
};
#endif /* UAVOBJECTBROWSERWIDGET_H_ */

View File

@ -43,11 +43,14 @@ UAVObjectTreeModel::UAVObjectTreeModel(QObject *parent, bool categorize, bool us
m_categorize(categorize),
m_recentlyUpdatedTimeout(500), // ms
m_recentlyUpdatedColor(QColor(255, 230, 230)),
m_manuallyChangedColor(QColor(230, 230, 255))
m_manuallyChangedColor(QColor(230, 230, 255)),
m_unknownObjectColor(QColor(Qt::gray))
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
Q_ASSERT(objManager);
// Create highlight manager, let it run every 300 ms.
m_highlightManager = new HighLightManager(300);
connect(objManager, SIGNAL(newObject(UAVObject *)), this, SLOT(newObject(UAVObject *)));
@ -112,9 +115,10 @@ void UAVObjectTreeModel::addDataObject(UAVDataObject *obj)
if (existing) {
addInstance(obj, existing);
} else {
DataObjectTreeItem *dataTreeItem = new DataObjectTreeItem(obj->getName() + " (" + QString::number(obj->getNumBytes()) + " bytes)");
DataObjectTreeItem *dataTreeItem = new DataObjectTreeItem(obj->getName(), obj);
dataTreeItem->setHighlightManager(m_highlightManager);
connect(dataTreeItem, SIGNAL(updateHighlight(TreeItem *)), this, SLOT(updateHighlight(TreeItem *)));
connect(dataTreeItem, SIGNAL(updateIsKnown(TreeItem *)), this, SLOT(updateIsKnown(TreeItem *)));
parent->insertChild(dataTreeItem);
root->addObjectTreeItem(obj->getObjID(), dataTreeItem);
UAVMetaObject *meta = obj->getMetaObject();
@ -165,16 +169,18 @@ MetaObjectTreeItem *UAVObjectTreeModel::addMetaObject(UAVMetaObject *obj, TreeIt
void UAVObjectTreeModel::addInstance(UAVObject *obj, TreeItem *parent)
{
connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(highlightUpdatedObject(UAVObject *)));
connect(obj, SIGNAL(isKnownChanged(UAVObject *, bool)), this, SLOT(isKnownChanged(UAVObject *, bool)));
TreeItem *item;
if (obj->isSingleInstance()) {
item = parent;
DataObjectTreeItem *p = static_cast<DataObjectTreeItem *>(parent);
p->setObject(obj);
DataObjectTreeItem *objectItem = static_cast<DataObjectTreeItem *>(parent);
connect(objectItem, SIGNAL(updateIsKnown(TreeItem *)), this, SLOT(updateIsKnown(TreeItem *)));
} else {
QString name = tr("Instance") + " " + QString::number(obj->getInstID());
item = new InstanceTreeItem(obj, name);
item->setHighlightManager(m_highlightManager);
connect(item, SIGNAL(updateHighlight(TreeItem *)), this, SLOT(updateHighlight(TreeItem *)));
connect(item, SIGNAL(updateIsKnown(TreeItem *)), this, SLOT(updateIsKnown(TreeItem *)));
parent->appendChild(item);
}
foreach(UAVObjectField * field, obj->getFields()) {
@ -192,6 +198,7 @@ void UAVObjectTreeModel::addArrayField(UAVObjectField *field, TreeItem *parent)
item->setHighlightManager(m_highlightManager);
connect(item, SIGNAL(updateHighlight(TreeItem *)), this, SLOT(updateHighlight(TreeItem *)));
connect(item, SIGNAL(updateIsKnown(TreeItem *)), this, SLOT(updateIsKnown(TreeItem *)));
for (uint i = 0; i < field->getNumElements(); ++i) {
addSingleField(i, field, item);
}
@ -245,7 +252,9 @@ void UAVObjectTreeModel::addSingleField(int index, UAVObjectField *field, TreeIt
Q_ASSERT(false);
}
item->setHighlightManager(m_highlightManager);
item->setDescription(field->getDescription());
connect(item, SIGNAL(updateHighlight(TreeItem *)), this, SLOT(updateHighlight(TreeItem *)));
connect(item, SIGNAL(updateIsKnown(TreeItem *)), this, SLOT(updateIsKnown(TreeItem *)));
parent->appendChild(item);
}
@ -352,17 +361,21 @@ QVariant UAVObjectTreeModel::data(const QModelIndex &index, int role) const
return QVariant();
}
if (index.column() == TreeItem::dataColumn && role == Qt::EditRole) {
TreeItem *item = static_cast<TreeItem *>(index.internalPointer());
TreeItem *item = static_cast<TreeItem *>(index.internalPointer());
if (index.column() == TreeItem::DATA_COLUMN && role == Qt::EditRole) {
return item->data(index.column());
}
if (role == Qt::ToolTipRole) {
TreeItem *item = static_cast<TreeItem *>(index.internalPointer());
return item->description();
}
TreeItem *item = static_cast<TreeItem *>(index.internalPointer());
if (role == Qt::ForegroundRole) {
if (!dynamic_cast<TopTreeItem *>(item) && !item->isKnown()) {
return QVariant(m_unknownObjectColor);
}
}
if (index.column() == 0 && role == Qt::BackgroundRole) {
if (!dynamic_cast<TopTreeItem *>(item) && item->highlighted()) {
@ -370,7 +383,7 @@ QVariant UAVObjectTreeModel::data(const QModelIndex &index, int role) const
}
}
if (index.column() == TreeItem::dataColumn && role == Qt::BackgroundRole) {
if (index.column() == TreeItem::DATA_COLUMN && role == Qt::BackgroundRole) {
FieldTreeItem *fieldItem = dynamic_cast<FieldTreeItem *>(item);
if (fieldItem && fieldItem->highlighted()) {
return QVariant(m_recentlyUpdatedColor);
@ -385,7 +398,7 @@ QVariant UAVObjectTreeModel::data(const QModelIndex &index, int role) const
return QVariant();
}
if (index.column() == TreeItem::dataColumn) {
if (index.column() == TreeItem::DATA_COLUMN) {
EnumFieldTreeItem *fieldItem = dynamic_cast<EnumFieldTreeItem *>(item);
if (fieldItem) {
int enumIndex = fieldItem->data(index.column()).toInt();
@ -411,7 +424,7 @@ Qt::ItemFlags UAVObjectTreeModel::flags(const QModelIndex &index) const
return 0;
}
if (index.column() == TreeItem::dataColumn) {
if (index.column() == TreeItem::DATA_COLUMN) {
TreeItem *item = static_cast<TreeItem *>(index.internalPointer());
if (item->isEditable()) {
return Qt::ItemIsEnabled | Qt::ItemIsSelectable | Qt::ItemIsEditable;
@ -482,5 +495,22 @@ void UAVObjectTreeModel::updateHighlight(TreeItem *item)
QModelIndex itemIndex = index(item);
Q_ASSERT(itemIndex != QModelIndex());
emit dataChanged(itemIndex, itemIndex.sibling(itemIndex.row(), TreeItem::dataColumn));
emit dataChanged(itemIndex, itemIndex.sibling(itemIndex.row(), TreeItem::DATA_COLUMN));
}
void UAVObjectTreeModel::updateIsKnown(TreeItem *item)
{
QModelIndex itemIndex = index(item);
Q_ASSERT(itemIndex != QModelIndex());
emit dataChanged(itemIndex, itemIndex.sibling(itemIndex.row(), TreeItem::TITLE_COLUMN));
}
void UAVObjectTreeModel::isKnownChanged(UAVObject *object, bool isKnown)
{
Q_UNUSED(isKnown);
ObjectTreeItem *item = findObjectTreeItem(object);
if (item) {
item->updateIsKnown(isKnown);
}
}

View File

@ -62,6 +62,10 @@ public:
int rowCount(const QModelIndex &parent = QModelIndex()) const;
int columnCount(const QModelIndex &parent = QModelIndex()) const;
void setUnknowObjectColor(QColor color)
{
m_unknownObjectColor = color;
}
void setRecentlyUpdatedColor(QColor color)
{
m_recentlyUpdatedColor = color;
@ -88,8 +92,10 @@ public slots:
void newObject(UAVObject *obj);
private slots:
void updateHighlight(TreeItem *item);
void updateIsKnown(TreeItem *item);
void highlightUpdatedObject(UAVObject *obj);
void updateHighlight(TreeItem *);
void isKnownChanged(UAVObject *object, bool isKnown);
private:
void setupModelData(UAVObjectManager *objManager);
@ -115,6 +121,7 @@ private:
int m_recentlyUpdatedTimeout;
QColor m_recentlyUpdatedColor;
QColor m_manuallyChangedColor;
QColor m_unknownObjectColor;
bool m_onlyHilightChangedValues;
// Highlight manager to handle highlighting of tree items.

View File

@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>169</width>
<height>96</height>
<width>172</width>
<height>124</height>
</rect>
</property>
<property name="windowTitle">
@ -35,6 +35,13 @@
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="cbDescription">
<property name="text">
<string>Show Description</string>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>

View File

@ -41,10 +41,10 @@ UAVMetaObject::UAVMetaObject(quint32 objID, const QString & name, UAVObject *par
QStringList modesBitField;
modesBitField << tr("FlightReadOnly") << tr("GCSReadOnly") << tr("FlightTelemetryAcked") << tr("GCSTelemetryAcked") << tr("FlightUpdatePeriodic") << tr("FlightUpdateOnChange") << tr("GCSUpdatePeriodic") << tr("GCSUpdateOnChange") << tr("LoggingUpdatePeriodic") << tr("LoggingUpdateOnChange");
QList<UAVObjectField *> fields;
fields.append(new UAVObjectField(tr("Modes"), tr("boolean"), UAVObjectField::BITFIELD, modesBitField, QStringList()));
fields.append(new UAVObjectField(tr("Flight Telemetry Update Period"), tr("ms"), UAVObjectField::UINT16, 1, QStringList()));
fields.append(new UAVObjectField(tr("GCS Telemetry Update Period"), tr("ms"), UAVObjectField::UINT16, 1, QStringList()));
fields.append(new UAVObjectField(tr("Logging Update Period"), tr("ms"), UAVObjectField::UINT16, 1, QStringList()));
fields.append(new UAVObjectField(tr("Modes"), tr("Metadata modes"), tr("boolean"), UAVObjectField::BITFIELD, modesBitField, QStringList()));
fields.append(new UAVObjectField(tr("Flight Telemetry Update Period"), tr("This is how often flight side will update telemetry data"), tr("ms"), UAVObjectField::UINT16, 1, QStringList()));
fields.append(new UAVObjectField(tr("GCS Telemetry Update Period"), tr("This is how often GCS will update telemetry data"), tr("ms"), UAVObjectField::UINT16, 1, QStringList()));
fields.append(new UAVObjectField(tr("Logging Update Period"), tr("This is how often logging will be updated."), tr("ms"), UAVObjectField::UINT16, 1, QStringList()));
// Initialize parent
UAVObject::initialize(0);
UAVObject::initializeFields(fields, (quint8 *)&parentMetadata, sizeof(Metadata));

View File

@ -63,6 +63,7 @@ UAVObject::UAVObject(quint32 objID, bool isSingleInst, const QString & name)
this->data = 0;
this->numBytes = 0;
this->mutex = new QMutex(QMutex::Recursive);
m_isKnown = false;
}
/**
@ -603,6 +604,25 @@ void UAVObject::emitNewInstance(UAVObject *obj)
emit newInstance(obj);
}
bool UAVObject::isKnown() const
{
QMutexLocker locker(mutex);
return m_isKnown;
}
void UAVObject::setIsKnown(bool isKnown)
{
lock();
bool changed = m_isKnown != isKnown;
m_isKnown = isKnown;
unlock();
if (changed) {
emit isKnownChanged(this, isKnown);
}
}
bool UAVObject::isSettingsObject()
{
return false;

View File

@ -142,6 +142,9 @@ public:
void emitTransactionCompleted(bool success);
void emitNewInstance(UAVObject *);
bool isKnown() const;
void setIsKnown(bool isKnown);
virtual bool isSettingsObject();
virtual bool isDataObject();
virtual bool isMetaDataObject();
@ -178,9 +181,7 @@ signals:
void updateRequested(UAVObject *obj, bool all = false);
void transactionCompleted(UAVObject *obj, bool success);
void newInstance(UAVObject *obj);
private slots:
void fieldUpdated(UAVObjectField *field);
void isKnownChanged(UAVObject *obj, bool isKnown);
protected:
quint32 objID;
@ -197,6 +198,12 @@ protected:
void initializeFields(QList<UAVObjectField *> & fields, quint8 *data, quint32 numBytes);
void setDescription(const QString & description);
void setCategory(const QString & category);
private:
bool m_isKnown;
private slots:
void fieldUpdated(UAVObjectField *field);
};
#endif // UAVOBJECT_H

View File

@ -30,7 +30,7 @@
#include <QDebug>
#include <QtWidgets>
UAVObjectField::UAVObjectField(const QString & name, const QString & units, FieldType type, quint32 numElements, const QStringList & options, const QString &limits)
UAVObjectField::UAVObjectField(const QString & name, const QString & description, const QString & units, FieldType type, quint32 numElements, const QStringList & options, const QString &limits)
{
QStringList elementNames;
@ -39,18 +39,19 @@ UAVObjectField::UAVObjectField(const QString & name, const QString & units, Fiel
elementNames.append(QString("%1").arg(n));
}
// Initialize
constructorInitialize(name, units, type, elementNames, options, limits);
constructorInitialize(name, description, units, type, elementNames, options, limits);
}
UAVObjectField::UAVObjectField(const QString & name, const QString & units, FieldType type, const QStringList & elementNames, const QStringList & options, const QString &limits)
UAVObjectField::UAVObjectField(const QString & name, const QString & description, const QString & units, FieldType type, const QStringList & elementNames, const QStringList & options, const QString &limits)
{
constructorInitialize(name, units, type, elementNames, options, limits);
constructorInitialize(name, description, units, type, elementNames, options, limits);
}
void UAVObjectField::constructorInitialize(const QString & name, const QString & units, FieldType type, const QStringList & elementNames, const QStringList & options, const QString &limits)
void UAVObjectField::constructorInitialize(const QString & name, const QString & description, const QString & units, FieldType type, const QStringList & elementNames, const QStringList & options, const QString &limits)
{
// Copy params
this->name = name;
this->description = description;
this->units = units;
this->type = type;
this->options = options;
@ -458,11 +459,65 @@ bool UAVObjectField::isWithinLimits(QVariant var, quint32 index, int board)
default:
return true;
}
default:
return true;
}
}
return true;
}
QString UAVObjectField::getLimitsAsString(quint32 index, int board)
{
QString limitString;
if (elementLimits.keys().contains(index)) {
foreach(LimitStruct struc, elementLimits.value(index)) {
if ((struc.board != board) && board != 0 && struc.board != 0) {
continue;
}
switch (struc.type) {
case EQUAL:
{
limitString.append(tr("one of")).append(" [");
bool first = true;
foreach(QVariant var, struc.values) {
if (!first) {
limitString.append(", ");
}
limitString.append(var.toString());
first = false;
}
return limitString.append("]");
}
case NOT_EQUAL:
{
limitString.append(tr("none of")).append(" [");
bool first = true;
foreach(QVariant var, struc.values) {
if (!first) {
limitString.append(", ");
}
limitString.append(var.toString());
first = false;
}
return limitString.append("]");
}
case BIGGER: return limitString.append(QString("%1 %2").arg(tr("more than"), struc.values.at(0).toString()));
case BETWEEN: return limitString.append(QString("%1 %2 %3 %4")
.arg(tr("between"), struc.values.at(0).toString(),
tr(" and "), struc.values.at(1).toString()));
case SMALLER: return limitString.append(QString("%1 %2").arg(tr("less than"), struc.values.at(0).toString()));
default:
break;
}
}
}
return limitString;
}
QVariant UAVObjectField::getMaxLimit(quint32 index, int board)
{
if (!elementLimits.keys().contains(index)) {
@ -478,20 +533,14 @@ QVariant UAVObjectField::getMaxLimit(quint32 index, int board)
case BIGGER:
return QVariant();
break;
break;
case BETWEEN:
return struc.values.at(1);
break;
case SMALLER:
return struc.values.at(0);
break;
default:
return QVariant();
break;
}
}
return QVariant();
@ -511,20 +560,14 @@ QVariant UAVObjectField::getMinLimit(quint32 index, int board)
case SMALLER:
return QVariant();
break;
break;
case BETWEEN:
return struc.values.at(0);
break;
case BIGGER:
return struc.values.at(0);
break;
default:
return QVariant();
break;
}
}
return QVariant();
@ -609,6 +652,11 @@ QString UAVObjectField::getName()
return name;
}
QString UAVObjectField::getDescription()
{
return description;
}
QString UAVObjectField::getUnits()
{
return units;

View File

@ -45,20 +45,21 @@ class UAVOBJECTS_EXPORT UAVObjectField : public QObject {
public:
typedef enum { INT8 = 0, INT16, INT32, UINT8, UINT16, UINT32, FLOAT32, ENUM, BITFIELD, STRING } FieldType;
typedef enum { EQUAL, NOT_EQUAL, BETWEEN, BIGGER, SMALLER } LimitType;
typedef enum { EQUAL, NOT_EQUAL, BETWEEN, BIGGER, SMALLER, UNDEFINED } LimitType;
typedef struct {
LimitType type;
QList<QVariant> values;
int board;
} LimitStruct;
UAVObjectField(const QString & name, const QString & units, FieldType type, quint32 numElements, const QStringList & options, const QString & limits = QString());
UAVObjectField(const QString & name, const QString & units, FieldType type, const QStringList & elementNames, const QStringList & options, const QString & limits = QString());
UAVObjectField(const QString & name, const QString & description, const QString & units, FieldType type, quint32 numElements, const QStringList & options, const QString & limits = QString());
UAVObjectField(const QString & name, const QString & description, const QString & units, FieldType type, const QStringList & elementNames, const QStringList & options, const QString & limits = QString());
void initialize(quint8 *data, quint32 dataOffset, UAVObject *obj);
UAVObject *getObject();
FieldType getType();
QString getTypeAsString();
QString getName();
QString getDescription();
QString getUnits();
quint32 getNumElements();
QStringList getElementNames();
@ -84,6 +85,7 @@ public:
void fromJson(const QJsonObject &jsonObject);
bool isWithinLimits(QVariant var, quint32 index, int board = 0);
QString getLimitsAsString(quint32 index, int board = 0);
QVariant getMaxLimit(quint32 index, int board = 0);
QVariant getMinLimit(quint32 index, int board = 0);
signals:
@ -91,6 +93,7 @@ signals:
protected:
QString name;
QString description;
QString units;
FieldType type;
QStringList elementNames;
@ -102,7 +105,7 @@ protected:
UAVObject *obj;
QMap<quint32, QList<LimitStruct> > elementLimits;
void clear();
void constructorInitialize(const QString & name, const QString & units, FieldType type, const QStringList & elementNames, const QStringList & options, const QString &limits);
void constructorInitialize(const QString & name, const QString & description, const QString & units, FieldType type, const QStringList & elementNames, const QStringList & options, const QString &limits);
void limitsInitialize(const QString &limits);
};

View File

@ -41,10 +41,13 @@ Telemetry::Telemetry(UAVTalk *utalk, UAVObjectManager *objMngr) : objMngr(objMng
mutex = new QMutex(QMutex::Recursive);
// Register all objects in the list
QList< QList<UAVObject *> > objs = objMngr->getObjects();
for (int objidx = 0; objidx < objs.length(); ++objidx) {
foreach(QList<UAVObject *> instances, objMngr->getObjects()) {
foreach(UAVObject * object, instances) {
// make sure we 'forget' all objects before we request it from the flight side
object->setIsKnown(false);
}
// we only need to register one instance per object type
registerObject(objs[objidx][0]);
registerObject(instances.first());
}
// Listen to new object creations
@ -74,6 +77,12 @@ Telemetry::Telemetry(UAVTalk *utalk, UAVObjectManager *objMngr) : objMngr(objMng
Telemetry::~Telemetry()
{
closeAllTransactions();
foreach(QList<UAVObject *> instances, objMngr->getObjects()) {
foreach(UAVObject * object, instances) {
// make sure we 'forget' all objects before we request it from the flight side
object->setIsKnown(false);
}
}
}
/**
@ -235,10 +244,14 @@ void Telemetry::transactionCompleted(UAVObject *obj, bool success)
if (transInfo) {
if (success) {
// We now know tat the flight side knows of this object.
obj->setIsKnown(true);
#ifdef VERBOSE_TELEMETRY
qDebug() << "Telemetry - transaction successful for object" << obj->toStringBrief();
#endif
} else {
obj->setIsKnown(false);
qWarning() << "Telemetry - !!! transaction failed for object" << obj->toStringBrief();
}

View File

@ -79,8 +79,6 @@ public:
void resetStats();
void transactionTimeout(ObjectTransactionInfo *info);
signals:
private:
// Constants
static const int REQ_TIMEOUT_MS = 250;

View File

@ -26,16 +26,18 @@
*/
#include "telemetrymanager.h"
#include "telemetry.h"
#include "telemetrymonitor.h"
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/icore.h>
#include <coreplugin/threadmanager.h>
TelemetryManager::TelemetryManager() : autopilotConnected(false)
TelemetryManager::TelemetryManager() : m_isAutopilotConnected(false)
{
moveToThread(Core::ICore::instance()->threadManager()->getRealTimeThread());
// Get UAVObjectManager instance
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
objMngr = pm->getObject<UAVObjectManager>();
m_uavobjectManager = pm->getObject<UAVObjectManager>();
// connect to start stop signals
connect(this, SIGNAL(myStart()), this, SLOT(onStart()), Qt::QueuedConnection);
@ -47,24 +49,24 @@ TelemetryManager::~TelemetryManager()
bool TelemetryManager::isConnected()
{
return autopilotConnected;
return m_isAutopilotConnected;
}
void TelemetryManager::start(QIODevice *dev)
{
device = dev;
m_telemetryDevice = dev;
// OP-1383
// take ownership of the device by moving it to the TelemetryManager thread (see TelemetryManager constructor)
// this removes the following runtime Qt warning and incidentally fixes GCS crashes:
// QObject: Cannot create children for a parent that is in a different thread.
// (Parent is QSerialPort(0x56af73f8), parent's thread is QThread(0x23f69ae8), current thread is QThread(0x2649cfd8)
device->moveToThread(thread());
m_telemetryDevice->moveToThread(thread());
emit myStart();
}
void TelemetryManager::onStart()
{
utalk = new UAVTalk(device, objMngr);
m_uavTalk = new UAVTalk(m_telemetryDevice, m_uavobjectManager);
if (false) {
// UAVTalk must be thread safe and for that:
// 1- all public methods must lock a mutex
@ -73,25 +75,25 @@ void TelemetryManager::onStart()
// It is assumed that the UAVObjectManager is thread safe
// Create the reader and move it to the reader thread
IODeviceReader *reader = new IODeviceReader(utalk);
reader->moveToThread(&readerThread);
IODeviceReader *reader = new IODeviceReader(m_uavTalk);
reader->moveToThread(&m_telemetryReaderThread);
// The reader will be deleted (later) when the thread finishes
connect(&readerThread, &QThread::finished, reader, &QObject::deleteLater);
connect(&m_telemetryReaderThread, &QThread::finished, reader, &QObject::deleteLater);
// Connect IO device to reader
connect(device, SIGNAL(readyRead()), reader, SLOT(read()));
connect(m_telemetryDevice, SIGNAL(readyRead()), reader, SLOT(read()));
// start the reader thread
readerThread.start();
m_telemetryReaderThread.start();
} else {
// Connect IO device to reader
connect(device, SIGNAL(readyRead()), utalk, SLOT(processInputStream()));
connect(m_telemetryDevice, SIGNAL(readyRead()), m_uavTalk, SLOT(processInputStream()));
}
telemetry = new Telemetry(utalk, objMngr);
telemetryMon = new TelemetryMonitor(objMngr, telemetry);
m_telemetry = new Telemetry(m_uavTalk, m_uavobjectManager);
m_telemetryMonitor = new TelemetryMonitor(m_uavobjectManager, m_telemetry);
connect(telemetryMon, SIGNAL(connected()), this, SLOT(onConnect()));
connect(telemetryMon, SIGNAL(disconnected()), this, SLOT(onDisconnect()));
connect(telemetryMon, SIGNAL(telemetryUpdated(double, double)), this, SLOT(onTelemetryUpdate(double, double)));
connect(m_telemetryMonitor, SIGNAL(connected()), this, SLOT(onConnect()));
connect(m_telemetryMonitor, SIGNAL(disconnected()), this, SLOT(onDisconnect()));
connect(m_telemetryMonitor, SIGNAL(telemetryUpdated(double, double)), this, SLOT(onTelemetryUpdate(double, double)));
}
void TelemetryManager::stop()
@ -99,29 +101,29 @@ void TelemetryManager::stop()
emit myStop();
if (false) {
readerThread.quit();
readerThread.wait();
m_telemetryReaderThread.quit();
m_telemetryReaderThread.wait();
}
}
void TelemetryManager::onStop()
{
telemetryMon->disconnect(this);
delete telemetryMon;
delete telemetry;
delete utalk;
m_telemetryMonitor->disconnect(this);
delete m_telemetryMonitor;
delete m_telemetry;
delete m_uavTalk;
onDisconnect();
}
void TelemetryManager::onConnect()
{
autopilotConnected = true;
m_isAutopilotConnected = true;
emit connected();
}
void TelemetryManager::onDisconnect()
{
autopilotConnected = false;
m_isAutopilotConnected = false;
emit disconnected();
}
@ -130,10 +132,10 @@ void TelemetryManager::onTelemetryUpdate(double txRate, double rxRate)
emit telemetryUpdated(txRate, rxRate);
}
IODeviceReader::IODeviceReader(UAVTalk *uavTalk) : uavTalk(uavTalk)
IODeviceReader::IODeviceReader(UAVTalk *uavTalk) : m_uavTalk(uavTalk)
{}
void IODeviceReader::read()
{
uavTalk->processInputStream();
m_uavTalk->processInputStream();
}

View File

@ -29,13 +29,14 @@
#define TELEMETRYMANAGER_H
#include "uavtalk_global.h"
#include "telemetrymonitor.h"
#include "telemetry.h"
#include "uavtalk.h"
#include "uavobjectmanager.h"
#include <QIODevice>
#include <QObject>
class Telemetry;
class TelemetryMonitor;
class UAVTALK_EXPORT TelemetryManager : public QObject {
Q_OBJECT
@ -62,13 +63,13 @@ private slots:
void onStop();
private:
UAVObjectManager *objMngr;
UAVTalk *utalk;
Telemetry *telemetry;
TelemetryMonitor *telemetryMon;
QIODevice *device;
bool autopilotConnected;
QThread readerThread;
UAVObjectManager *m_uavobjectManager;
UAVTalk *m_uavTalk;
Telemetry *m_telemetry;
TelemetryMonitor *m_telemetryMonitor;
QIODevice *m_telemetryDevice;
bool m_isAutopilotConnected;
QThread m_telemetryReaderThread;
};
@ -77,7 +78,7 @@ class IODeviceReader : public QObject {
public:
IODeviceReader(UAVTalk *uavTalk);
UAVTalk *uavTalk;
UAVTalk *m_uavTalk;
public slots:
void read();

View File

@ -48,9 +48,6 @@ bool UAVTalkPlugin::initialize(const QStringList & arguments, QString *errorStri
// Done
Q_UNUSED(arguments);
Q_UNUSED(errorString);
// Get UAVObjectManager instance
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
objMngr = pm->getObject<UAVObjectManager>();
// Create TelemetryManager
telMngr = new TelemetryManager();

View File

@ -30,11 +30,8 @@
#include <extensionsystem/iplugin.h>
#include <extensionsystem/pluginmanager.h>
#include <QtPlugin>
#include "telemetrymonitor.h"
#include "telemetry.h"
#include "uavtalk.h"
#include "telemetrymanager.h"
#include "uavobjectmanager.h"
class UAVTALK_EXPORT UAVTalkPlugin : public ExtensionSystem::IPlugin {
Q_OBJECT
@ -53,7 +50,6 @@ protected slots:
void onDeviceDisconnect();
private:
UAVObjectManager *objMngr;
TelemetryManager *telMngr;
};

View File

@ -10,8 +10,6 @@ Rectangle {
sourceComponent: scrollDecorator.flickableItem ? scrollBar : undefined
}
Component.onDestruction: scrollLoader.sourceComponent = undefined
Component {
id: scrollBar
Rectangle {

View File

@ -259,8 +259,9 @@ bool UAVObjectGeneratorGCS::process_object(ObjectInfo *info)
.arg(varOptionName)
.arg(options[m]));
}
finit.append(QString(" fields.append( new UAVObjectField(QString(\"%1\"), QString(\"%2\"), UAVObjectField::ENUM, %3, %4, QString(\"%5\")));\n")
finit.append(QString(" fields.append( new UAVObjectField(QString(\"%1\"), tr(\"%2\"), QString(\"%3\"), UAVObjectField::ENUM, %4, %5, QString(\"%6\")));\n")
.arg(info->fields[n]->name)
.arg(info->fields[n]->description)
.arg(info->fields[n]->units)
.arg(varElemName)
.arg(varOptionName)
@ -268,8 +269,9 @@ bool UAVObjectGeneratorGCS::process_object(ObjectInfo *info)
}
// For all other types
else {
finit.append(QString(" fields.append( new UAVObjectField(QString(\"%1\"), QString(\"%2\"), UAVObjectField::%3, %4, QStringList(), QString(\"%5\")));\n")
finit.append(QString(" fields.append( new UAVObjectField(QString(\"%1\"), tr(\"%2\"), QString(\"%3\"), UAVObjectField::%4, %5, QStringList(), QString(\"%6\")));\n")
.arg(info->fields[n]->name)
.arg(info->fields[n]->description)
.arg(info->fields[n]->units)
.arg(fieldTypeStrCPPClass[info->fields[n]->type])
.arg(varElemName)

View File

@ -25,7 +25,7 @@
*/
#include "uavobjectparser.h"
#include <QDebug>
/**
* Constructor
*/
@ -441,6 +441,21 @@ QString UAVObjectParser::processObjectFields(QDomNode & childNode, ObjectInfo *i
field->name = name;
}
// Get description attribute if any
elemAttr = elemAttributes.namedItem("description");
if (!elemAttr.isNull()) {
field->description = elemAttr.nodeValue();
} else {
// Look for a child description node
QDomNode node = childNode.firstChildElement("description");
if (!node.isNull()) {
QDomNode description = node.firstChild();
if (!description.isNull()) {
field->description = description.nodeValue();
}
}
}
// Get units attribute
elemAttr = elemAttributes.namedItem("units");
if (elemAttr.isNull()) {

View File

@ -49,6 +49,7 @@ typedef enum {
typedef struct {
QString name;
QString description;
QString units;
FieldType type;
int numElements;

View File

@ -1,6 +1,6 @@
<xml>
<object name="CameraStabSettings" singleinstance="true" settings="true" category="Control">
<description>Settings for the @ref CameraStab mmodule</description>
<description>Settings for the @ref CameraStab module</description>
<field name="Input" units="channel" type="enum" elementnames="Roll,Pitch,Yaw" options="Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5,None" defaultvalue="None"/>
<field name="InputRange" units="deg" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="20"/>
<field name="InputRate" units="deg/s" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="50"/>

View File

@ -1,7 +1,10 @@
<xml>
<object name="DebugLogSettings" singleinstance="true" settings="true" category="System">
<description>Configure On Board Logging Facilities</description>
<field name="LoggingEnabled" units="" type="enum" elements="1" options="Disabled,OnlyWhenArmed,Always" defaultvalue="Disabled" />
<field name="LoggingEnabled" units="" type="enum" elements="1" options="Disabled,OnlyWhenArmed,Always" defaultvalue="Disabled">
<description>If set to OnlyWhenArmed logs will only be saved when craft is armed. Disabled turns logging off, and Always will always log.</description>
</field>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>

View File

@ -1,10 +1,10 @@
<xml>
<object name="DebugLogStatus" singleinstance="true" settings="false" category="System">
<description>Log Status Object, contains log partition status information</description>
<field name="Flight" units="" type="uint16" elements="1" />
<field name="Entry" units="" type="uint16" elements="1" />
<field name="UsedSlots" units="" type="uint16" elements="1" />
<field name="FreeSlots" units="" type="uint16" elements="1" />
<field name="Flight" units="" type="uint16" elements="1" description="The current flight number (logging session)"/>
<field name="Entry" units="" type="uint16" elements="1" description="The current log entry id"/>
<field name="UsedSlots" units="" type="uint16" elements="1" description="Holds the total log entries saved"/>
<field name="FreeSlots" units="" type="uint16" elements="1" description="The number of free log slots available"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="1000"/>

View File

@ -7,69 +7,69 @@
<!-- Note these options should be identical to those in StabilizationDesired.StabilizationMode -->
<field name="Stabilization1Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
defaultvalue="Attitude,Attitude,AxisLock,Manual"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl:Attitude:Rattitude:Acro+:WeakLeveling:VirtualBar; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
/>
<field name="Stabilization2Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
defaultvalue="Attitude,Attitude,Rate,Manual"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl:Attitude:Rattitude:Acro+:WeakLeveling:VirtualBar; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
/>
<field name="Stabilization3Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
defaultvalue="Rate,Rate,Rate,Manual"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl:Attitude:Rattitude:Acro+:WeakLeveling:VirtualBar; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
/>
<field name="Stabilization4Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
defaultvalue="Attitude,Attitude,AxisLock,CruiseControl"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl:Attitude:Rattitude:Acro+:WeakLeveling:VirtualBar; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
/>
<field name="Stabilization5Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
defaultvalue="Attitude,Attitude,Rate,CruiseControl"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl:Attitude:Rattitude:Acro+:WeakLeveling:VirtualBar; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
/>
<field name="Stabilization6Settings" units="" type="enum"
elementnames="Roll,Pitch,Yaw,Thrust"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
defaultvalue="Rate,Rate,Rate,CruiseControl"
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl:Attitude:Rattitude:Acro+:WeakLeveling:VirtualBar; \
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude,\
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Acro+:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
/>
<!-- Note these options values should be identical to those defined in FlightMode -->

View File

@ -6,7 +6,7 @@
<field name="MaxPDOP" units="" type="float" elements="1" defaultvalue="3.5"/>
<!-- Ubx self configuration. Enable to allow the flight board to auto configure ubx GPS options,
store does AutoConfig and save GPS settings (i.e. to prevent issues if gps is power cycled) -->
<field name="UbxAutoConfig" units="" type="enum" elements="1" options="Disabled,Configure,ConfigureAndStore" defaultvalue="Disabled"/>
<field name="UbxAutoConfig" units="" type="enum" elements="1" options="Disabled,Configure,ConfigureAndStore" defaultvalue="Configure"/>
<!-- Ubx position update rate, -1 for auto -->
<field name="UbxRate" units="Hz" type="int8" elements="1" defaultvalue="5" />
<!-- Ubx dynamic model, see UBX datasheet for more details -->

View File

@ -1,6 +1,6 @@
<xml>
<object name="HomeLocation" singleinstance="true" settings="true" category="Navigation">
<description>HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule.</description>
<description>HomeLocation setting which contains the constants to translate from longitude and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule.</description>
<field name="Set" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="Latitude" units="deg * 10e6" type="int32" elements="1" defaultvalue="0"/>
<field name="Longitude" units="deg * 10e6" type="int32" elements="1" defaultvalue="0"/>

View File

@ -12,7 +12,7 @@
<field name="RV_TelemetryPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,ComAux,ComBridge" defaultvalue="Telemetry"/>
<field name="RV_GPSPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,ComAux,ComBridge" defaultvalue="GPS"/>
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Outputs,Outputs" defaultvalue="PWM"/>
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Telemetry,PPM+Outputs,Outputs,Telemetry" defaultvalue="PWM"/>
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM2,DSMX (10bit),DSMX (11bit),DebugConsole,ComBridge,OsdHk" defaultvalue="Disabled"/>
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM2,DSMX (10bit),DSMX (11bit),DebugConsole,ComBridge,OsdHk" defaultvalue="Disabled"/>

View File

@ -1,6 +1,6 @@
<xml>
<object name="ManualControlCommand" singleinstance="true" settings="false" category="Control">
<description>The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control.</description>
<description>The output from the @ref ManualControlModule which decodes the receiver inputs. Overriden by GCS for fly-by-wire control.</description>
<field name="Connected" units="" type="enum" elements="1" options="False,True"/>
<field name="Throttle" units="%" type="float" elements="1"/>
<field name="Roll" units="%" type="float" elements="1"/>

View File

@ -7,14 +7,19 @@
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="42" limits="%BE:0:180"/>
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,175" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,50" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="StickExpo" units="percent" type="int8" elementnames="Roll,Pitch,Yaw" defaultvalue="0,0,0" limits="%BE:-100:100; %BE:-100:100; %BE:-100:100"/>
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3" limits="%BE:0:0.01; %BE:0:0.01 ; ; "/>
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.015; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.015; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3" limits="%BE:0:0.01; %BE:0:0.015 ; ; "/>
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit"/>
<field name="AcroInsanityFactor" units="percent" type="float" elements="1" defaultvalue="0.5" limits="%BE:0.0:1.0"/>
<field name="EnablePiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="ThrustPIDScaleCurve" units="percent" type="float" elementnames="0,25,50,75,100" defaultvalue="0.3,0.15,0,-0.15,-0.3"/>
<field name="ThrustPIDScaleSource" units="" type="enum" elements="1" options="ManualControlThrottle,StabilizationDesiredThrust,ActuatorDesiredThrust" defaultvalue="ActuatorDesiredThrust" />

View File

@ -6,7 +6,7 @@
<field name="Yaw" units="degrees" type="float" elements="1"/>
<field name="Thrust" units="%" type="float" elements="1"/>
<!-- These values should match those in FlightModeSettings.Stabilization{1,2,3}Settings -->
<field name="StabilizationMode" units="" type="enum" elementnames="Roll,Pitch,Yaw,Thrust" options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"/>
<field name="StabilizationMode" units="" type="enum" elementnames="Roll,Pitch,Yaw,Thrust" options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="1000"/>

View File

@ -7,14 +7,19 @@
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="35" limits="%BE:0:180"/>
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="220,220,220" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="StickExpo" units="percent" type="int8" elementnames="Roll,Pitch,Yaw" defaultvalue="0,0,0" limits="%BE:-100:100; %BE:-100:100; %BE:-100:100"/>
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.015; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.015; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.00620,0.01000,0.00005,0.3" limits="%BE:0:0.01; %BE:0:0.015 ; ; "/>
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="AcroInsanityFactor" units="percent" type="float" elements="1" defaultvalue="0.5" limits="%BE:0.0:1.0"/>
<field name="EnablePiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="ThrustPIDScaleCurve" units="percent" type="float" elementnames="0,25,50,75,100" defaultvalue="0.3,0.15,0,-0.15,-0.3"/>
<field name="ThrustPIDScaleSource" units="" type="enum" elements="1" options="ManualControlThrottle,StabilizationDesiredThrust,ActuatorDesiredThrust" defaultvalue="ActuatorDesiredThrust" />

View File

@ -7,14 +7,19 @@
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="35" limits="%BE:0:180"/>
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="220,220,220" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="StickExpo" units="percent" type="int8" elementnames="Roll,Pitch,Yaw" defaultvalue="0,0,0" limits="%BE:-100:100; %BE:-100:100; %BE:-100:100"/>
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.015; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.015; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.00620,0.01000,0.00005,0.3" limits="%BE:0:0.01; %BE:0:0.015 ; ; "/>
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="AcroInsanityFactor" units="percent" type="float" elements="1" defaultvalue="0.5" limits="%BE:0.0:1.0"/>
<field name="EnablePiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="ThrustPIDScaleCurve" units="percent" type="float" elementnames="0,25,50,75,100" defaultvalue="0.3,0.15,0,-0.15,-0.3"/>
<field name="ThrustPIDScaleSource" units="" type="enum" elements="1" options="ManualControlThrottle,StabilizationDesiredThrust,ActuatorDesiredThrust" defaultvalue="ActuatorDesiredThrust" />

View File

@ -7,14 +7,19 @@
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="35" limits="%BE:0:180"/>
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="220,220,220" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="StickExpo" units="percent" type="int8" elementnames="Roll,Pitch,Yaw" defaultvalue="0,0,0" limits="%BE:-100:100; %BE:-100:100; %BE:-100:100"/>
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.015; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.015; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.00620,0.01000,0.00005,0.3" limits="%BE:0:0.01; %BE:0:0.015 ; ; "/>
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="AcroInsanityFactor" units="percent" type="float" elements="1" defaultvalue="0.5" limits="%BE:0.0:1.0"/>
<field name="EnablePiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
<field name="EnableThrustPIDScaling" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="ThrustPIDScaleCurve" units="percent" type="float" elementnames="0,25,50,75,100" defaultvalue="0.3,0.15,0,-0.15,-0.3"/>
<field name="ThrustPIDScaleSource" units="" type="enum" elements="1" options="ManualControlThrottle,StabilizationDesiredThrust,ActuatorDesiredThrust" defaultvalue="ActuatorDesiredThrust" />

View File

@ -11,7 +11,7 @@
<elementname>Thrust</elementname>
</elementnames>
</field>
<field name="InnerLoop" units="" type="enum" options="Direct,VirtualFlyBar,RelayTuning,AxisLock,Rate,CruiseControl">
<field name="InnerLoop" units="" type="enum" options="Direct,VirtualFlyBar,Acro+,RelayTuning,AxisLock,Rate,CruiseControl">
<elementnames>
<elementname>Roll</elementname>
<elementname>Pitch</elementname>

View File

@ -2,6 +2,7 @@
<object name="SystemSettings" singleinstance="true" settings="true" category="System">
<description>Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand</description>
<field name="AirframeType" units="" type="enum" elements="1" options="FixedWing,FixedWingElevon,FixedWingVtail,VTOL,HeliCP,QuadX,QuadP,QuadH,Hexa,Octo,Custom,HexaX,HexaH,OctoV,OctoCoaxP,OctoCoaxX,OctoX,HexaCoax,Tri,GroundVehicleCar,GroundVehicleDifferential,GroundVehicleMotorcycle" defaultvalue="QuadX"/>
<field name="VehicleName" units="char" type="uint8" elements="20" defaultvalue="0"/>
<field name="ThrustControl" units="" type="enum" elements="1" options="Throttle,Collective,None" defaultvalue="Throttle" />
<!-- Which way the vehicle controls its thrust. Can be through
"Throttle" (quadcopter, simple brushless planes,

View File

@ -19,7 +19,8 @@
Pitch Attitude.Kp, Pitch Attitude.Ki, Pitch Attitude.ILimit, Pitch Attitude.Resp,
Roll+Pitch Attitude.Kp, Roll+Pitch Attitude.Ki, Roll+Pitch Attitude.ILimit, Roll+Pitch Attitude.Resp,
Yaw Attitude.Kp, Yaw Attitude.Ki, Yaw Attitude.ILimit, Yaw Attitude.Resp,
GyroTau"
Roll.Expo, Pitch.Expo, Roll+Pitch.Expo, Yaw.Expo,
GyroTau,AcroPlusFactor"
defaultvalue="Disabled"/>
<field name="MinPID" units="" type="float" elementnames="Instance1,Instance2,Instance3" defaultvalue="0"/>
<field name="MaxPID" units="" type="float" elementnames="Instance1,Instance2,Instance3" defaultvalue="0"/>