diff --git a/WHATSNEW.txt b/WHATSNEW.txt index 27c13926b..6a41ef9c1 100644 --- a/WHATSNEW.txt +++ b/WHATSNEW.txt @@ -1,3 +1,67 @@ +Release Notes - OpenPilot - Version RELEASE-15.05 +Fully autonomous flight is now possible with autotakeoff and landing as flight modes available to path plans. +An all new implementation of altitude vario provides improved altitude maintenance and smoother flight. +A new RateTrainer mode for beginners and aerial photography make it easier to learn this mode my limiting the pitch and roll extents. +4CH transmitters for multirotor and 2CH for ground is now supported. +It is now easier to takeoff with an improved axislock on yaw implementation. +Full speed flight just got faster with new motor constraints that maintain your ability to enact roll without requiring a upper throttle limit. +Setup on GPS just got easier. See the wiki for details. +New control protocols and support for due telemtry and OSD programing have been added. + +The full list of bugfixes in this release is accessible here: + +** Bug + * [OP-1691] - PIOS_DELAY_WaitmS() in RFM22B causes jitter + * [OP-1756] - Add option to Vehicle Setup Wizard to calibrate all motor outputs at the same time. + * [OP-1778] - resolve win_sdk_install.sh issue with https:// + * [OP-1793] - Fixes for Sensor module + * [OP-1794] - AxisLock windup not cleared with low throttle while armed + * [OP-1834] - Piro Comp - adverse effect in Atti/Ratti Modes + * [OP-1841] - Serial telemetry is not reliable + * [OP-1855] - Limit parsing error in logs when starting GCS + * [OP-1858] - PathPlanner AutoTakeoff fixes + * [OP-1867] - PathPlanner AutoLand simplification + * [OP-1869] - Allow Analog Airspeed scale + * [OP-1872] - Vehicle Wiz Tricopter tail servo settings don't save + + +** Improvement + * [OP-1289] - Need Revo to send two telemetry streams for OSD and GCS + * [OP-1734] - Clarify the need of reversing servo in FW vehicle wizard + * [OP-1736] - Make package label something more meaningful than the date. + * [OP-1739] - Add GNSS (GPS/GLONASS) selection to UBX autoconf + * [OP-1750] - Revo state estimation CPU optimization + * [OP-1776] - Performance optimizations for UAVTalk telemetry + * [OP-1783] - Fall back PathPlanner flight mode to PH with config warning if no plan + * [OP-1791] - Change the description of the stabilization modes + * [OP-1796] - Upgrade GCS to qt 5.4.1 + * [OP-1797] - Improve GCS workspace layout management reactivity + * [OP-1798] - GCS ophid plugin is too verbose + * [OP-1802] - Throttle filterstationary fake pos/vel data rate + * [OP-1808] - Make the flight mode switch step in transmitter setup wizard to be optional + * [OP-1814] - Reset Button for mAH used + * [OP-1828] - Changes ADC module to support other pins as optional analog inputs + * [OP-1835] - Add motor constraints in place of overhead throttle buffer for enhanced stability and power. + * [OP-1837] - Add support for Multiplex SRXL protocol + * [OP-1840] - GPS serlal port needed features + * [OP-1844] - Create a vagrant environment that contains all the bits for Android development, including Android. + * [OP-1848] - Rewrite AltVario/Hold in C++ for functional improvements + * [OP-1852] - Include version number in window title bar. + * [OP-1874] - Various improvements to led notifications + +** New Feature + * [OP-1696] - PathFollower C++ Rewrite: Autonomous Landing, Velocity Roam, RTBL, GroundPathFollower + * [OP-1760] - AutoTakeoff + * [OP-1769] - Support Ground Vehicles with 2CH receiver and reversible motor + * [OP-1781] - Ground Input Channel Configuration + * [OP-1803] - Create UAVTalk objects for receiver signal quality + * [OP-1818] - Update OP toolchain for compiling osgearth + * [OP-1832] - Need method to get default UAV Object settings in Java UAVObjects + * [OP-1849] - Support programming/update of minimosd using USB VCP port + * [OP-1863] - RateTrainer mode - add maxpitch for beginners and aerial photography + + + --- RELEASE-15.02.02 --- This release fixes a bug that prevents revo onboard mag to work correctly. diff --git a/flight/libraries/inc/plans.h b/flight/libraries/inc/plans.h index 64159ea36..c241dd85d 100644 --- a/flight/libraries/inc/plans.h +++ b/flight/libraries/inc/plans.h @@ -67,7 +67,7 @@ void plan_setup_AutoTakeoff(); /** * @brief setup pathplanner/pathfollower for braking */ -void plan_setup_assistedcontrol(uint8_t timeout_occurred); +void plan_setup_assistedcontrol(); #define PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_NORTH 0 #define PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_EAST 1 diff --git a/flight/libraries/plans.c b/flight/libraries/plans.c index 4005a9d6f..7055744b8 100644 --- a/flight/libraries/plans.c +++ b/flight/libraries/plans.c @@ -615,7 +615,7 @@ void plan_run_VelocityRoam() // avoid brake then hold sequence to continue descent. plan_setup_land_from_velocityroam(); } else { - plan_setup_assistedcontrol(false); + plan_setup_assistedcontrol(); } } // otherwise nothing to do in braking/hold modes @@ -824,7 +824,7 @@ void plan_run_AutoCruise() #define ASSISTEDCONTROL_TIMETOSTOP_MAXIMUM 9.0f // seconds #define ASSISTEDCONTROL_DELAY_TO_BRAKE 1.0f // seconds #define ASSISTEDCONTROL_TIMEOUT_MULTIPLIER 2.0f // actual deceleration rate can be 50% of desired...timeouts need to cater for this -void plan_setup_assistedcontrol(uint8_t timeout_occurred) +void plan_setup_assistedcontrol() { PositionStateData positionState; @@ -832,75 +832,55 @@ void plan_setup_assistedcontrol(uint8_t timeout_occurred) PathDesiredData pathDesired; FlightStatusAssistedControlStateOptions assistedControlFlightMode; - FlightStatusAssistedControlStateGet(&assistedControlFlightMode); - if (timeout_occurred) { - FlightStatusFlightModeOptions flightMode; - FlightStatusFlightModeGet(&flightMode); - if (flightMode == FLIGHTSTATUS_FLIGHTMODE_LAND) { - plan_setup_land_helper(&pathDesired); - } else { - pathDesired.End.North = positionState.North; - pathDesired.End.East = positionState.East; - pathDesired.End.Down = positionState.Down; - pathDesired.Start.North = positionState.North; - pathDesired.Start.East = positionState.East; - pathDesired.Start.Down = positionState.Down; - pathDesired.StartingVelocity = 0.0f; - pathDesired.EndingVelocity = 0.0f; - pathDesired.Mode = PATHDESIRED_MODE_GOTOENDPOINT; - } - assistedControlFlightMode = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_HOLD; - } else { - VelocityStateData velocityState; - VelocityStateGet(&velocityState); - float brakeRate; - VtolPathFollowerSettingsBrakeRateGet(&brakeRate); - if (brakeRate < ASSISTEDCONTROL_BRAKERATE_MINIMUM) { - brakeRate = ASSISTEDCONTROL_BRAKERATE_MINIMUM; // set a minimum to avoid a divide by zero potential below - } - // Calculate the velocity - float velocity = velocityState.North * velocityState.North + velocityState.East * velocityState.East + velocityState.Down * velocityState.Down; - velocity = sqrtf(velocity); - - // Calculate the desired time to zero velocity. - float time_to_stopped = ASSISTEDCONTROL_DELAY_TO_BRAKE; // we allow at least 0.5 seconds to rotate to a brake angle. - time_to_stopped += velocity / brakeRate; - - // Sanity check the brake rate by ensuring that the time to stop is within a range. - if (time_to_stopped < ASSISTEDCONTROL_TIMETOSTOP_MINIMUM) { - time_to_stopped = ASSISTEDCONTROL_TIMETOSTOP_MINIMUM; - } else if (time_to_stopped > ASSISTEDCONTROL_TIMETOSTOP_MAXIMUM) { - time_to_stopped = ASSISTEDCONTROL_TIMETOSTOP_MAXIMUM; - } - - // calculate the distance we will travel - float north_delta = velocityState.North * ASSISTEDCONTROL_DELAY_TO_BRAKE; // we allow at least 0.5s to rotate to brake angle - north_delta += (time_to_stopped - ASSISTEDCONTROL_DELAY_TO_BRAKE) * 0.5f * velocityState.North; // area under the linear deceleration plot - float east_delta = velocityState.East * ASSISTEDCONTROL_DELAY_TO_BRAKE; // we allow at least 0.5s to rotate to brake angle - east_delta += (time_to_stopped - ASSISTEDCONTROL_DELAY_TO_BRAKE) * 0.5f * velocityState.East; // area under the linear deceleration plot - float down_delta = velocityState.Down * ASSISTEDCONTROL_DELAY_TO_BRAKE; - down_delta += (time_to_stopped - ASSISTEDCONTROL_DELAY_TO_BRAKE) * 0.5f * velocityState.Down; // area under the linear deceleration plot - float net_delta = east_delta * east_delta + north_delta * north_delta + down_delta * down_delta; - net_delta = sqrtf(net_delta); - - pathDesired.Start.North = positionState.North; - pathDesired.Start.East = positionState.East; - pathDesired.Start.Down = positionState.Down; - pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_NORTH] = velocityState.North; - pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_EAST] = velocityState.East; - pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_DOWN] = velocityState.Down; - - pathDesired.End.North = positionState.North + north_delta; - pathDesired.End.East = positionState.East + east_delta; - pathDesired.End.Down = positionState.Down + down_delta; - - pathDesired.StartingVelocity = velocity; - pathDesired.EndingVelocity = 0.0f; - pathDesired.Mode = PATHDESIRED_MODE_BRAKE; - pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_TIMEOUT] = time_to_stopped * ASSISTEDCONTROL_TIMEOUT_MULTIPLIER; - assistedControlFlightMode = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE; + VelocityStateData velocityState; + VelocityStateGet(&velocityState); + float brakeRate; + VtolPathFollowerSettingsBrakeRateGet(&brakeRate); + if (brakeRate < ASSISTEDCONTROL_BRAKERATE_MINIMUM) { + brakeRate = ASSISTEDCONTROL_BRAKERATE_MINIMUM; // set a minimum to avoid a divide by zero potential below } + // Calculate the velocity + float velocity = velocityState.North * velocityState.North + velocityState.East * velocityState.East + velocityState.Down * velocityState.Down; + velocity = sqrtf(velocity); + + // Calculate the desired time to zero velocity. + float time_to_stopped = ASSISTEDCONTROL_DELAY_TO_BRAKE; // we allow at least 0.5 seconds to rotate to a brake angle. + time_to_stopped += velocity / brakeRate; + + // Sanity check the brake rate by ensuring that the time to stop is within a range. + if (time_to_stopped < ASSISTEDCONTROL_TIMETOSTOP_MINIMUM) { + time_to_stopped = ASSISTEDCONTROL_TIMETOSTOP_MINIMUM; + } else if (time_to_stopped > ASSISTEDCONTROL_TIMETOSTOP_MAXIMUM) { + time_to_stopped = ASSISTEDCONTROL_TIMETOSTOP_MAXIMUM; + } + + // calculate the distance we will travel + float north_delta = velocityState.North * ASSISTEDCONTROL_DELAY_TO_BRAKE; // we allow at least 0.5s to rotate to brake angle + north_delta += (time_to_stopped - ASSISTEDCONTROL_DELAY_TO_BRAKE) * 0.5f * velocityState.North; // area under the linear deceleration plot + float east_delta = velocityState.East * ASSISTEDCONTROL_DELAY_TO_BRAKE; // we allow at least 0.5s to rotate to brake angle + east_delta += (time_to_stopped - ASSISTEDCONTROL_DELAY_TO_BRAKE) * 0.5f * velocityState.East; // area under the linear deceleration plot + float down_delta = velocityState.Down * ASSISTEDCONTROL_DELAY_TO_BRAKE; + down_delta += (time_to_stopped - ASSISTEDCONTROL_DELAY_TO_BRAKE) * 0.5f * velocityState.Down; // area under the linear deceleration plot + float net_delta = east_delta * east_delta + north_delta * north_delta + down_delta * down_delta; + net_delta = sqrtf(net_delta); + + pathDesired.Start.North = positionState.North; + pathDesired.Start.East = positionState.East; + pathDesired.Start.Down = positionState.Down; + pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_NORTH] = velocityState.North; + pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_EAST] = velocityState.East; + pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_DOWN] = velocityState.Down; + + pathDesired.End.North = positionState.North + north_delta; + pathDesired.End.East = positionState.East + east_delta; + pathDesired.End.Down = positionState.Down + down_delta; + + pathDesired.StartingVelocity = velocity; + pathDesired.EndingVelocity = 0.0f; + pathDesired.Mode = PATHDESIRED_MODE_BRAKE; + pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_TIMEOUT] = time_to_stopped * ASSISTEDCONTROL_TIMEOUT_MULTIPLIER; + assistedControlFlightMode = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE; FlightStatusAssistedControlStateSet(&assistedControlFlightMode); PathDesiredSet(&pathDesired); } diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index ca7ebeba5..633e390e6 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -59,8 +59,8 @@ #define CBTASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL #define ASSISTEDCONTROL_NEUTRALTHROTTLERANGE_FACTOR 0.2f -#define ASSISTEDCONTROL_BRAKETHRUST_DEADBAND_FACTOR_LO 0.92f -#define ASSISTEDCONTROL_BRAKETHRUST_DEADBAND_FACTOR_HI 1.08f +#define ASSISTEDCONTROL_BRAKETHRUST_DEADBAND_FACTOR_LO 0.96f +#define ASSISTEDCONTROL_BRAKETHRUST_DEADBAND_FACTOR_HI 1.04f // defined handlers @@ -242,7 +242,7 @@ static void manualControlTask(void) // set assist mode to none to avoid an assisted flight mode position // carrying over and impacting a newly selected non-assisted flight mode pos newFlightModeAssist = FLIGHTSTATUS_FLIGHTMODEASSIST_NONE; - // The following are eqivalent to none effectively. Code should always + // The following are equivalent to none effectively. Code should always // check the flightmodeassist state. newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_PRIMARY; newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL; @@ -264,6 +264,16 @@ static void manualControlTask(void) #ifndef PIOS_EXCLUDE_ADVANCED_FEATURES newFlightModeAssist = isAssistedFlightMode(position, newMode, &modeSettings); + + if (newFlightModeAssist != flightStatus.FlightModeAssist) { + // On change of assist mode reinitialise control state. This is required + // for the scenario where a flight position change reuses a flight mode + // but adds assistedcontrol. + newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_PRIMARY; + newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL; + } + + if (newFlightModeAssist) { // assess roll/pitch state bool flagRollPitchHasInput = (fabsf(cmd.Roll) > 0.0f || fabsf(cmd.Pitch) > 0.0f); @@ -301,7 +311,7 @@ static void manualControlTask(void) // retain thrust cmd for later comparison with actual in braking thrustAtBrakeStart = cmd.Thrust; - // calculate hi and low value of +-8% as a mini-deadband + // calculate hi and low value of +-4% as a mini-deadband // for use in auto-override in brake sequence thrustLo = ASSISTEDCONTROL_BRAKETHRUST_DEADBAND_FACTOR_LO * thrustAtBrakeStart; thrustHi = ASSISTEDCONTROL_BRAKETHRUST_DEADBAND_FACTOR_HI * thrustAtBrakeStart; diff --git a/flight/modules/ManualControl/pathfollowerhandler.c b/flight/modules/ManualControl/pathfollowerhandler.c index 86912a168..dc71cebf3 100644 --- a/flight/modules/ManualControl/pathfollowerhandler.c +++ b/flight/modules/ManualControl/pathfollowerhandler.c @@ -72,7 +72,7 @@ void pathFollowerHandler(bool newinit) if ((flightModeAssist != FLIGHTSTATUS_FLIGHTMODEASSIST_NONE) && (assistedControlFlightMode == FLIGHTSTATUS_ASSISTEDCONTROLSTATE_PRIMARY)) { // Switch from primary (just entered this PH flight mode) into brake - plan_setup_assistedcontrol(false); + plan_setup_assistedcontrol(); } else { plan_setup_positionHold(); } @@ -116,7 +116,7 @@ void pathFollowerHandler(bool newinit) case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6: if (assistedControlFlightMode == FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE) { // Just initiated braking after returning from stabi control - plan_setup_assistedcontrol(false); + plan_setup_assistedcontrol(); } break; diff --git a/flight/modules/PathFollower/vtolbrakecontroller.cpp b/flight/modules/PathFollower/vtolbrakecontroller.cpp index 862011057..ffa492461 100644 --- a/flight/modules/PathFollower/vtolbrakecontroller.cpp +++ b/flight/modules/PathFollower/vtolbrakecontroller.cpp @@ -193,6 +193,21 @@ void VtolBrakeController::UpdateVelocityDesired() if (!mManualThrust) { controlDown.UpdatePositionSetpoint(positionState.Down); } + + + FlightStatusFlightModeAssistOptions flightModeAssist; + FlightStatusFlightModeAssistGet(&flightModeAssist); + if (flightModeAssist != FLIGHTSTATUS_FLIGHTMODEASSIST_NONE) { + // Notify manualcommand via setting hold state in flightstatus assistedcontrolstate + FlightStatusAssistedControlStateOptions assistedControlFlightMode; + FlightStatusAssistedControlStateGet(&assistedControlFlightMode); + // sanity check that we are in brake state according to flight status, which means + // we are being used for gpsassist + if (assistedControlFlightMode == FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE) { + assistedControlFlightMode = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_HOLD; + FlightStatusAssistedControlStateSet(&assistedControlFlightMode); + } + } } // Update position state and control position to create inputs to velocity control diff --git a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts index a63392f6e..52fe25ef4 100644 --- a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts +++ b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts @@ -136,7 +136,7 @@ Core::Internal::MainWindow - + &File &Fichier @@ -161,12 +161,7 @@ &Aide - - OpenPilot GCS - - - - + Ctrl+Shift+S Ctrl+Maj+S @@ -181,7 +176,12 @@ Enregistrer Paramètres &GCS par Défaut - + + OpenPilot GCS + + + + Ctrl+Q Ctrl+Q @@ -5600,172 +5600,108 @@ La même valeur est utilisé pour tous les axes. CC_HW_Widget - Form - Formulaire + Formulaire - HW settings - Paramètres Matériels + Paramètres Matériels - Messages - Messages + Messages - Changes on this page only take effect after board reset or power cycle - Les changements sur cette page ne prendront effet qu'après un reset ou une coupure d'alimentation + Les changements sur cette page ne prendront effet qu'après un reset ou une coupure d'alimentation - Telemetry speed: - Vitesse de télémétrie : + Vitesse de télémétrie : - GPS speed: - Vitesse GPS : + Vitesse GPS : - ComUsbBridge speed: - Vitesse COMUsbBridge : + Vitesse COMUsbBridge : - Select the speed here. - Sélectionner ici la vitesse. + Sélectionner ici la vitesse. - - USB HID Port - - - - - USB VCP Port - - - - Takes you to the wiki page - Vous renvoie à la page wiki + Vous renvoie à la page wiki - Send to OpenPilot but don't write in SD. Beware of not locking yourself out! - Envoie vers l'OpenPilot mais n'écrit pas dans la SD. + Envoie vers l'OpenPilot mais n'écrit pas dans la SD. Méfiez-vous de ne pas vous verrouiller l'accès ! - Apply - Appliquer + Appliquer - Applies and Saves all settings to SD. Beware of not locking yourself out! - Applique et Enregistre tous les paramètres dans la SD. + Applique et Enregistre tous les paramètres dans la SD. Méfiez-vous de ne pas vous verrouiller l'accès ! - Save - Enregistrer + Enregistrer - GPS protocol : - Protocole GPS : - - - - Main Port - - - - - Flexi Port - - - - - Receiver Port - + Protocole GPS : ccattitude - Form - Formulaire + Formulaire - Attitude - Attitude + Attitude - Rotate virtual attitude relative to board - Pivoter l'attitude virtuelle par rapport à la carte + Pivoter l'attitude virtuelle par rapport à la carte - - Roll - - - - - Yaw - - - - - Pitch - - - - Calibration - Calibration + Calibration - Place aircraft very flat, and then click level to compute the accelerometer and gyro bias - Placer l'appareil bien à plat et cliquer ensuite sur Niveau pour calculer les ajustements des accéléromètres et gyroscopes + Placer l'appareil bien à plat et cliquer ensuite sur Niveau pour calculer les ajustements des accéléromètres et gyroscopes - Launch horizontal calibration. - Lancer la calibration du niveau horizontal. + Lancer la calibration du niveau horizontal. - Level - Niveau + Niveau - If enabled, a fast recalibration of gyro zero point will be done whenever the frame is armed. Do not move the airframe while arming it in that case! - Si activé, une recalibration rapide des gyros est effectuée à chaque fois que + Si activé, une recalibration rapide des gyros est effectuée à chaque fois que la carte est armée. Dans ce cas ne bougez pas l'appareil lors de l'armement ! - Zero gyros while arming aircraft - Mettre les gyros à zéro lors de l'armement + Mettre les gyros à zéro lors de l'armement - Accelerometer filtering. Sets the amount of lowpass filtering of accelerometer data @@ -5776,7 +5712,7 @@ Range: 0.00 - 0.20, Good starting value: 0.05 - 0.10 Start low and raise until drift stops. A setting of 0.00 disables the filter. - Filtrage accéléromètres. + Filtrage accéléromètres. Ajuste le niveau de filtrage passe-bas des données d'accéléromètres pour l'estimation de l'inclinaison. Des valeurs élevées donnent un filtrage plus @@ -5788,35 +5724,29 @@ Commencez à un niveau bas et augmentez jusqu'à ce que le glissement s&apo Une valeur de 0.00 désactive le filtre. - Takes you to the wiki page - Vous renvoie à la page wiki + Vous renvoie à la page wiki - Apply - Appliquer + Appliquer - Click to permanently save the accel bias in the CopterControl Flash. - Cliquer pour enregistrer définitivement les ajustements des + Cliquer pour enregistrer définitivement les ajustements des accéléromètres dans la mémoire Flash de la carte. - Save - Enregistrer + Enregistrer - Filtering - Filtrage + Filtrage - Accelerometers - Accéléromètres + Accéléromètres @@ -6490,9 +6420,8 @@ Applique et Enregistre tous les paramètres sur la SD Stabilisé 6 - <html><head/><body><p>Avoid &quot;Manual&quot; for multirotors! Never select &quot;Altitude&quot;, &quot;VelocityControl&quot; or &quot;CruiseControl&quot; on a fixed wing!</p></body></html> - <html><head/><body><p>Éviter &quot;Manuel&quot; pour les multirotors ! Ne jamais sélectionner &quot;Altitude&quot;, &quot;VelocityControl&quot; ou &quot;CruiseControl&quot; sur une aile volante !</p></body></html> + <html><head/><body><p>Éviter &quot;Manuel&quot; pour les multirotors ! Ne jamais sélectionner &quot;Altitude&quot;, &quot;VelocityControl&quot; ou &quot;CruiseControl&quot; sur une aile volante !</p></body></html> @@ -6541,6 +6470,11 @@ Applique et Enregistre tous les paramètres sur la SD Do not translate ! + + + <html><head/><body><p>Never select &quot;Manual&quot; as Flight Mode when flying a multitrotor! Never select &quot;Altitude&quot; or &quot;CruiseControl&quot; in Stabilization Modes when using a fixed wing!</p></body></html> + <html><head/><body><p>Éviter &quot;Manuel&quot; comme Mode de Vol pour les multirotors ! Ne jamais sélectionner &quot;Altitude&quot; ou &quot;CruiseControl&quot; comme Mode de Stabilisation sur une aile volante !</p></body></html> + MixerCurve @@ -7964,30 +7898,12 @@ Useful if you have accidentally changed some settings. Velocity Integral Intégrale Vitesse Verticale - - - fieldname:AltitudePI - Pas toucher ! - - scale:0.01 Pas toucher ! - - - fieldname:VelocityPI - Pas toucher ! - - - - - scale:0.00001 - Pas toucher ! - - Control Coefficients @@ -8070,9 +7986,8 @@ Useful if you have accidentally changed some settings. <html><head/><body><p>Détermine de combien le véhicule augmente ou diminue les gaz pour compenser ou atteindre une certaine vitesse verticale. Des valeurs plus élevées entraînent des variations de gaz plus agressives qui peuvent produire des oscillations. C'est le paramètre à changer en fonction de la poussée moteur de l'appareil. Des appareils chargés avec des moteurs faibles peuvent demander des valeurs plus élevées.</p></body></html> - <html><head/><body><p>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 &quot;throttle trim&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.</p></body></html> - <html><head/><body><p>Détermine la vitesse à laquelle le véhicule doit ajuster son estimation de gaz au neutre. Le Maintien d'Altitude suppose que lorsque il est activé, il est la plage nécessaire pour se maintenir en l'air. Si les gaz est beaucoup plus élevé ou plus bas, il faut ajuster ce "trim". 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.</p></body></html> + <html><head/><body><p>Détermine la vitesse à laquelle le véhicule doit ajuster son estimation de gaz au neutre. Le Maintien d'Altitude suppose que lorsque il est activé, il est la plage nécessaire pour se maintenir en l'air. Si les gaz est beaucoup plus élevé ou plus bas, il faut ajuster ce "trim". 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.</p></body></html> @@ -8431,8 +8346,55 @@ response (deg) <html><head/><body><p>Ceci ajuste le niveau de stabilité en lacet de votre véhicule en mode Rate. Un bon point de départ pour l'Intégrale est le double de la valeur Proportionnel</p></body></html> - <html><head/><body><p>How fast the vehicle should climb or descent to compensate a certain altitude difference. Higher values could result in more accurate altitude hold but also more violent control actions, lower values are safer and ensure smoother flight. The default value should be fine for the majority of crafts.</p></body></html> + <html><head/><body><p>Détermine la vitesse à laquelle doit monter ou descendre le véhicule pour compenser une certaine différence d'altitude. Des valeurs plus élevées pourraient entraîner un maintien d'altitude plus précis mais aussi des réactions plus violentes, des valeurs inférieures sont plus sûres et donnent un vol plus doux. La valeur par défaut devrait être bonne pour la plupart des appareils.</p></body></html> + + + + fieldname:VerticalPosP + Pas toucher ! + + + + + <html><head/><body><p>How fast the vehicle should attain its target velocity. For neutral throttle estimation, the altitude module assumes that when engaged the throttle thrust limit neutral setting is in the range required to hover. If the throttle required is a lot higher or lower, it needs to adjust this &quot;throttle trim&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.</p></body></html> + <html><head/><body><p>Détermine la rapidité à laquelle le véhicule doit atteindre la vitesse désirée. Pour l'estimation du neutre de manche des gaz, le module Altitude suppose que lorsqu'il est activé le manche des gaz est dans la zone nécessaire à un vol stabilisé. Si la valeur de gaz est beaucoup plus haute ou basse, il doit ajuster son &quot;Trim de Gaz&quot;. Des valeurs élevées donneront un ajustement plus rapide mais cela peut entrainer de vilaines oscillations. Laissez par défaut si vous ne savez pas ce que vous faites.</p></body></html> + + + + fieldname:VerticalVelPID + Pas toucher ! + + + + + Velocity Derivative + Dérivée Vitesse Verticale + + + + <html><head/><body><p>Small abouts of Kd can reduce oscillations in the velocity controller.</p></body></html> + <html><head/><body><p>Un faible valeur de Kd peut réduire les oscillations dans le controlleur de vitesse.</p></body></html> + + + + Velocity Beta + Beta Vitesse Verticale + + + + <html><head/><body><p>The beta value applies a setpoint weighting that reduces the sensitivity to quick changes in the desired velocity. Transitions from altitude hold to descent/climb can be made smooth applying a Beta value of around 80 to 90%.</p></body></html> + <html><head/><body><p>La valeur de Beta applique une pondération de consigne qui réduit la sensibilité à des changements rapides de la vitesse souhaitée. Les transitions montée/descente en maintien d'altitude peuvent être adoucies en mettant une valeur de Beta entre 80 et 90%.</p></body></html> + + + + element:Beta + Pas toucher ! + + + + + <html><head/><body><p>How fast the vehicle should climb or descent to compensate a certain altitude difference. Higher values could result in more accurate altitude hold but also more violent control actions, lower values are safer and ensure smoother flight. The default value should be fine for the majority of crafts.</p></body></html> <html><head/><body><p>Détermine la vitesse à laquelle doit monter ou descendre le véhicule pour compenser une certaine différence d'altitude. Des valeurs plus élevées pourraient entraîner un maintien d'altitude plus précis mais aussi des réactions plus violentes, des valeurs inférieures sont plus sûres et donnent un vol plus doux. La valeur par défaut devrait être bonne pour la plupart des appareils.</p></body></html> @@ -9146,7 +9108,7 @@ les données en cache Diagramme de Connexion - + Save File Enregistrer Fichier @@ -9277,7 +9239,7 @@ p, li { white-space: pre-wrap; } <p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">It is necessary that your firmware and ground control software are the same version.</span></p> <p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">When you are ready you can start the upgrade below by pushing the button. It is critical that nothing disturbs the board while the firmware is being written.</span></p> <p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">It is recommended that you erase all settings on the board when upgrading firmware. Using saved settings for a previous version of the firmware </span><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt; font-weight:600;">may result in undefined behaviour</span><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;"> and in worst case danger. It is possible to suppress the erase by deselecting the check box below.</span></p></body></html> - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> @@ -9311,25 +9273,15 @@ p, li { white-space: pre-wrap; } - + Connect Connecter - + <Unknown> <Inconnu> - - - OpenPilot CopterControl - - - - - OpenPilot CopterControl 3D - - OpenPilot Revolution @@ -9637,12 +9589,12 @@ Veuillez sélectionner le type de multirotor désiré pour la configuration ci-d - + Output value : <b>%1</b> µs Valeur de sortie : <b>%1</b> µs - + <html><head/><body><p><span style=" font-size:10pt;">To find </span><span style=" font-size:10pt; font-weight:600;">the neutral rate for this reversable motor</span><span style=" font-size:10pt;">, press the Start button below and slide the slider to the right or left until you find the value where the motor doesn't start. <br/><br/>When done press button again to stop.</span></p></body></html> <html><head/><body><p><span style=" font-size:10pt;">Pour trouver </span><span style=" font-size:10pt; font-weight:600;">la valeur de neutre de ce moteur inversable</span><span style=" font-size:10pt;">, appuyez sur le bouton Démarrer et bouger le curseur à gauche ou à droite jusqu'à trouver la position centrale où le moteur ne démarre pas. <br/><br/>Lorsque c'est terminé, appuyer à nouveau sur le bouton pour arrêter.</span></p></body></html> @@ -9662,7 +9614,7 @@ Please make sure the correct firmware version is used then restart the wizard an Soyez certain d'utiliser la bonne version de firmware puis redémarrer l'assistant et essayez à nouveau. Si le problème persiste, consultez le forum openpilot.org. - + Output value : <b>%1</b> µs (Min) Valeur de sortie : <b>%1</b> µs (Min) @@ -10650,54 +10602,38 @@ p, li { white-space: pre-wrap; } ConfigCCHWWidget - Enable GPS module and reboot the board to be able to select GPS protocol - Activez le module GPS et redémarrez la carte pour pouvoir choisir le protocole GPS + Activez le module GPS et redémarrez la carte pour pouvoir choisir le protocole GPS - Warning: you have configured more than one DebugConsole, this currently is not supported - Attention : vous avez configuré plus d'une DebugConsole, ce n'est actuellement pas possible + Attention : vous avez configuré plus d'une DebugConsole, ce n'est actuellement pas possible - Warning: you have configured both MainPort and FlexiPort for the same function, this currently is not supported Attention - Attention : vous avez configuré la même fonction sur les deux ports MainPort et FlexiPort, ce n'est actuellement pas possible + Attention : vous avez configuré la même fonction sur les deux ports MainPort et FlexiPort, ce n'est actuellement pas possible - Warning: you have configured both USB HID Port and USB VCP Port for the same function, this currently is not supported - Attention : vous avez configuré la même fonction sur les deux ports USB HID et USB VCP, ce n'est actuellement pas possible + Attention : vous avez configuré la même fonction sur les deux ports USB HID et USB VCP, ce n'est actuellement pas possible - Warning: you have disabled USB Telemetry on both USB HID Port and USB VCP Port, this currently is not supported - Attention : vous avez désactivé la télémétrie USB sur les deux ports USB HID et USB VCP, ce n'est actuellement pas possible - - - - http://wiki.openpilot.org/x/D4AUAQ - + Attention : vous avez désactivé la télémétrie USB sur les deux ports USB HID et USB VCP, ce n'est actuellement pas possible ConfigCCAttitudeWidget - Calibration timed out before receiving required updates. - Temps d'attente dépassé avant d'avoir reçu les mises à jour demandées. - - - - http://wiki.openpilot.org/x/44Cf - + Temps d'attente dépassé avant d'avoir reçu les mises à jour demandées. ConfigGadgetWidget - + Unsaved changes Modifications non sauvegardées @@ -11001,13 +10937,27 @@ Bougez le manche %1. Connexions : - + Disconnect Déconnecter - - + + CopterControl Not Supported + CopterControl Non Supporté + + + + This version of OpenPilot GCS does not support CC and CC3D boards. + +Please use OpenPilot GCS version 15.02.xx instead + Cette version d'OpenPilot GCS ne supporte pas les cartes CC et CC3D. + +Veuillez utiliser OpenPilot GCS version 15.02.xx à la place + + + + Connect Connecter @@ -11295,20 +11245,10 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Assistant Configuration OpenPilot - + Controller type: Type de contrôleur : - - - OpenPilot CopterControl - - - - - OpenPilot CopterControl 3D - - OpenPilot Revolution @@ -11610,7 +11550,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Échoué ! - + Writing External Mag sensor settings Écriture paramètres Compas Externe @@ -11630,7 +11570,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Écriture paramètres matériels - + Writing actuator settings @@ -11652,7 +11592,6 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Écriture paramètres d'ajustement gyro et accéléromètres - Writing board settings Écriture paramètres carte @@ -11892,12 +11831,12 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende. - + Device Périphérique - + http://wiki.openpilot.org/display/Doc/Erase+board+settings @@ -11907,20 +11846,20 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.En cours d'exécution - + Timed out while waiting for all boards to be disconnected! Bof Expiration du temps d'attente de la déconnexion de toutes les cartes ! - - + + Timed out while waiting for a board to be connected! Bof Expiration du temps dans l'attente d'une connexion de carte ! - + To upgrade the OPLinkMini board please disconnect it from the USB port, press the Upgrade again button and follow instructions on screen. Pour mettre à jour une carte OPLinkMini veuillez la déconnecterdu port USB, appuyez à nouveau sur le bouton de mise à jour et suivez les instructions à l'écran. @@ -11936,7 +11875,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Échec du passage en mode bootloader. - + Unknown board id '0x%1' Carte inconnue id '0x%1' @@ -11966,7 +11905,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Échec du téléversement de la description firmware. - + Timed out while booting. Expiration du temps d'attente lors du démarrage. @@ -12132,7 +12071,7 @@ La carte sera redémarrée et tous les paramètres effacés. Veuillez vérifier que la carte n'est pas armée et appuyez à nouveau Réinitialiser pour continuer ou allumer/éteindre la carte pour forcer la réinitialisation. - + Annuler @@ -13669,12 +13608,12 @@ p, li { white-space: pre-wrap; } - + %1 Hz %1 Hz - + The actuator module is in an error state. This can also occur because there are no inputs. Please fix these before testing outputs. Le module actionneur est en erreur. Cela peut aussi arriver lorsque il n'y a pas d'entrées (Rx radiocommande). Veuillez corriger cela avant de tester les sorties. @@ -13689,7 +13628,7 @@ p, li { white-space: pre-wrap; } Vous pouvez enregistrer vos changements des réglages de neutre. - + http://wiki.openpilot.org/x/WIGf @@ -13718,7 +13657,7 @@ En utilisant "PPM_PIN6+OneShot" la banque 4 (sortie 6) doit être rég Désactivé - + http://wiki.openpilot.org/x/GgDBAQ @@ -13811,7 +13750,7 @@ En utilisant "PPM_PIN6+OneShot" la banque 4 (sortie 6) doit être rég DeviceWidget - + Device ID: ID Périphérique : @@ -13821,7 +13760,7 @@ En utilisant "PPM_PIN6+OneShot" la banque 4 (sortie 6) doit être rég Révision Matériel : - + Flash access: Accès flash : @@ -13906,7 +13845,7 @@ En utilisant "PPM_PIN6+OneShot" la banque 4 (sortie 6) doit être rég Firmware chargé : - + Select firmware file Sélectionner le fichier de firmware @@ -13935,7 +13874,7 @@ En utilisant "PPM_PIN6+OneShot" la banque 4 (sortie 6) doit être rég CRC Firmware : - + BL version: Version BL : @@ -14831,7 +14770,7 @@ Des valeurs trop élevées pour les contrôles principaux peuvent entraîner des et même conduire au crash. A utiliser avec prudence. - + Chan %1 Canal %1 @@ -16399,7 +16338,7 @@ Il est suggéré que si cela est une première configuration de votre contrôleu &Ne pas afficher ce message à nouveau. - + Unknown Inconnu diff --git a/shared/uavobjectdefinition/altitudeholdsettings.xml b/shared/uavobjectdefinition/altitudeholdsettings.xml index e85ff09e6..7058041e2 100644 --- a/shared/uavobjectdefinition/altitudeholdsettings.xml +++ b/shared/uavobjectdefinition/altitudeholdsettings.xml @@ -6,7 +6,7 @@ - + diff --git a/shared/uavobjectdefinition/mpu6000settings.xml b/shared/uavobjectdefinition/mpu6000settings.xml index 943243fa7..4813a9c71 100644 --- a/shared/uavobjectdefinition/mpu6000settings.xml +++ b/shared/uavobjectdefinition/mpu6000settings.xml @@ -18,7 +18,7 @@ - + diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml index 9187d13f3..644bfbf41 100644 --- a/shared/uavobjectdefinition/stabilizationsettings.xml +++ b/shared/uavobjectdefinition/stabilizationsettings.xml @@ -18,7 +18,7 @@ - + diff --git a/shared/uavobjectdefinition/vtolpathfollowersettings.xml b/shared/uavobjectdefinition/vtolpathfollowersettings.xml index 4f6758035..62469c113 100644 --- a/shared/uavobjectdefinition/vtolpathfollowersettings.xml +++ b/shared/uavobjectdefinition/vtolpathfollowersettings.xml @@ -7,11 +7,11 @@ - - + + - +