mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-31 16:52:10 +01:00
Merge branch 'master' into next
This commit is contained in:
commit
33fd073248
@ -9,7 +9,7 @@ Install XCode and its relatated command line tools (follow Apple documentation).
|
||||
Install git, curl and p7zip. You can use brew `brew install git curl p7zip` or macport: `sudo port install git curl p7zip`
|
||||
###Ubuntu
|
||||
|
||||
sudo apt-get install git build-essentials curl gdb wget debhelper p7zip-full unzip flex bison libsdl1.2-dev libudev-dev libusb-1.0-0-dev libc6-i386 mesa-common-dev
|
||||
sudo apt-get install git build-essential curl gdb wget debhelper p7zip-full unzip flex bison libsdl1.2-dev libudev-dev libusb-1.0-0-dev libc6-i386 mesa-common-dev
|
||||
|
||||
|
||||
###Windows
|
||||
|
11
CREDITS.txt
11
CREDITS.txt
@ -1,4 +1,4 @@
|
||||
Connor Abbott
|
||||
Connor Abbott
|
||||
Sergiy Anikeyev
|
||||
David Ankers
|
||||
Fredrik Arvidsson
|
||||
@ -6,13 +6,14 @@ Pedro Assuncao
|
||||
Werner Backes
|
||||
Jose Barros
|
||||
Alex Beck
|
||||
Roy Bekken
|
||||
Andre Bernet
|
||||
Mikael Blomqvist
|
||||
Pete Boehl
|
||||
Berkely Brown
|
||||
Joel Brueziere
|
||||
Thierry Bugeat
|
||||
Samuel Brugger
|
||||
Thierry Bugeat
|
||||
Glenn Campigli
|
||||
David Carlson
|
||||
Mike Carr
|
||||
@ -47,6 +48,7 @@ Andy Honecker
|
||||
Patrick Huebner
|
||||
Ryan Hunt
|
||||
Mark James
|
||||
Paul Jewell
|
||||
Michael Johnston
|
||||
Stefan Karlsson
|
||||
Ricky King
|
||||
@ -61,12 +63,13 @@ Edouard Lafargue
|
||||
Laurent Lalanne
|
||||
Fredrik Larsson
|
||||
Xavier Lecluse
|
||||
Richard Von Lehe
|
||||
Pablo Lema
|
||||
Matt Lipski
|
||||
David Llama
|
||||
Jasper Van Loenen
|
||||
Ben Matthews
|
||||
Greg Matthews
|
||||
Greg Matthews
|
||||
Guy McCaldin
|
||||
Alessio Morale
|
||||
Gary Mortimer
|
||||
@ -107,11 +110,9 @@ Rowan Taubitz
|
||||
Jim Allen Thibodaux
|
||||
Andrew Thoms
|
||||
Vladimir Timofeev
|
||||
Jasper Van Loenen
|
||||
Philippe Vanhaesendonck
|
||||
Vassilis Varveropoulos
|
||||
Kevin Vertucio
|
||||
Richard Von Lehe
|
||||
Alex Vrubel
|
||||
Mike Walters
|
||||
Sam Wang
|
||||
|
@ -1 +1,6 @@
|
||||
To be rewrited
|
||||
The LibrePilot code is licensed under the GPLv3. There are a few minor exceptions to this so please see
|
||||
the headers of all source code for copyright and license information. The full text of the GPLv3 can be
|
||||
read here: http://www.gnu.org/licenses/gpl-3.0.txt
|
||||
|
||||
Artwork is licensed under the Creative Commons BY-SA v3 license.
|
||||
For details please see: http://creativecommons.org/licenses/by-sa/3.0/
|
||||
|
45
Makefile
45
Makefile
@ -56,15 +56,32 @@ DIRS := $(DL_DIR) $(TOOLS_DIR) $(BUILD_DIR) $(PACKAGE_DIR) $(DIST_DIR) $(OPGCSSY
|
||||
|
||||
# Naming for binaries and packaging etc,.
|
||||
export ORG_BIG_NAME := LibrePilot
|
||||
GCS_BIG_NAME := ${ORG_BIG_NAME} GCS
|
||||
GCS_LABEL := GCS
|
||||
GCS_BIG_NAME := $(ORG_BIG_NAME) $(GCS_LABEL)
|
||||
# These should be lowercase with no spaces
|
||||
export ORG_SMALL_NAME := $(call smallify,$(ORG_BIG_NAME))
|
||||
GCS_SMALL_NAME := $(call smallify,$(GCS_BIG_NAME))
|
||||
# Change this once the DNS is set to http://wiki.librepilot.org/
|
||||
WIKI_URL_ROOT := https://librepilot.atlassian.net/wiki/display/LPDOC/
|
||||
|
||||
WEBSITE_URL := http://librepilot.org
|
||||
GIT_URL := https://bitbucket.org/librepilot/librepilot.git
|
||||
GITWEB_URL := https://bitbucket.org/librepilot/librepilot
|
||||
# Change this once the DNS is set to http://wiki.librepilot.org/
|
||||
WIKI_URL_ROOT := https://librepilot.atlassian.net/wiki/display/LPDOC/
|
||||
USAGETRACKER_URL := https://usagetracker.librepilot.org/
|
||||
|
||||
PACKAGING_EMAIL_ADDRESS := packaging@librepilot.org
|
||||
|
||||
define DESCRIPTION_SHORT :=
|
||||
A ground control station and firmware for UAV flight controllers
|
||||
endef
|
||||
|
||||
define DESCRIPTION_LONG :=
|
||||
The LibrePilot open source project was founded in July 2015.
|
||||
It focuses on research and development of software and hardware to be used in a variety of applications including vehicle control and stabilization, unmanned autonomous vehicles and robotics.
|
||||
One of the project’s primary goals is to provide an open and collaborative environment making it the ideal home for development of innovative ideas.
|
||||
endef
|
||||
|
||||
|
||||
# Set up default build configurations (debug | release)
|
||||
GCS_BUILD_CONF := release
|
||||
GOOGLE_API_VERSION := 14
|
||||
@ -170,7 +187,9 @@ UAVOBJGENERATOR_DIR := $(BUILD_DIR)/uavobjgenerator
|
||||
DIRS += $(UAVOBJGENERATOR_DIR)
|
||||
|
||||
.PHONY: uavobjgenerator
|
||||
uavobjgenerator $(UAVOBJGENERATOR): | $(UAVOBJGENERATOR_DIR)
|
||||
uavobjgenerator: $(UAVOBJGENERATOR)
|
||||
|
||||
$(UAVOBJGENERATOR): | $(UAVOBJGENERATOR_DIR)
|
||||
$(V1) cd $(UAVOBJGENERATOR_DIR) && \
|
||||
( [ -f Makefile ] || $(QMAKE) $(ROOT_DIR)/ground/uavobjgenerator/uavobjgenerator.pro \
|
||||
-spec $(QT_SPEC) CONFIG+=$(GCS_BUILD_CONF) CONFIG+=$(GCS_SILENT) ) && \
|
||||
@ -184,13 +203,13 @@ uavobjects: $(addprefix uavobjects_, $(UAVOBJ_TARGETS))
|
||||
UAVOBJ_XML_DIR := $(ROOT_DIR)/shared/uavobjectdefinition
|
||||
UAVOBJ_OUT_DIR := $(BUILD_DIR)/uavobject-synthetics
|
||||
|
||||
uavobjects_%: uavobjgenerator
|
||||
uavobjects_%: $(UAVOBJGENERATOR)
|
||||
@$(MKDIR) -p $(UAVOBJ_OUT_DIR)/$*
|
||||
$(V1) ( cd $(UAVOBJ_OUT_DIR)/$* && \
|
||||
$(UAVOBJGENERATOR) -$* $(UAVOBJ_XML_DIR) $(ROOT_DIR) ; \
|
||||
)
|
||||
|
||||
uavobjects_test: uavobjgenerator
|
||||
uavobjects_test: $(UAVOBJGENERATOR)
|
||||
$(V1) $(UAVOBJGENERATOR) -v $(UAVOBJ_XML_DIR) $(ROOT_DIR)
|
||||
|
||||
uavobjects_clean:
|
||||
@ -256,7 +275,7 @@ gcs_qmake $(GCS_MAKEFILE): | $(GCS_DIR)
|
||||
$(GCS_QMAKE_OPTS)
|
||||
|
||||
.PHONY: gcs
|
||||
gcs: uavobjgenerator $(GCS_MAKEFILE)
|
||||
gcs: $(UAVOBJGENERATOR) $(GCS_MAKEFILE)
|
||||
$(V1) $(MAKE) -w -C $(GCS_DIR)/$(MAKE_DIR);
|
||||
|
||||
.PHONY: gcs_clean
|
||||
@ -692,7 +711,7 @@ help:
|
||||
@$(ECHO)
|
||||
@$(ECHO) " This Makefile is known to work on Linux and Mac in a standard shell environment."
|
||||
@$(ECHO) " It also works on Windows by following the instructions given on this wiki page:"
|
||||
@$(ECHO) " http://wiki.openpilot.org/display/Doc/Windows%3A+Building+and+Packaging"
|
||||
@$(ECHO) " $(WIKI_ROOT_URL)Windows+Building+and+Packaging"
|
||||
@$(ECHO)
|
||||
@$(ECHO) " Here is a summary of the available targets:"
|
||||
@$(ECHO)
|
||||
@ -723,7 +742,7 @@ help:
|
||||
@$(ECHO) " <tool>_distclean - Remove downloaded <tool> distribution file(s)"
|
||||
@$(ECHO)
|
||||
@$(ECHO) " [Big Hammer]"
|
||||
@$(ECHO) " all - Generate UAVObjects, build openpilot firmware and gcs"
|
||||
@$(ECHO) " all - Generate UAVObjects, build $(ORG_BIG_NAME) firmware and gcs"
|
||||
@$(ECHO) " all_flight - Build all firmware, bootloaders and bootloader updaters"
|
||||
@$(ECHO) " all_fw - Build only firmware for all boards"
|
||||
@$(ECHO) " all_bl - Build only bootloaders for all boards"
|
||||
@ -776,9 +795,9 @@ help:
|
||||
@$(ECHO) " ut_<test>_run - Run test and dump output to console"
|
||||
@$(ECHO)
|
||||
@$(ECHO) " [Simulation]"
|
||||
@$(ECHO) " sim_osx - Build OpenPilot simulation firmware for OSX"
|
||||
@$(ECHO) " sim_osx - Build $(ORG_BIG_NAME) simulation firmware for OSX"
|
||||
@$(ECHO) " sim_osx_clean - Delete all build output for the osx simulation"
|
||||
@$(ECHO) " sim_win32 - Build OpenPilot simulation firmware for Windows"
|
||||
@$(ECHO) " sim_win32 - Build $(ORG_BIG_NAME) simulation firmware for Windows"
|
||||
@$(ECHO) " using mingw and msys"
|
||||
@$(ECHO) " sim_win32_clean - Delete all build output for the win32 simulation"
|
||||
@$(ECHO)
|
||||
@ -804,7 +823,7 @@ help:
|
||||
@$(ECHO) " Supported groups are ($(UAVOBJ_TARGETS))"
|
||||
@$(ECHO)
|
||||
@$(ECHO) " [Packaging]"
|
||||
@$(ECHO) " package - Build and package the OpenPilot platform-dependent package (no clean)"
|
||||
@$(ECHO) " package - Build and package the platform-dependent package (no clean)"
|
||||
@$(ECHO) " opfw_resource - Generate resources to embed firmware binaries into the GCS"
|
||||
@$(ECHO) " dist - Generate source archive for distribution"
|
||||
@$(ECHO) " fw_dist - Generate archive of firmware"
|
||||
@ -836,5 +855,5 @@ help:
|
||||
@$(ECHO) " Tool download and install directories can be changed using environment variables:"
|
||||
@$(ECHO) " DL_DIR full path to downloads directory [downloads if not set]"
|
||||
@$(ECHO) " TOOLS_DIR full path to installed tools directory [tools if not set]"
|
||||
@$(ECHO) " More info: http://wiki.openpilot.org/display/Doc/OpenPilot+Build+System+Overview"
|
||||
@$(ECHO) " More info: $(WIKI_URL_ROOT)LibrePilot+Build+System+Overview"
|
||||
@$(ECHO)
|
||||
|
113
WHATSNEW.txt
113
WHATSNEW.txt
@ -1,3 +1,116 @@
|
||||
-- RELEASE-15.09 - First LibrePilot Release -- Supermoon Eclipse
|
||||
This is the first LibrePilot release.
|
||||
The main focus of this release is to bring back support for CC3D and a general re-branding of the GCS.
|
||||
|
||||
The full list of bug fixes and enhancements in this release is available here:
|
||||
https://librepilot.atlassian.net/issues/?filter=10300
|
||||
|
||||
|
||||
** Bug
|
||||
* [LP-37] - Memory wasted in pvPortMallocGeneric
|
||||
* [LP-57] - Errors during NewsPanel data scraping
|
||||
* [LP-58] - Splash Screen doesn't display
|
||||
* [LP-59] - Replace openpilot email address in packaging
|
||||
* [LP-65] - Heli config tab refresh
|
||||
* [LP-69] - Add SRXL to CC3D target
|
||||
* [LP-70] - Vehicle Setup Wizard allows a not working CC3D configuration
|
||||
* [LP-84] - Nano (Revo Nano) does not automatically select correct firmware after Firmware then Halt
|
||||
* [LP-89] - Port bug fixes from OP HotFix 150501
|
||||
* [LP-107] - Motors could accidentally turn off with the recent motor output scaling feature
|
||||
* [LP-115] - TPS and Acro+ settings are initialized incorrectly
|
||||
* [LP-116] - Add uninstall to Makefile to prevent side effects from Installing over a previous installation
|
||||
* [LP-123] - EasyTune yaw calculation is active even if easytune is not active
|
||||
* [LP-125] - PathUtils should return absolute pathes
|
||||
* [LP-127] - Fix Mac tool install md5 check
|
||||
* [LP-128] - ElevateAndCompress is broken at full throttle
|
||||
* [LP-134] - Obsolete Google Satellite Version
|
||||
* [LP-135] - Aux mag calibration issue
|
||||
* [LP-136] - Build errors caused by broken uavobjgenerator make dependencies
|
||||
* [LP-153] - Bug in configrevohwwidget.cpp use MAINPORT enum not FLEXIPORT
|
||||
* [LP-155] - GCS crashes on OS X 10.11 when the board is halted
|
||||
* [LP-156] - Update Vehicle templates to work with current UAVO's
|
||||
|
||||
** Epic
|
||||
* [LP-1] - Code Rebranding
|
||||
|
||||
** Story
|
||||
* [LP-3] - Artwork rebranding
|
||||
* [LP-4] - Add a Gitter chat link to README.txt
|
||||
* [LP-5] - Add back CC/CC3D Support
|
||||
* [LP-6] - Laurent/lp 03 artwork rebranding
|
||||
* [LP-7] - OP-1879 remove openpilot hardcoding
|
||||
* [LP-8] - OP-1929 broken package src
|
||||
* [LP-9] - Hotfix for files that were missed in share directory move due to rebase
|
||||
* [LP-12] - Openpilot migration
|
||||
* [LP-13] - some more OP hardcoding fixes
|
||||
* [LP-14] - Remove some more openpilot hardcoding
|
||||
* [LP-17] - Laurent/lp 03 artwork icons splashscreen
|
||||
* [LP-18] - Makefile fix
|
||||
* [LP-19] - Remove openpilot hardcoding
|
||||
* [LP-20] - Menu item change
|
||||
* [LP-21] - udevdir fix
|
||||
* [LP-22] - Desktopfile migration
|
||||
* [LP-23] - amorale/lp-05 readd cc rebased
|
||||
* [LP-24] - filnet/op 1518 osgearth
|
||||
* [LP-28] - Removed OpenPilot reference in About menu
|
||||
* [LP-33] - Remove op from gcs dir structure
|
||||
* [LP-35] - Removed OpenPilot reference in About Menu
|
||||
* [LP-43] - change links and headers in welcome plugin
|
||||
* [LP-44] - Review and cleanup to free some memory for CC3D
|
||||
* [LP-47] - Fixed missing QDataStream includes to make compilation on qt 5.5 work
|
||||
* [LP-48] - French translation
|
||||
* [LP-49] - Laurent/lp 48 update rebranding strings translations
|
||||
* [LP-50] - Make name define available for all by setting in openpilotgcs.pri
|
||||
* [LP-51] - Wrong config tab contents
|
||||
* [LP-52] - LP-51 Fix merge issue for Revo / Revonano HW config display
|
||||
* [LP-53] - Set up Anonymous data collection to send information to the LibrePilot website
|
||||
* [LP-55] - Config fix for echo without -e
|
||||
* [LP-62] - Implement rpm spec
|
||||
|
||||
** New Feature
|
||||
* [LP-100] - Make firmware package
|
||||
* [LP-101] - Make build possible with prebuilt firmware
|
||||
|
||||
** Task
|
||||
* [LP-16] - Vehicle template enhancements.
|
||||
* [LP-26] - Update Welcome page plugin.
|
||||
* [LP-27] - LP-16 Vehicle templates enhancements
|
||||
* [LP-36] - Win install fixes
|
||||
* [LP-41] - Add support for ccache
|
||||
* [LP-42] - Added option for config file.
|
||||
* [LP-60] - Fix project links in readme
|
||||
* [LP-92] - Remove old Feed Forward
|
||||
* [LP-98] - SystemHealth refresh
|
||||
* [LP-99] - Decouple flight build
|
||||
* [LP-113] - Create new tool install framework
|
||||
* [LP-129] - Remove broken scaleMotor modes
|
||||
* [LP-138] - Remove OpenPilot branding from Makefile Help text
|
||||
* [LP-141] - Missing link for wiki help page on Stabilization Configuration page
|
||||
* [LP-142] - Replace remaining OpenPilot wiki links with LibrePilot links
|
||||
|
||||
** Improvement
|
||||
* [LP-10] - Cleanup build warnings on OSX
|
||||
* [LP-56] - Split roll/pitch acro+ factors
|
||||
* [LP-61] - Make more things configurable with make config
|
||||
* [LP-64] - Install target for ccache
|
||||
* [LP-66] - Add differential Roll mixing to Fixed Wing frames
|
||||
* [LP-67] - Add a txpid option that manage all PID factors at once
|
||||
* [LP-77] - Jira needs more Component options
|
||||
* [LP-80] - Extend linux packaging to easily support new distros
|
||||
* [LP-82] - Define all packaging descriptions and URLs in top Makefile
|
||||
* [LP-87] - Remove OpenPilot branding from Doxygen Documentation
|
||||
* [LP-93] - Thermal calibration should calculate also gyro bias
|
||||
* [LP-94] - Set up Wiki link in Configuration tabs to point to Librepilot Wiki
|
||||
* [LP-102] - Remove OpenPilot links in "About Plugins" dialog boxes
|
||||
* [LP-106] - Setup Wizard refresh
|
||||
* [LP-108] - Fixes for mpu6k
|
||||
* [LP-110] - Wizard : high rate servos and normal Esc rate for planes and ground vehicles
|
||||
* [LP-114] - Support to more than three Accessory channels
|
||||
* [LP-124] - Rename RollRatePID and PitcahRatePID to EasyTuneRateRoll and EasyTuneRatePitch
|
||||
* [LP-130] - Add an overridable postfix that is appended to GCS name
|
||||
* [LP-162] - Add more data to usage tracker.
|
||||
|
||||
|
||||
--- RELEASE-15.05.01 HOTFIX --- Banana Split ---
|
||||
This release fixes an important bug. All Revolution hardware running 15.05 should upgrade to 15.05.01. Note that this is a hotfix; it can
|
||||
simply be flashed without an erase settings. Furthermore, please review your vtolpathfollowersettings:HorizontalVelMax; a value of around 4m/s would be more appropriate for preliminary trialing of a new release and will be changed in future.
|
||||
|
@ -37,7 +37,7 @@
|
||||
* @note If repository or git utility is unavailable, strings can be empty or be "None".
|
||||
* So do not assume they have some particular format when used, use them as strings only.
|
||||
*
|
||||
* More info: http://wiki.openpilot.org/display/Doc/Building+and+Packaging+Overview
|
||||
* More info: https://librepilot.atlassian.net/wiki/display/LPDOC/Building+and+Packaging+Overview
|
||||
*/
|
||||
class VersionInfo {
|
||||
public:
|
||||
|
@ -316,8 +316,8 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index)
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_RCVRPORT_COMBRIDGE:
|
||||
|
@ -314,8 +314,8 @@ void ConfigRevoNanoHWWidget::rcvrPortChanged(int index)
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_RCVRPORT_COMBRIDGE:
|
||||
|
@ -241,6 +241,16 @@ void ConfigRevoWidget::storeAndClearBoardRotation()
|
||||
data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = 0;
|
||||
data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = 0;
|
||||
attitudeSettings->setData(data);
|
||||
|
||||
// Store current aux mag board rotation
|
||||
AuxMagSettings *auxMagSettings = AuxMagSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(auxMagSettings);
|
||||
AuxMagSettings::DataFields auxMagData = auxMagSettings->getData();
|
||||
auxMagStoredBoardRotation = auxMagData.Orientation;
|
||||
|
||||
// Set aux mag board rotation to no rotation
|
||||
auxMagData.Orientation = 0.0f;
|
||||
auxMagSettings->setData(auxMagData);
|
||||
}
|
||||
}
|
||||
|
||||
@ -250,6 +260,7 @@ void ConfigRevoWidget::recallBoardRotation()
|
||||
// Recall current board rotation
|
||||
isBoardRotationStored = false;
|
||||
|
||||
// Restore the flight controller board rotation
|
||||
AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(attitudeSettings);
|
||||
AttitudeSettings::DataFields data = attitudeSettings->getData();
|
||||
@ -257,6 +268,13 @@ void ConfigRevoWidget::recallBoardRotation()
|
||||
data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = storedBoardRotation[AttitudeSettings::BOARDROTATION_ROLL];
|
||||
data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = storedBoardRotation[AttitudeSettings::BOARDROTATION_PITCH];
|
||||
attitudeSettings->setData(data);
|
||||
|
||||
// Restore the aux mag board rotation
|
||||
AuxMagSettings *auxMagSettings = AuxMagSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(auxMagSettings);
|
||||
AuxMagSettings::DataFields auxMagData = auxMagSettings->getData();
|
||||
auxMagData.Orientation = auxMagStoredBoardRotation;
|
||||
auxMagSettings->setData(auxMagData);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -62,8 +62,9 @@ private:
|
||||
|
||||
Ui_RevoSensorsWidget *m_ui;
|
||||
|
||||
// Board rotation store/recall
|
||||
// Board rotation store/recall for FC and for aux mag
|
||||
qint16 storedBoardRotation[3];
|
||||
float auxMagStoredBoardRotation;
|
||||
bool isBoardRotationStored;
|
||||
|
||||
private slots:
|
||||
|
@ -58,6 +58,8 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
|
||||
ui = new Ui_StabilizationWidget();
|
||||
ui->setupUi(this);
|
||||
|
||||
setWikiURL("Stabilization+Configuration");
|
||||
|
||||
setupExpoPlot();
|
||||
|
||||
setupStabBanksGUI();
|
||||
|
@ -707,7 +707,7 @@ Throttle channel greater or equal to Throttle Max value.</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>FullPID Settings</string>
|
||||
<string>EasyTune Settings</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="0" column="1">
|
||||
@ -851,7 +851,7 @@ font:bold;</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Roll/Pitch I factor for full PID mode</string>
|
||||
<string>Roll/Pitch I factor for EasyTune mode</string>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>25</number>
|
||||
@ -928,7 +928,7 @@ font:bold;</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Roll/Pitch D factor for full PID mode</string>
|
||||
<string>Roll/Pitch D factor for EasyTune mode</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>4</number>
|
||||
@ -1010,7 +1010,7 @@ font:bold;</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Yaw P factor for full PID mode</string>
|
||||
<string>Yaw P factor for EasyTune mode</string>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>10</number>
|
||||
@ -1084,7 +1084,7 @@ font:bold;</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Yaw I factor for full PID mode</string>
|
||||
<string>Yaw I factor for EasyTune mode</string>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<double>0.000000000000000</double>
|
||||
@ -1146,7 +1146,7 @@ font:bold;</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Yaw D factor for full PID mode</string>
|
||||
<string>Yaw D factor for EasyTune mode</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>4</number>
|
||||
@ -1264,7 +1264,7 @@ font:bold;</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Yaw P factor for full PID mode</string>
|
||||
<string>Yaw P factor for EasyTune mode</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>1</number>
|
||||
@ -1307,7 +1307,7 @@ font:bold;</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Roll/Pitch I factor for full PID mode</string>
|
||||
<string>Roll/Pitch I factor for EasyTune mode</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>1</number>
|
||||
|
@ -2,7 +2,8 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file importexportgadgetwidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @brief Widget for Import/Export Plugin
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
@ -202,7 +203,7 @@ void ImportExportGadgetWidget::importConfiguration(const QString & fileName)
|
||||
|
||||
void ImportExportGadgetWidget::on_helpButton_clicked()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(tr("http://wiki.openpilot.org/x/OQBj")));
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Import+and+Export+Settings")));
|
||||
}
|
||||
|
||||
|
||||
|
@ -118,6 +118,8 @@ struct hid_device_ {
|
||||
pthread_barrier_t barrier; /* Ensures correct startup sequence */
|
||||
pthread_barrier_t shutdown_barrier; /* Ensures correct shutdown sequence */
|
||||
int shutdown_thread;
|
||||
|
||||
bool run_loop_stopped;
|
||||
};
|
||||
|
||||
static hid_device *new_hid_device(void)
|
||||
@ -133,6 +135,7 @@ static hid_device *new_hid_device(void)
|
||||
dev->input_report_buf = NULL;
|
||||
dev->input_reports = NULL;
|
||||
dev->shutdown_thread = 0;
|
||||
dev->run_loop_stopped = 0;
|
||||
|
||||
/* Thread objects */
|
||||
pthread_mutex_init(&dev->mutex, NULL);
|
||||
@ -173,7 +176,13 @@ static void free_hid_device(hid_device *dev)
|
||||
pthread_mutex_destroy(&dev->mutex);
|
||||
|
||||
/* Free the structure itself. */
|
||||
free(dev);
|
||||
// Note: We can't delete the dev struct, since we might get
|
||||
// an asynchronous call to hid_device_removal_callback, which
|
||||
// gets the dev passed as an argument.
|
||||
//
|
||||
// See stop_run_loop for an explanation why this happens.
|
||||
//
|
||||
// free(dev);
|
||||
}
|
||||
|
||||
static IOHIDManagerRef hid_mgr = 0x0;
|
||||
@ -548,6 +557,38 @@ hid_device * HID_API_EXPORT hid_open(unsigned short vendor_id, unsigned short pr
|
||||
return handle;
|
||||
}
|
||||
|
||||
// Use a shared mutex for all devices.
|
||||
static pthread_mutex_t stop_run_loop_mutex = PTHREAD_MUTEX_INITIALIZER;
|
||||
|
||||
static void stop_run_loop(hid_device* dev)
|
||||
{
|
||||
bool stop_run_loop;
|
||||
|
||||
// There seems to be a bug in IOHIDDeviceRegisterRemovalCallback,
|
||||
// which causes de-registration of the removal callback
|
||||
// (hid_device_removal_callbacl) to fail.
|
||||
//
|
||||
// Because of this, hid_device_removal_callback will be called after
|
||||
// the read_thread has executed perform_signal_callback, which also
|
||||
// calls CFRunLoopStop. This second call to CFRunLoopStop is executed
|
||||
// in another thread, sometimes after the read_thread has executed, and
|
||||
// this causes crashes.
|
||||
//
|
||||
// Because of this asynchronous call to hid_device_removal_callback,
|
||||
// the dev structs are leaked, for now.
|
||||
|
||||
pthread_mutex_lock(&stop_run_loop_mutex);
|
||||
stop_run_loop = !dev->run_loop_stopped;
|
||||
if (stop_run_loop) {
|
||||
dev->run_loop_stopped = 1;
|
||||
}
|
||||
pthread_mutex_unlock(&stop_run_loop_mutex);
|
||||
|
||||
if (stop_run_loop) {
|
||||
CFRunLoopStop(dev->run_loop);
|
||||
}
|
||||
}
|
||||
|
||||
static void hid_device_removal_callback(void *context, IOReturn result,
|
||||
void *sender)
|
||||
{
|
||||
@ -555,7 +596,8 @@ static void hid_device_removal_callback(void *context, IOReturn result,
|
||||
hid_device *d = context;
|
||||
|
||||
d->disconnected = 1;
|
||||
CFRunLoopStop(d->run_loop);
|
||||
|
||||
stop_run_loop(d);
|
||||
}
|
||||
|
||||
/* The Run Loop calls this function for each input report received.
|
||||
@ -614,7 +656,8 @@ static void hid_report_callback(void *context, IOReturn result, void *sender,
|
||||
static void perform_signal_callback(void *context)
|
||||
{
|
||||
hid_device *dev = context;
|
||||
CFRunLoopStop(dev->run_loop); /*TODO: CFRunLoopGetCurrent()*/
|
||||
|
||||
stop_run_loop(dev);
|
||||
}
|
||||
|
||||
static void *read_thread(void *param)
|
||||
|
@ -163,7 +163,7 @@ int opHID_hidapi::open(int max, int vid, int pid, int usage_page, int usage)
|
||||
devices_found = false;
|
||||
} else {
|
||||
OPHID_DEBUG("HID Device Found");
|
||||
OPHID_DEBUG(" type:............VID(%04hx).PID(%04hx)", vid, pid);
|
||||
OPHID_DEBUG(" type:............VID(%04hx).PID(%04hx)", (unsigned short)vid, (unsigned short)pid);
|
||||
devices_found = true;
|
||||
}
|
||||
} else {
|
||||
|
@ -1872,13 +1872,13 @@ void VehicleConfigurationHelper::setupElevon()
|
||||
mixerChannelSettings channels[ActuatorSettings::CHANNELADDR_NUMELEM];
|
||||
GUIConfigDataUnion guiSettings = getGUIConfigData();
|
||||
|
||||
// Motor (Chan 3)
|
||||
channels[2].type = MIXER_TYPE_MOTOR;
|
||||
channels[2].throttle1 = 100;
|
||||
channels[2].throttle2 = 0;
|
||||
channels[2].roll = 0;
|
||||
channels[2].pitch = 0;
|
||||
channels[2].yaw = 0;
|
||||
// Motor (Chan 4)
|
||||
channels[3].type = MIXER_TYPE_MOTOR;
|
||||
channels[3].throttle1 = 100;
|
||||
channels[3].throttle2 = 0;
|
||||
channels[3].roll = 0;
|
||||
channels[3].pitch = 0;
|
||||
channels[3].yaw = 0;
|
||||
|
||||
// Elevon Servo 1 (Chan 1)
|
||||
channels[0].type = MIXER_TYPE_SERVO;
|
||||
@ -1896,7 +1896,7 @@ void VehicleConfigurationHelper::setupElevon()
|
||||
channels[1].pitch = 100;
|
||||
channels[1].yaw = 0;
|
||||
|
||||
guiSettings.fixedwing.FixedWingThrottle = 3;
|
||||
guiSettings.fixedwing.FixedWingThrottle = 4;
|
||||
guiSettings.fixedwing.FixedWingRoll1 = 1;
|
||||
guiSettings.fixedwing.FixedWingRoll2 = 2;
|
||||
|
||||
|
@ -34,7 +34,7 @@
|
||||
#include <QLineEdit>
|
||||
#include <QToolButton>
|
||||
|
||||
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), m_currentBoardId(-1), m_isConnected(false), m_isWidgetUpdatesAllowed(true),
|
||||
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), m_currentBoardId(-1), m_isConnected(false), m_isWidgetUpdatesAllowed(true), m_wikiURL("Welcome"),
|
||||
m_saveButton(NULL), m_isDirty(false), m_outOfLimitsStyle("background-color: rgb(255, 0, 0);"), m_realtimeUpdateTimer(NULL)
|
||||
{
|
||||
m_pluginManager = ExtensionSystem::PluginManager::instance();
|
||||
|
@ -2,7 +2,8 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file importsummary.cpp
|
||||
* @author (C) 2011 The OpenPilot Team, http://www.openpilot.org
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup UAVSettingsImportExport UAVSettings Import/Export Plugin
|
||||
@ -59,7 +60,8 @@ ImportSummaryDialog::~ImportSummaryDialog()
|
||||
*/
|
||||
void ImportSummaryDialog::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(tr("http://wiki.openpilot.org/display/Doc/UAV+Settings+import-export"), QUrl::StrictMode));
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("UAV+Settings+Import-Export"),
|
||||
QUrl::StrictMode));
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -2,7 +2,8 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file uploadergadgetwidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup YModemUploader YModem Serial Uploader Plugin
|
||||
@ -550,7 +551,8 @@ void UploaderGadgetWidget::systemEraseBoot()
|
||||
commonSystemBoot(true, true);
|
||||
break;
|
||||
case QMessageBox::Help:
|
||||
QDesktopServices::openUrl(QUrl(tr("http://wiki.openpilot.org/display/Doc/Erase+board+settings"), QUrl::StrictMode));
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Erase+board+settings"),
|
||||
QUrl::StrictMode));
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -1148,7 +1150,8 @@ UploaderGadgetWidget::~UploaderGadgetWidget()
|
||||
|
||||
void UploaderGadgetWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl(tr("http://wiki.openpilot.org/x/AoBZ"), QUrl::StrictMode));
|
||||
QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Firmware+Tab"),
|
||||
QUrl::StrictMode));
|
||||
}
|
||||
|
||||
int UploaderGadgetWidget::confirmEraseSettingsMessageBox()
|
||||
|
@ -199,10 +199,12 @@ void UsageTrackerPlugin::collectUsageParameters(QMap<QString, QString> ¶mete
|
||||
parameters["conf_uport"] = getUAVFieldValue(objManager, "HwSettings", "USB_HIDPort");
|
||||
parameters["conf_vport"] = getUAVFieldValue(objManager, "HwSettings", "USB_VCPPort");
|
||||
|
||||
parameters["conf_acceltau"] = getUAVFieldValue(objManager, "AttitudeSettings", "AccelTau");
|
||||
parameters["conf_rotation"] = QString("[%1:%2:%3]")
|
||||
.arg(getUAVFieldValue(objManager, "AttitudeSettings", "BoardRotation", 0))
|
||||
.arg(getUAVFieldValue(objManager, "AttitudeSettings", "BoardRotation", 1))
|
||||
.arg(getUAVFieldValue(objManager, "AttitudeSettings", "BoardRotation", 2));
|
||||
|
||||
parameters["conf_pidr"] = QString("[%1:%2:%3:%4][%5:%6:%7:%8][%9:%10:%11:%12]")
|
||||
.arg(getUAVFieldValue(objManager, "StabilizationSettingsBank1", "RollRatePID", 0))
|
||||
.arg(getUAVFieldValue(objManager, "StabilizationSettingsBank1", "RollRatePID", 1))
|
||||
|
@ -22,7 +22,7 @@ Item {
|
||||
ListModel {
|
||||
id: sitesModel
|
||||
ListElement { link: "http://www.librepilot.org" }
|
||||
ListElement { link: "http://wiki.openpilot.org" }
|
||||
ListElement { link: "https://librepilot.atlassian.net/wiki/display/LPDOC/Welcome" }
|
||||
ListElement { link: "http://forum.librepilot.org" }
|
||||
ListElement { link: "http://github.com/librepilot/LibrePilot/pulls" }
|
||||
ListElement { link: "http://github.com/librepilot/LibrePilot/issues" }
|
||||
|
@ -4,7 +4,7 @@
|
||||
<context>
|
||||
<name>Application</name>
|
||||
<message>
|
||||
<location filename="../../app/main.cpp" line="+202"/>
|
||||
<location filename="../../app/main.cpp" line="+203"/>
|
||||
<source>Failed to load core plug-in, reason is: %1</source>
|
||||
<translation>Échec du chargement du module complémentaire core, la raison est : %1</translation>
|
||||
</message>
|
||||
@ -14,7 +14,7 @@
|
||||
<translation>Impossible de passer les arguments de la ligne de commande à l'instance en cours d'exécution. Elle semble ne pas répondre.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+349"/>
|
||||
<location line="+347"/>
|
||||
<source>Could not find 'Core.pluginspec' in %1</source>
|
||||
<translatorcomment>[Platypus]Ajout de "est"</translatorcomment>
|
||||
<translation>'Core.pluginspec' est introuvable dans %1</translation>
|
||||
@ -52,7 +52,7 @@
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../plugins/coreplugin/generalsettings.cpp" line="+64"/>
|
||||
<location filename="../../plugins/coreplugin/generalsettings.cpp" line="+65"/>
|
||||
<source>General</source>
|
||||
<translation>Général</translation>
|
||||
</message>
|
||||
@ -126,7 +126,7 @@
|
||||
<context>
|
||||
<name>Core::Internal::MainWindow</name>
|
||||
<message>
|
||||
<location filename="../../plugins/coreplugin/mainwindow.cpp" line="+416"/>
|
||||
<location filename="../../plugins/coreplugin/mainwindow.cpp" line="+417"/>
|
||||
<source>&File</source>
|
||||
<translation>&Fichier</translation>
|
||||
</message>
|
||||
@ -1472,7 +1472,7 @@ Raison : %3</translation>
|
||||
<context>
|
||||
<name>OpenWith::Editors</name>
|
||||
<message>
|
||||
<location filename="../../plugins/coreplugin/coreconstants.h" line="+85"/>
|
||||
<location filename="../../plugins/coreplugin/coreconstants.h" line="+86"/>
|
||||
<source>Plain Text Editor</source>
|
||||
<translation>Éditeur de texte</translation>
|
||||
</message>
|
||||
@ -4111,107 +4111,6 @@ uniquement lorsque les valeurs changent</translation>
|
||||
<source>Form</source>
|
||||
<translation>Formulaire</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Feed Forward</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Accel Time Constant</source>
|
||||
<translation>Constante Temps Accélération </translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Decel Time Constant</source>
|
||||
<translation>Constante Temps Décélération </translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Mixer Settings</source>
|
||||
<translation>Paramètres de Mixage</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Feed Forward Configuration</source>
|
||||
<translation>Paramètres Feed Forward</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>When tuning: Slowly raise decel time from zero to just
|
||||
under the level where the motor starts to undershoot
|
||||
its target speed when decelerating.
|
||||
|
||||
Do it after accel time is setup.</source>
|
||||
<translation>Lors du réglage : Augmentez lentement temps de décélération de zéro jusqu'à
|
||||
arriver juste en dessous du niveau où le moteur commence à dépasser sa vitesse
|
||||
de consigne lors de la décélération.
|
||||
|
||||
A faire après avoir configuré la constante de temps d'accélération.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>In miliseconds.
|
||||
When tuning: Slowly raise accel time from zero to just
|
||||
under the level where the motor starts to overshoot
|
||||
its target speed.</source>
|
||||
<translation>En millisecondes.
|
||||
|
||||
Lors du réglage : Augmentez lentement le temps d'accélération de zéro jusqu'à arriver juste
|
||||
en dessous du niveau où le moteur commence à dépasser sa vitesse de consigne.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>1000</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Overall level of feed forward (in percentage).</source>
|
||||
<translation>Niveau global de Feed Forward (en pourcentage).</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Limits how much the engines can accelerate or decelerate.
|
||||
In 'units per second', a sound default is 1000.</source>
|
||||
<translation>Limite de combien les moteurs peuvent accélérer ou ralentir.
|
||||
En 'unités par seconde', la valeur par défaut est 1000.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>MaxAccel</source>
|
||||
<translation>AccélérationMaxi</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>000</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>FeedForward </source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><!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;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html></source>
|
||||
<translation><!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;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Méfiez-vous ! Cochez </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">les trois</span><span style=" font-family:'Sans'; font-size:10pt;"> cases pour essayer Feed Forward.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Cela fonctionnera uniquement si la carte est armée.</span></p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Enable FF tuning</source>
|
||||
<translation>Activer le réglage de Feed Forward</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Takes you to the wiki page</source>
|
||||
@ -4248,35 +4147,6 @@ p, li { white-space: pre-wrap; }
|
||||
<source>Enter name of vehicle. Max 20 characters.</source>
|
||||
<translation>Entrez le nom du véhicule : 20 caractères maximum.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><!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;">
|
||||
<table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;">
|
||||
<tr>
|
||||
<td style="border: none;">
|
||||
<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD REQUIRES CAUTION</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</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:'Lucida Grande'; font-size:13pt;">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.</span></p></td></tr></table></body></html></source>
|
||||
<translation><!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:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
<table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;">
|
||||
<tr>
|
||||
<td style="border: none;">
|
||||
<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">LA MISE EN PLACE DE FEED FORWARD EXIGE DE LA PRUDENCE</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Attention : L'activation du réglage Feed Forward lancera tous les moteurs à mi-gaz, vous avez été averti !</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:'Lucida Grande'; font-size:13pt;">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.</span></p></td></tr></table></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Vehicle Setup Wizard...</source>
|
||||
@ -5227,11 +5097,6 @@ valeur.</translation>
|
||||
<translatorcomment>Pas toucher !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>url:http://wiki.openpilot.org/display/Doc/Camera+Stabilization+Configuration</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Load default CameraStabilization settings except output channels into GCS.
|
||||
@ -6493,7 +6358,7 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>GPSAssist adds a brake/hold sequence to Stabilization when pitch & roll is centered, and on initiation of PositionHold. GPSAssist also enables pitch & roll control during the auto landing flight mode.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Le mode GPSAssist ajoute une séquence de freinage/maintien à la Stabilisation lorsque les manches Pitch et Roll sont centrés,ainsi qu'au début d'un maintien en position. GPSAssist autorise également l'utilisation des manches pitch et roll avec le mode de vol Auto Landing.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Le mode GPSAssist ajoute une séquence de freinage/maintien à la Stabilisation lorsque les manches Pitch et Roll sont centrés,ainsi qu'au début d'un maintien en position. GPSAssist autorise également l'utilisation des manches pitch et roll avec le mode de vol Auto Landing.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -7062,11 +6927,6 @@ Une valeur de 0.00 désactive le filtre.</translation>
|
||||
<source>Cancel</source>
|
||||
<translation>Annuler</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>url:http://wiki.openpilot.org/display/Doc/Revolution+Manual+Sensor+Calibration</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Accelerometer calibration</source>
|
||||
@ -7598,11 +7458,6 @@ value as the Kp.</source>
|
||||
<translatorcomment>Pas toucher</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>url:http://wiki.openpilot.org/x/DAO9</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Reloads the saved settings into GCS.
|
||||
@ -8243,11 +8098,6 @@ response (deg)</source>
|
||||
<translatorcomment>Pas toucher !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Factor</source>
|
||||
<translation>Facteur</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Expo</source>
|
||||
@ -8390,6 +8240,21 @@ response (deg)</source>
|
||||
<source><html><head/><body><p>In AxisLock mode, this setting controls how many degrees per second you can request with the stick before flight controller stops trying to gently hold its position and goes into normal rate mode. This setting works almost like a dead band. Default value should work fine.</p></body></html></source>
|
||||
<translation><html><head/><body><p>En mode AxisLock, ce paramètre contrôle combien de degrés par seconde vous pouvez demander avec le manche avant que la carte de vol ne cesse d'essayer de tenir doucement sa position et passe en mode rate normal. Ce paramètre fonctionne presque comme une zone morte. La valeur par défaut devrait fonctionner correctement.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>Link roll &amp; pitch sliders to move together</p></body></html></source>
|
||||
<translation><html><head/><body><p>Lier les curseurs roll &amp; pitch pour qu'ils bougent ensemble</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Roll Factor</source>
|
||||
<translation>Facteur Roll</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Pitch Factor</source>
|
||||
<translation>Facteur Pitch</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>TxPIDWidget</name>
|
||||
@ -8535,29 +8400,6 @@ d'une valeur de gaz supérieure ou égale à la la valeur maximale des gaz.
|
||||
<source>Update Mode</source>
|
||||
<translation>Mode Mise à Jour</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>PID values update mode which can be set to:
|
||||
- Never: this disables PID updates (but module still will be run if enabled),
|
||||
- When Armed: PID updated only when system is armed,
|
||||
- Always: PID updated always regardless of arm state.
|
||||
|
||||
Since the GCS updates GUI PID values in real time on change, could be
|
||||
tricky to change other PID values from the GUI if the module is enabled
|
||||
and constantly updates stabilization settings object. As a workaround,
|
||||
this option can be used to temporarily disable updates or enable them
|
||||
only when system is armed without disabling the module.</source>
|
||||
<translation>Mode de mise à jour des valeurs PID qui peut être réglé à :
|
||||
- Never : ceci désactive les mises à jour PID (mais le module continue de fonctionner, si activé,)
|
||||
- When Armed : Les PID sont mis à jour lorsque le système est armé,
|
||||
- Always : les PID sont toujours mis à jour, indépendamment de l'état d'armement.
|
||||
|
||||
Puisque la mise à jour des valeurs PID se fait en temps réel lors des changements, il peut-être
|
||||
difficile de changer les valeurs PID à partir de l'interface graphique si le module est activé
|
||||
et actualise les paramètres de stabilisation. Pour contourner ce problème,
|
||||
cette option peut être utilisée pour désactiver temporairement les mises à jour ou les permettre
|
||||
uniquement lorsque le système est armé, sans désactiver le module.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Throttle Range</source>
|
||||
@ -8584,11 +8426,6 @@ uniquement lorsque le système est armé, sans désactiver le module.</translati
|
||||
<translatorcomment>Pas toucher.</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>url:http://wiki.openpilot.org/x/DACiAQ</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Send settings to the board but do not save to the non-volatile memory</source>
|
||||
@ -8614,6 +8451,201 @@ uniquement lorsque le système est armé, sans désactiver le module.</translati
|
||||
<source>PID Bank</source>
|
||||
<translation>Banque PID</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>PID values update mode, which can be set to:
|
||||
- Never: this disables PID updates (but module still will be run if enabled),
|
||||
- When Armed: PID updated only when system is armed,
|
||||
- Always: PID updated always, regardless of arm state.
|
||||
|
||||
Since the GCS updates GUI PID values in real time on change, it could be
|
||||
tricky to change other PID values from the GUI if the module is enabled
|
||||
and constantly updates stabilization settings object. As a workaround,
|
||||
this option can be used to temporarily disable updates or enable them
|
||||
only when system is armed without disabling the module.</source>
|
||||
<translation>Mode de mise à jour des valeurs PID, qui peut être réglé à :
|
||||
- Never : ceci désactive les mises à jour PID (mais le module continue de fonctionner, si activé,)
|
||||
- When Armed : Les PID sont mis à jour lorsque le système est armé,
|
||||
- Always : les PID sont toujours mis à jour, indépendamment de l'état d'armement.
|
||||
|
||||
Puisque la mise à jour des valeurs PID se fait en temps réel lors des changements, il peut-être
|
||||
difficile de changer les valeurs PID à partir de l'interface graphique si le module est activé
|
||||
et actualise les paramètres de stabilisation. Pour contourner ce problème,
|
||||
cette option peut être utilisée pour désactiver temporairement les mises à jour ou les permettre
|
||||
uniquement lorsque le système est armé, sans désactiver le module.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Photographer</source>
|
||||
<translation>Photographe</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>FPV Racer</source>
|
||||
<translation>FPV Racer</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Reset Roll/Pitch factors to default values</source>
|
||||
<translation>RaZ des facteurs Roll/Pitch aux valeurs par défaut</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Default</source>
|
||||
<translation>Défaut</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>button:default</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>buttongroup:10</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Roll/Pitch I Factor</source>
|
||||
<translation>Facteur I Roll/Pitch</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>objname:TxPIDSettings</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>fieldname:EasyTunePitchRollRateFactors</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>scale:0.1</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>element:I</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Roll/Pitch D Factor</source>
|
||||
<translation>Facteur D Roll/Pitch</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>scale:1</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>element:D</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Calculate Yaw PIDs based on Roll/Pitch PIDs</source>
|
||||
<translation>Calculer les PIDs Yaw à partir des PIDs Pitch/Roll</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>AutoCalc Yaw</source>
|
||||
<translation>Calcul Auto Yaw</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>fieldname:EasyTuneRatePIDRecalculateYaw</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>buttongroup:11</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Yaw P Factor</source>
|
||||
<translation>Facteur P Yaw</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>fieldname:EasyTuneYawRateFactors</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>element:P</source>
|
||||
<translatorcomment>Do not translate !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Yaw I Factor</source>
|
||||
<translation>Facteur I Yaw</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Yaw D Factor</source>
|
||||
<translation>Facteur D Yaw</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Soft</source>
|
||||
<translation>Doux</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Reset Yaw factors to default values</source>
|
||||
<translation>RaZ des facteurs Yaw aux valeurs par défaut</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Aggressive</source>
|
||||
<translation>Agressif</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>EasyTune Settings</source>
|
||||
<translation>Paramètres EasyTune</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Roll/Pitch I factor for EasyTune mode</source>
|
||||
<translation>Facteur I Roll/Pitch pour le mode EasyTune</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Roll/Pitch D factor for EasyTune mode</source>
|
||||
<translation>Facteur D Roll/Pitch pour le mode EasyTune</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Yaw P factor for EasyTune mode</source>
|
||||
<translation>Facteur P Yaw pour le mode EasyTune</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Yaw I factor for EasyTune mode</source>
|
||||
<translation>Facteur I Yaw pour le mode EasyTune</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Yaw D factor for EasyTune mode</source>
|
||||
<translation>Facteur D Yaw pour le mode EasyTune</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>VernierWidget</name>
|
||||
@ -9096,12 +9128,12 @@ les données en cache</translation>
|
||||
<translation>Fermer</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../plugins/setupwizard/connectiondiagram.cpp" line="+41"/>
|
||||
<location filename="../../plugins/setupwizard/connectiondiagram.cpp" line="+42"/>
|
||||
<source>Connection Diagram</source>
|
||||
<translation>Diagramme de Connexion</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+233"/>
|
||||
<location line="+235"/>
|
||||
<source>Save File</source>
|
||||
<translation>Enregistrer Fichier</translation>
|
||||
</message>
|
||||
@ -9232,12 +9264,12 @@ p, li { white-space: pre-wrap; }
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<location filename="../../plugins/setupwizard/pages/controllerpage.cpp" line="+205"/>
|
||||
<location filename="../../plugins/setupwizard/pages/controllerpage.cpp" line="+235"/>
|
||||
<source>Connect</source>
|
||||
<translation>Connecter</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../plugins/setupwizard/pages/controllerpage.cpp" line="-71"/>
|
||||
<location filename="../../plugins/setupwizard/pages/controllerpage.cpp" line="-100"/>
|
||||
<source><Unknown></source>
|
||||
<translation><Inconnu></translation>
|
||||
</message>
|
||||
@ -9556,32 +9588,42 @@ Veuillez sélectionner le type de multirotor désiré pour la configuration ci-d
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<location filename="../../plugins/setupwizard/pages/outputcalibrationpage.cpp" line="+561"/>
|
||||
<location line="+131"/>
|
||||
<location filename="../../plugins/setupwizard/pages/outputcalibrationpage.cpp" line="+639"/>
|
||||
<location line="+179"/>
|
||||
<location line="+14"/>
|
||||
<source>Start</source>
|
||||
<translation>Démarrer</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../plugins/setupwizard/pages/outputcalibrationpage.cpp" line="-268"/>
|
||||
<location filename="../../plugins/setupwizard/pages/outputcalibrationpage.cpp" line="-392"/>
|
||||
<location line="+8"/>
|
||||
<location line="+243"/>
|
||||
<location line="+40"/>
|
||||
<location line="+353"/>
|
||||
<source>Output value : <b>%1</b> µs</source>
|
||||
<translation>Valeur de sortie : <b>%1</b> µs</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="-286"/>
|
||||
<location line="-356"/>
|
||||
<source><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></source>
|
||||
<translation><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></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+132"/>
|
||||
<location line="+131"/>
|
||||
<location line="+23"/>
|
||||
<location line="+23"/>
|
||||
<location line="+369"/>
|
||||
<location line="+99"/>
|
||||
<location line="+100"/>
|
||||
<source>Output %1 value : <b>%2</b> µs</source>
|
||||
<translation>Valeur de sortie %1 : <b>%2</b> µs</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="-420"/>
|
||||
<location line="+179"/>
|
||||
<location line="+14"/>
|
||||
<source>Stop</source>
|
||||
<translation>Arrêter</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="-59"/>
|
||||
<location line="-78"/>
|
||||
<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 librepilot.org support forum.</source>
|
||||
@ -9590,14 +9632,21 @@ 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 librepilot.org.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+134"/>
|
||||
<source>Output value : <b>%1</b> µs (Min)</source>
|
||||
<translation>Valeur de sortie : <b>%1</b> µs (Min)</translation>
|
||||
<location line="+124"/>
|
||||
<location line="+100"/>
|
||||
<location line="+100"/>
|
||||
<source>Output %1 value : <b>%2</b> µs (Min)</source>
|
||||
<translation>Valeur de sortie %1 : <b>%2</b> µs (Min)</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="-169"/>
|
||||
<location line="+31"/>
|
||||
<source>Output value : <b>%1</b> µs (Max)</source>
|
||||
<translation>Valeur de sortie : <b>%1</b> µs (Max)</translation>
|
||||
<location line="+70"/>
|
||||
<location line="+31"/>
|
||||
<location line="+69"/>
|
||||
<location line="+32"/>
|
||||
<source>Output %1 value : <b>%2</b> µs (Max)</source>
|
||||
<translation>Valeur de sortie %1 : <b>%2</b> µs (Max)</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../plugins/setupwizard/pages/outputcalibrationpage.ui"/>
|
||||
@ -9625,22 +9674,6 @@ Soyez certain d'utiliser la bonne version de firmware puis redémarrer l&ap
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Cantarell'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This step calibrates</span><span style=" font-size:10pt; font-weight:600;"> the minimum, center and maximum angle of the servo</span><span style=" font-size:10pt;">. 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. <br />When done press button again to stop.</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-size:10pt;">Check Reverse to reverse servo action.</span></p></body></html></source>
|
||||
<translation><!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:'Cantarell'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Cette étape va ajuster</span><span style=" font-size:10pt; font-weight:600;"> l'angle minimum, centré et maximum du servo</span><span style=" font-size:10pt;">. Pour ajuster les positions de ce servo, appuyez sur "Démarrer" et déplacez les curseurs en fonction de l'angle désiré. Le servo bouge en fonction de la position du curseur en cours.<br />Lorsque vous avez terminé, appuyez à nouveau sur le bouton pour arrêter.</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-size:10pt;">Cochez "Inverser" pour changer la direction de mouvement du servo.</span></p></body></html>
|
||||
</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><!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:'Cantarell'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br />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. </span></p></body></html></source>
|
||||
<translation><!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">
|
||||
@ -9681,6 +9714,38 @@ p, li { white-space: pre-wrap; }
|
||||
<p align="center" style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:10pt; font-weight:600; color:#ff0000;">TRES IMPORTANT !</span><span style=" font-family:'Lucida Grande'; font-size:10pt;"><br /></span><span style=" font-family:'Lucida Grande'; font-size:10pt; font-weight:600; color:#ff0000;">ENLEVER TOUTES LES HELICES DE VOTRE VEHICULE AVANT DE CONTINUER !</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:'Lucida Grande'; font-size:10pt;">Branchez tous les composants comme sur l'illustration dans la page de résumé et alimentez avec une source externe comme une batterie avant de continuer.</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:'Lucida Grande'; font-size:10pt;">En fonction du véhicule que vous avez sélectionné, les moteurs pilotés par des variateurs et/ou les servos contrôlés directement par la carte de vol devront-être calibrés. Les étapes suivantes vous guideront en toute sécurité dans ce processus. </span></p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><!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:'Cantarell'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This step calibrates</span><span style=" font-size:10pt; font-weight:600;"> the minimum, center and maximum angle of the servo</span><span style=" font-size:10pt;">. 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. <br />When done press button again to stop.</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-size:10pt;">Check Reverse to reverse servo action if green arrow </span><a name="result_box"></a>does not match the movement of the servo.</p></body></html></source>
|
||||
<translation><!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:'Cantarell'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Cette étape va ajuster</span><span style=" font-size:10pt; font-weight:600;"> l'angle minimum, centré et maximum du servo</span><span style=" font-size:10pt;">. Pour ajuster les positions de ce servo, appuyez sur "Démarrer" et déplacez les curseurs en fonction de l'angle désiré. Le servo bouge en fonction de la position du curseur en cours.<br />Lorsque vous avez terminé, appuyez à nouveau sur le bouton pour arrêter.</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-size:10pt;">Cochez "Inverser" pour changer la direction si le mouvement du servo ne correspond pas à la flèche verte.</span></p></body></html>
|
||||
</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><!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:'Cantarell'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This step calibrates</span><span style=" font-size:10pt; font-weight:600;"> the minimum, center and maximum angle of the two servo</span><span style=" font-size:10pt;">, at same time. To set the angles for those servo, press the Start button below and slide the slider for the angle to set. The servo will follow the sliders position. Please adjust and compare the two servo's movement.<br />When done press button again to stop.</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-size:10pt;">Check Reverse to reverse servo action if green arrow </span><a name="result_box"></a>does not match the movement of the servo.</p></body></html></source>
|
||||
<translation><!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:'Cantarell'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Cette étape va ajuster</span><span style=" font-size:10pt; font-weight:600;"> l'angle minimum, centré et maximum de deux servos</span><span style=" font-size:10pt;">, en même temps. Pour ajuster les positions de ces servos, appuyez sur "Démarrer" et déplacez les curseurs en fonction de l'angle désiré. Le servo bouge en fonction de la position du curseur en cours.<br />Lorsque vous avez terminé, appuyez à nouveau sur le bouton pour arrêter.</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-size:10pt;">Cochez "Inverser" pour changer la direction si le mouvement d'un servo ne correspond pas à la flèche verte.</span></p></body></html>
|
||||
</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>SavePage</name>
|
||||
@ -10417,7 +10482,7 @@ p, li { white-space: pre-wrap; }
|
||||
<context>
|
||||
<name>ConfigMultiRotorWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp" line="+169"/>
|
||||
<location filename="../../plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp" line="+174"/>
|
||||
<source>Input</source>
|
||||
<translation>Entrée</translation>
|
||||
</message>
|
||||
@ -10427,7 +10492,7 @@ p, li { white-space: pre-wrap; }
|
||||
<translation>Sortie</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+420"/>
|
||||
<location line="+427"/>
|
||||
<location line="+24"/>
|
||||
<location line="+31"/>
|
||||
<location line="+31"/>
|
||||
@ -10435,18 +10500,18 @@ p, li { white-space: pre-wrap; }
|
||||
<location line="+24"/>
|
||||
<location line="+24"/>
|
||||
<location line="+44"/>
|
||||
<location line="+255"/>
|
||||
<location line="+267"/>
|
||||
<location line="+70"/>
|
||||
<source>Configuration OK</source>
|
||||
<translation>Configuration OK</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="-360"/>
|
||||
<location line="-372"/>
|
||||
<source><font color='red'>ERROR: Assign a Yaw channel</font></source>
|
||||
<translation><font color='red'>ERREUR : Veuillez affecter le canal de Yaw</font></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+429"/>
|
||||
<location line="+441"/>
|
||||
<source>Duplicate channel in motor outputs</source>
|
||||
<translation>Canaux en double dans le sorties moteur</translation>
|
||||
</message>
|
||||
@ -10469,7 +10534,7 @@ p, li { white-space: pre-wrap; }
|
||||
<context>
|
||||
<name>ConfigCCHWWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/config_cc_hw_widget.cpp" line="+91"/>
|
||||
<location filename="../../plugins/config/config_cc_hw_widget.cpp" line="+92"/>
|
||||
<source>Enable GPS module and reboot the board to be able to select GPS protocol</source>
|
||||
<translation>Activez le module GPS et redémarrez la carte pour pouvoir choisir le protocole GPS</translation>
|
||||
</message>
|
||||
@ -10494,29 +10559,19 @@ p, li { white-space: pre-wrap; }
|
||||
<source>Warning: you have disabled USB Telemetry on both USB HID Port and USB VCP Port, this currently is not supported</source>
|
||||
<translation>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</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+15"/>
|
||||
<source>http://wiki.openpilot.org/x/D4AUAQ</source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>ConfigCCAttitudeWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/configccattitudewidget.cpp" line="+159"/>
|
||||
<location filename="../../plugins/config/configccattitudewidget.cpp" line="+160"/>
|
||||
<source>Calibration timed out before receiving required updates.</source>
|
||||
<translation>Temps d'attente dépassé avant d'avoir reçu les mises à jour demandées.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+58"/>
|
||||
<source>http://wiki.openpilot.org/x/44Cf</source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>ConfigGadgetWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/configgadgetwidget.cpp" line="+220"/>
|
||||
<location filename="../../plugins/config/configgadgetwidget.cpp" line="+221"/>
|
||||
<source>Unsaved changes</source>
|
||||
<translation>Modifications non sauvegardées</translation>
|
||||
</message>
|
||||
@ -10531,12 +10586,7 @@ Voulez-vous toujours continuer ?</translation>
|
||||
<context>
|
||||
<name>ConfigInputWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/configinputwidget.cpp" line="+396"/>
|
||||
<source>http://wiki.openpilot.org/x/04Cf</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+7"/>
|
||||
<location filename="../../plugins/config/configinputwidget.cpp" line="+422"/>
|
||||
<source>Arming Settings are now set to 'Always Disarmed' for your safety.</source>
|
||||
<translatorcomment>Contexte : Onglet "Paramètres d'Armement"</translatorcomment>
|
||||
<translation>Pour des raisons de sécurité les Paramètres d'Armement ont été modifiés à 'Toujours Désarmé'.</translation>
|
||||
@ -10646,7 +10696,7 @@ Voulez-vous toujours continuer ?</translation>
|
||||
<translation><p>Vous avez la possibilité d'appuyer sur Suivant pour ignorer ce canal.</p></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+796"/>
|
||||
<location line="+822"/>
|
||||
<source>Ground Vehicle</source>
|
||||
<translation>Véhicule terrestre</translation>
|
||||
</message>
|
||||
@ -10656,7 +10706,7 @@ Voulez-vous toujours continuer ?</translation>
|
||||
<translation type="unfinished"><p>Veuillez <b>centrer</b> le contrôle des gaz et appuyez sur OK lorsque vous êtes prêt.</p></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="-999"/>
|
||||
<location line="-1025"/>
|
||||
<source>Please center all controls and trims and press Next when ready.
|
||||
|
||||
For a ground vehicle, this center position will be used as neutral value of each channel.</source>
|
||||
@ -10670,7 +10720,7 @@ Pour un véhicule terrestre, ces positions centrales seront utilisées comme neu
|
||||
<translation>Suivant / Sauter</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+748"/>
|
||||
<location line="+774"/>
|
||||
<source>Stop Manual Calibration</source>
|
||||
<translation>Arrêter Calibration Manuelle</translation>
|
||||
</message>
|
||||
@ -10859,7 +10909,7 @@ Pour un véhicule terrestre, ces positions centrales seront utilisées comme neu
|
||||
<context>
|
||||
<name>NotificationItem</name>
|
||||
<message>
|
||||
<location filename="../../plugins/notify/notificationitem.cpp" line="+70"/>
|
||||
<location filename="../../plugins/notify/notificationitem.cpp" line="+71"/>
|
||||
<source>Never</source>
|
||||
<translation>Jamais</translation>
|
||||
</message>
|
||||
@ -11298,7 +11348,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
|
||||
<context>
|
||||
<name>VehicleConfigurationHelper</name>
|
||||
<message>
|
||||
<location filename="../../plugins/setupwizard/vehicleconfigurationhelper.cpp" line="+85"/>
|
||||
<location filename="../../plugins/setupwizard/vehicleconfigurationhelper.cpp" line="+86"/>
|
||||
<location line="+12"/>
|
||||
<source>Done!</source>
|
||||
<translation>Terminé !</translation>
|
||||
@ -11331,8 +11381,8 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
|
||||
</message>
|
||||
<message>
|
||||
<location line="+203"/>
|
||||
<location line="+32"/>
|
||||
<location line="+37"/>
|
||||
<location line="+40"/>
|
||||
<location line="+45"/>
|
||||
<source>Writing actuator settings</source>
|
||||
<translation>Écriture paramètres actionneurs</translation>
|
||||
</message>
|
||||
@ -11383,7 +11433,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
|
||||
<translation>Écriture modèle de configuration pour %1</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+157"/>
|
||||
<location line="+152"/>
|
||||
<source>Preparing mixer settings</source>
|
||||
<translation>Préparation des paramètres de mixage</translation>
|
||||
</message>
|
||||
@ -11404,7 +11454,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
|
||||
<context>
|
||||
<name>SystemHealthGadgetWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/systemhealth/systemhealthgadgetwidget.cpp" line="+68"/>
|
||||
<location filename="../../plugins/systemhealth/systemhealthgadgetwidget.cpp" line="+71"/>
|
||||
<source>Displays flight system errors. Click on an alarm for more information.</source>
|
||||
<translation>Affiche les erreurs du système de vol. Cliquer sur une alarme pour plus d'informations.</translation>
|
||||
</message>
|
||||
@ -12375,6 +12425,21 @@ La carte sera redémarrée et tous les paramètres effacés.</translation>
|
||||
<source>Assign your motor output channel</source>
|
||||
<translation>Affecter votre canal de sortie moteur</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source> Roll Diff</source>
|
||||
<translation>Diff Roll</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Value of Roll differential in percent</source>
|
||||
<translation>Valeur de différentiel Roll en pourcentage</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>0</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>GroundConfigWidget</name>
|
||||
@ -12687,6 +12752,21 @@ Les valeurs classiques sont de 100% en configuration + et 50% en configuration X
|
||||
<source>Select output curve for Accessory2 RcInput</source>
|
||||
<translation>Sélectionnez la courbe de mixage pour l'entrée RC Accessory2</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Accessory3</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Select output channel for Accessory3 RcInput</source>
|
||||
<translation>Sélectionnez le canal de sortie pour l'entrée RC Accessory3</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Select output curve for Accessory3 RcInput</source>
|
||||
<translation>Sélectionnez la courbe de mixage pour l'entrée RC Accessory3</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>RevoHWWidget</name>
|
||||
@ -13103,11 +13183,6 @@ Méfiez-vous de ne pas vous verrouiller l'accès !</translation>
|
||||
<source><html><head/><body><p>This is the coordinator id we currently are bound to.</p><p>To manually bind to a specific coordinator, just type</p><p>or paste its device id in this box and save.</p><p>The device must be rebooted for the binding to take place.</p></body></html></source>
|
||||
<translation><html><head/><body><p>Ceci est l'identifiant coordinateur avec lequel vous êtes associé.</p><p>Pour s'associer manuellement avec un coordinateur particulier, tapez simplement ou copier/coller l'identifiant de l'appareil dans ce champ puis enregistrer.</p><p>L'appareil doit être redémarré pour que l'association soit effective.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>url:http://wiki.openpilot.org/x/hgAGAQ</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz.</source>
|
||||
@ -13124,42 +13199,6 @@ Méfiez-vous de ne pas vous verrouiller l'accès !</translation>
|
||||
<translation></translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>OsgEarthview</name>
|
||||
<message>
|
||||
<location filename="../../plugins/osgearthview/osgearthview.ui"/>
|
||||
<source>Form</source>
|
||||
<translation>Formulaire</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>OsgEarthviewGadgetOptionsPage</name>
|
||||
<message>
|
||||
<location filename="../../plugins/osgearthview/osgearthviewgadgetoptionspage.ui"/>
|
||||
<source>Form</source>
|
||||
<translation>Formulaire</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>PFD SVG: </source>
|
||||
<translation>SVG PFD : </translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Use OpenGL for rendering</source>
|
||||
<translation>Utiliser le rendu OpenGL</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>High Quality text (OpenGL)</source>
|
||||
<translation>Texte Haute Qualité (OpenGL)</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Smooth updates</source>
|
||||
<translation>Mises à jour lissées</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>PathActionEditor</name>
|
||||
<message>
|
||||
@ -13269,9 +13308,9 @@ p, li { white-space: pre-wrap; }
|
||||
<context>
|
||||
<name>GCSSplashScreen</name>
|
||||
<message>
|
||||
<location filename="../../app/gcssplashscreen.cpp" line="+47"/>
|
||||
<location filename="../../app/gcssplashscreen.cpp" line="+49"/>
|
||||
<source> The %1 Project - All Rights Reserved</source>
|
||||
<translation>Le Projet %1 - Tous droits réservés</translation>
|
||||
<translation> Le Projet %1 - Tous droits réservés</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+3"/>
|
||||
@ -13300,7 +13339,7 @@ p, li { white-space: pre-wrap; }
|
||||
<context>
|
||||
<name>ConfigOutputWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/configoutputwidget.cpp" line="+111"/>
|
||||
<location filename="../../plugins/config/configoutputwidget.cpp" line="+112"/>
|
||||
<source>-</source>
|
||||
<translation>-</translation>
|
||||
</message>
|
||||
@ -13326,12 +13365,7 @@ p, li { white-space: pre-wrap; }
|
||||
<translation>Vous pouvez enregistrer vos changements des réglages de neutre.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+223"/>
|
||||
<source>http://wiki.openpilot.org/x/WIGf</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+32"/>
|
||||
<location line="+256"/>
|
||||
<source>OneShot and PWMSync output only works with Receiver Port settings marked with '+OneShot'<br>When using Receiver Port setting 'PPM_PIN8+OneShot' <b><font color='%1'>Bank %2</font></b> must be set to PWM</source>
|
||||
<translation>OneShot et PWMSync fonctionnent uniquement avec les ports récepteur marqués avec '+OneShot'<br>Lors de l'utilisation de la configuration 'PPM_PIN8+OneShot' <b><font color='%1'>la Banque %2</font></b> doit être réglée sur PWM</translation>
|
||||
</message>
|
||||
@ -13339,15 +13373,10 @@ p, li { white-space: pre-wrap; }
|
||||
<context>
|
||||
<name>ConfigRevoHWWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/configrevohwwidget.cpp" line="+95"/>
|
||||
<location filename="../../plugins/config/configrevohwwidget.cpp" line="+96"/>
|
||||
<source>Disabled</source>
|
||||
<translation>Désactivé</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+244"/>
|
||||
<source>http://wiki.openpilot.org/x/GgDBAQ</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>Core::UAVGadgetOptionsPageDecorator</name>
|
||||
@ -13372,14 +13401,6 @@ p, li { white-space: pre-wrap; }
|
||||
<translation>JE NE SAIS PAS !</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>OsgEarthviewGadgetFactory</name>
|
||||
<message>
|
||||
<location filename="../../plugins/osgearthview/osgearthviewgadgetfactory.cpp" line="+34"/>
|
||||
<source>Osg Earth View</source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>PathActionEditorGadgetFactory</name>
|
||||
<message>
|
||||
@ -14175,7 +14196,7 @@ Veuillez vérifier le fichier.
|
||||
<context>
|
||||
<name>ConfigStabilizationWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/configstabilizationwidget.cpp" line="+173"/>
|
||||
<location filename="../../plugins/config/configstabilizationwidget.cpp" line="+177"/>
|
||||
<source>Settings Bank %1</source>
|
||||
<translation>Banque Paramètres %1</translation>
|
||||
</message>
|
||||
@ -14457,7 +14478,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
<context>
|
||||
<name>ConfigVehicleTypeWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/configvehicletypewidget.cpp" line="+142"/>
|
||||
<location filename="../../plugins/config/configvehicletypewidget.cpp" line="+140"/>
|
||||
<source>Multirotor</source>
|
||||
<translation>Multirotor</translation>
|
||||
</message>
|
||||
@ -14481,11 +14502,6 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
<source>Custom</source>
|
||||
<translation>Personnalisé</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+314"/>
|
||||
<source>http://wiki.openpilot.org/x/44Cf</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>OpenPilot::GyroBiasCalibrationModel</name>
|
||||
@ -14733,7 +14749,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
<translation>Échec de la calibration du baromètre !</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+23"/>
|
||||
<location line="+24"/>
|
||||
<source>Gyro is calibrated.</source>
|
||||
<translation>Les gyroscopes sont calibrés.</translation>
|
||||
</message>
|
||||
@ -15251,7 +15267,11 @@ Veuillez essayer à nouveau.</translation>
|
||||
Note: if previously selected input combinations use the Flexi-port for input, only estimated airspeed will be available.
|
||||
|
||||
</source>
|
||||
<translation type="unfinished"></translation>
|
||||
<translation>Cette partie de l'assistant va vous aider à choisir et configurer comment obtenir les données de vitesse air. Le firmware actuel supporte trois méthodes pour l'obtenir, la première utilise une technique d'estimation logicielle et les deux autres se basent sur des capteurs de mesure.
|
||||
|
||||
Note : si une configuration d'entrée Rc utilise le port Flexi, seule l'estimation logicielle sera disponible.
|
||||
|
||||
</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+6"/>
|
||||
@ -15571,7 +15591,7 @@ p, li { white-space: pre-wrap; }
|
||||
<context>
|
||||
<name>ConfigOPLinkWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/configoplinkwidget.cpp" line="+152"/>
|
||||
<location filename="../../plugins/config/configoplinkwidget.cpp" line="+154"/>
|
||||
<location line="+9"/>
|
||||
<location line="+9"/>
|
||||
<location line="+9"/>
|
||||
@ -15731,7 +15751,7 @@ IMPORTANT : Ces nouveaux paramètres ne sont pas encore enregistrés sur la cart
|
||||
<context>
|
||||
<name>ConfigCcpmWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/cfg_vehicletypes/configccpmwidget.cpp" line="+1080"/>
|
||||
<location filename="../../plugins/config/cfg_vehicletypes/configccpmwidget.cpp" line="+1112"/>
|
||||
<source><h1>Swashplate Leveling Routine</h1></source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
@ -15795,6 +15815,11 @@ IMPORTANT : Ces nouveaux paramètres ne sont pas encore enregistrés sur la cart
|
||||
<source><h2>The CCPM swashplate levelling code is NOT complete!</h2><p><font color=red>DO NOT use it for flight!</font></source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+173"/>
|
||||
<source>Channel already used</source>
|
||||
<translation type="unfinished">Canal déjà utilisé</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>VehicleTemplateSelectorWidget</name>
|
||||
@ -15923,7 +15948,7 @@ Il est suggéré que si cela est une première configuration de votre contrôleu
|
||||
<message>
|
||||
<location line="+2"/>
|
||||
<source>Built-in template.</source>
|
||||
<translation type="unfinished">Modèle intégré.</translation>
|
||||
<translation>Modèle intégré.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+6"/>
|
||||
@ -15944,7 +15969,7 @@ Il est suggéré que si cela est une première configuration de votre contrôleu
|
||||
<context>
|
||||
<name>UsageTrackerPlugin</name>
|
||||
<message>
|
||||
<location filename="../../plugins/usagetracker/usagetrackerplugin.cpp" line="+80"/>
|
||||
<location filename="../../plugins/usagetracker/usagetrackerplugin.cpp" line="+81"/>
|
||||
<source>Usage feedback</source>
|
||||
<translation>Retour d'utilisation</translation>
|
||||
</message>
|
||||
@ -16057,11 +16082,41 @@ Méfiez-vous de ne pas vous verrouiller l'accès !</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>ConfigRevoNanoHWWidget</name>
|
||||
<name>ConfigFixedWingWidget</name>
|
||||
<message>
|
||||
<location filename="../../plugins/config/configrevonanohwwidget.cpp" line="+337"/>
|
||||
<source>http://wiki.openpilot.org/x/GgDBAQ</source>
|
||||
<translation type="unfinished"></translation>
|
||||
<location filename="../../plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp" line="+616"/>
|
||||
<source>Rudders are optional for Elevon frame</source>
|
||||
<translation>Les dérives sont optionnelles sur une aile volante (elevon)</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+4"/>
|
||||
<source>Second aileron servo is optional</source>
|
||||
<translation>Le deuxième servo d'aileron est optionnel</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+4"/>
|
||||
<source>Second elevator servo is optional</source>
|
||||
<translation>Le second servo de profondeur est optionnel</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+2"/>
|
||||
<source>Rudder is highly recommended for fixed wing.</source>
|
||||
<translation>Une dérive est fortement recommandée pour une voilure fixe.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+4"/>
|
||||
<source>Please assign Channel</source>
|
||||
<translation>Veuillez assigner un Canal</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+1"/>
|
||||
<source><font color='red'>ERROR: Assign all necessary channels</font></source>
|
||||
<translation><font color='red'>ERREUR : Veuillez affecter tous les canaux nécessaires</font></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+9"/>
|
||||
<source>Channel already used</source>
|
||||
<translation>Canal déjà utilisé</translation>
|
||||
</message>
|
||||
</context>
|
||||
</TS>
|
||||
|
@ -29,5 +29,10 @@ lc = $(subst A,a,$(subst B,b,$(subst C,c,$(subst D,d,$(subst E,e,$(subst F,f,$(s
|
||||
# Function to make all lowercase and replace spaces with -
|
||||
EMPTY :=
|
||||
SPACE := $(EMPTY) $(EMPTY)
|
||||
define NEWLINE :=
|
||||
|
||||
|
||||
endef
|
||||
|
||||
smallify = $(subst $(SPACE),-,$(call lc,$1))
|
||||
|
||||
|
@ -6,6 +6,14 @@ ifndef TOP_LEVEL_MAKEFILE
|
||||
$(error Top level Makefile must be used to build this target)
|
||||
endif
|
||||
|
||||
SED_SCRIPT := sed -i -e ' \
|
||||
s/<ARCHIVE_PREFIX>/$(PACKAGE_NAME)/g; \
|
||||
s/<EMAIL>/$(PACKAGING_EMAIL_ADDRESS)/g; \
|
||||
s,<URL>,$(WEBSITE_URL),g; \
|
||||
s,<GIT_URL>,$(GIT_URL),g; \
|
||||
s,<GITWEB_URL>,$(GITWEB_URL),g; \
|
||||
'
|
||||
|
||||
# Are we using a debian based distro?
|
||||
ifneq ($(wildcard /etc/apt/sources.list),)
|
||||
include $(ROOT_DIR)/package/linux/deb.mk
|
||||
|
@ -1,10 +1,13 @@
|
||||
# Get some info about the distro
|
||||
-include /etc/lsb-release
|
||||
|
||||
DEB_DIST := unstable
|
||||
DEB_DIST := $(DISTRIB_CODENAME)
|
||||
# Instead of RELEASE-15.01-RC1 debian wants 15.01~RC1
|
||||
UPSTREAM_VER := $(subst -,~,$(subst RELEASE-,,$(PACKAGE_LBL)))
|
||||
ifeq ($(DEB_DIST), unstable) # This should be set manually for a submission to Debian or similar
|
||||
DEB_REV := 1
|
||||
ifeq ($(DEB_DIST), trusty)
|
||||
DEB_REV := $(DEB_REV)$(DEB_DIST)1
|
||||
else
|
||||
DEB_REV := 0$(DEB_DIST)1
|
||||
endif
|
||||
DEB_NAME := $(ORG_SMALL_NAME)
|
||||
DEB_ORIG_SRC := $(PACKAGE_DIR)/$(DEB_NAME)_$(UPSTREAM_VER).orig.tar.gz
|
||||
@ -14,11 +17,12 @@ DEB_PACKAGE_NAME := $(DEB_NAME)_$(UPSTREAM_VER)-$(DEB_REV)_$(DEB_ARCH)
|
||||
DEB_DIR := package/linux/debian
|
||||
|
||||
SED_DATE_STRG := $(shell date -R)
|
||||
SED_SCRIPT := sed -i -e ' \
|
||||
SED_SCRIPT := $(SED_SCRIPT)' \
|
||||
s/<VERSION>/$(UPSTREAM_VER)-$(DEB_REV)/g; \
|
||||
s/<DATE>/$(SED_DATE_STRG)/g; \
|
||||
s/<DIST>/$(DEB_DIST)/g; \
|
||||
s/<NAME>/$(DEB_NAME)/g; \
|
||||
s/<DESCRIPTION>/$(DESCRIPTION_SHORT)\n $(subst $(NEWLINE),\n ,$(DESCRIPTION_LONG))/g; \
|
||||
'
|
||||
|
||||
# Ubuntu 14.04 (Trusty Tahr) has different names for the qml-modules
|
||||
|
@ -1,25 +1,14 @@
|
||||
Source: <NAME>
|
||||
Section: electronics
|
||||
Priority: optional
|
||||
Maintainer: James Duley <james@openpilot.org>
|
||||
Maintainer: The LibrePilot Project <<EMAIL>>
|
||||
Build-Depends: debhelper (>= 9), libudev-dev, libusb-1.0-0-dev, libsdl1.2-dev, python, gcc-arm-none-eabi (>=4.9), qt5-default, qttools5-dev-tools, libqt5svg5-dev, qtdeclarative5-dev, qml-module-qtquick-controls, libqt5serialport5-dev, qtmultimedia5-dev, qtscript5-dev, libqt5opengl5-dev
|
||||
Standards-Version: 3.9.5
|
||||
Homepage: http://www.openpilot.org
|
||||
Vcs-Git: git://git.openpilot.org/OpenPilot.git
|
||||
Vcs-Browser: http://git.openpilot.org/changelog/OpenPilot
|
||||
Homepage: <URL>
|
||||
Vcs-Git: <GIT_URL>
|
||||
Vcs-Browser: <GITWEB_URL>
|
||||
|
||||
Package: <NAME>
|
||||
Architecture: any
|
||||
Depends: ${shlibs:Depends}, ${misc:Depends}, qml-module-qtquick-controls, qml-module-qtquick-dialogs, qml-module-qtquick-xmllistmodel, qml-module-qtquick-localstorage, qml-module-qtquick-particles2, qml-module-qtquick-window2, qml-module-qtquick2
|
||||
Description: Platform for aerial robotics or other mobile vehicular platforms
|
||||
OpenPilot is a next-generation Open Source UAV autopilot created by the
|
||||
OpenPilot Community (an all volunteer non-profit community). It is a highly
|
||||
capable platform for multirotors, helicopters, fixed wing aircraft, and
|
||||
other vehicles.
|
||||
.
|
||||
It has been designed from the ground up by a community of passionate
|
||||
developers from around the globe, with its core design principles being
|
||||
quality, safety, and ease of use. Simplicity does not come with any
|
||||
compromises either: with no hard-coded settings, a complete flight plan
|
||||
scripting language and other powerful features, OpenPilot is an extremely
|
||||
capable UAV autopilot platform.
|
||||
Description: <DESCRIPTION>
|
||||
|
@ -6,13 +6,14 @@ RPM_PACKAGE_NAME := $(RPM_NAME)-$(UPSTREAM_VER)-$(RPM_REL)$(shell rpm --eval
|
||||
RPM_PACKAGE_FILE := $(PACKAGE_DIR)/RPMS/$(RPM_ARCH)/$(RPM_PACKAGE_NAME)
|
||||
RPM_PACKAGE_SRC := $(PACKAGE_DIR)/SRPMS/$(RPM_PACKAGE_NAME).src.rpm
|
||||
|
||||
SED_SCRIPT := sed -i -e ' \
|
||||
SED_SCRIPT := $(SED_SCRIPT)' \
|
||||
s/<VERSION>/$(UPSTREAM_VER)/g; \
|
||||
s/<NAME>/$(RPM_NAME)/g; \
|
||||
s/<RELEASE>/$(RPM_REL)/g; \
|
||||
s/<SOURCE0>/$(notdir $(DIST_TAR_GZ))/g; \
|
||||
s/<SOURCE1>/$(notdir $(FW_DIST_TAR_GZ))/g; \
|
||||
s/<ARCHIVE_PREFIX>/$(PACKAGE_NAME)/g; \
|
||||
s/<SUMMARY>/$(DESCRIPTION_SHORT)/g; \
|
||||
s/<DESCRIPTION>/$(subst $(NEWLINE),\n,$(DESCRIPTION_LONG))/g; \
|
||||
'
|
||||
|
||||
RPM_DIRS := $(addprefix $(PACKAGE_DIR)/,BUILD RPMS SOURCES SPECS SRPMS)
|
||||
|
@ -1,11 +1,11 @@
|
||||
Name: <NAME>
|
||||
Summary: Ground Control Station
|
||||
Summary: <SUMMARY>
|
||||
Version: <VERSION>
|
||||
Release: <RELEASE>%{?dist}
|
||||
|
||||
Group: Applications/Scientific
|
||||
License: GPLv3+
|
||||
URL: http://forum.librepilot.org/
|
||||
URL: <URL>
|
||||
|
||||
Source0: <SOURCE0>
|
||||
Source1: <SOURCE1>
|
||||
@ -41,13 +41,7 @@ Requires: qt5-qtsvg
|
||||
|
||||
|
||||
%description
|
||||
LibrePilot is a next-generation Open Source UAV autopilot created by the
|
||||
LibrePilot Community. It is a highly capable platform for
|
||||
multirotors, helicopters, fixed wing aircraft, and other vehicles.
|
||||
It has been designed from the ground up by a community of passionate developers
|
||||
from around the globe, with its core design principles being quality, safety,
|
||||
and ease of use.
|
||||
|
||||
<DESCRIPTION>
|
||||
|
||||
%prep
|
||||
%setup -q -T -a 1 -c -n <ARCHIVE_PREFIX>/build
|
||||
|
Loading…
x
Reference in New Issue
Block a user