Merge branch 'next' into OP-1338_fix_specific_icu_so_version_number
60
CREDITS.txt
@ -1,73 +1,90 @@
|
||||
Connor Abbott
|
||||
David Ankers
|
||||
Sergiy Anikeyev
|
||||
Pedro Assuncao
|
||||
David Ankers
|
||||
Fredrik Arvidsson
|
||||
Pedro Assuncao
|
||||
Werner Backes
|
||||
Jose Barros
|
||||
Andre Bernet
|
||||
Mikael Blomqvist
|
||||
Pete Boehl
|
||||
Pete Boehl
|
||||
Berkely Brown
|
||||
Joel Brueziere
|
||||
Thierry Bugeat
|
||||
Glenn Campigli
|
||||
David Carlson
|
||||
Stefan Cenkov
|
||||
Andrés Chavarría Krauser
|
||||
Cosimo Corrado
|
||||
James Cotton
|
||||
Steve Doll
|
||||
Piotr Esden-Tempski
|
||||
Richard Flay
|
||||
Peter Farnworth
|
||||
Ed Faulkner
|
||||
Andrew Finegan
|
||||
Kevin Finisterre
|
||||
Richard Flay
|
||||
Darren Furniss
|
||||
Cliff Geerdes
|
||||
Frederic Goddeeris
|
||||
Daniel Godin
|
||||
Anthony Gomez
|
||||
Anthony Gomes
|
||||
Rodney Grainger
|
||||
Bani Greyling
|
||||
Nuno Guedes
|
||||
Erik Gustavsson
|
||||
Peter Gunnarsson
|
||||
Erik Gustavsson
|
||||
Dean Hall
|
||||
Joe Hlebasko
|
||||
Andy Honecker
|
||||
Patrick Huebner
|
||||
Ryan Hunt
|
||||
Mark James
|
||||
Michael Johnston
|
||||
Ricky King
|
||||
Thorsten Klose
|
||||
Sami Korhonen
|
||||
Hallvard Kristiansen
|
||||
Alan Krum
|
||||
Edouard Lafargue
|
||||
Mike Labranche
|
||||
Edouard Lafargue
|
||||
Laurent Lalanne
|
||||
Fredrik Larsson
|
||||
Richard von Lehe
|
||||
Xavier Lecluse
|
||||
Pablo Lema
|
||||
David Llama
|
||||
Matt Lipski
|
||||
Les Newell
|
||||
Ken Northup
|
||||
David Llama
|
||||
Ben Matthews
|
||||
Greg Matthews
|
||||
Greg Matthews
|
||||
Guy McCaldin
|
||||
Gary Mortimer
|
||||
Alessio Morale
|
||||
Gary Mortimer
|
||||
Cathy Moss
|
||||
Les Newell
|
||||
Ken Northup
|
||||
Bertrand Oresve
|
||||
Angus Peart
|
||||
John Pike
|
||||
Jorge Pombo Marcos
|
||||
Dmytro Poplavskiy
|
||||
Eric Price
|
||||
Richard Querin
|
||||
Randy Ram
|
||||
Philippe Renon
|
||||
Laurent Ribon
|
||||
Jonathan Rodgers
|
||||
Mathieu Rondonneau
|
||||
Jörg-D Rothfuchs
|
||||
Julien Rouviere
|
||||
Jackson Russell
|
||||
Zik Saleeba
|
||||
Professor Dale Schinstock
|
||||
Troy Schultz
|
||||
Michael Schwingen
|
||||
Professor Kenn Sebesta
|
||||
Oleg Semyonov
|
||||
Stacey Sheldon
|
||||
Troy Schultz
|
||||
Dr. Erhard Siegl
|
||||
Dusty Anne Smith
|
||||
Mike Smith
|
||||
@ -77,10 +94,12 @@ Pete Stapley
|
||||
Vova Starikh
|
||||
Rowan Taubitz
|
||||
Andrew Thoms
|
||||
Vladimir Timofeev
|
||||
Jasper Van Loenen
|
||||
Philippe Vanhaesendonck
|
||||
Jasper van Loenen
|
||||
Vassilis Varveropoulos
|
||||
Kevin Vertucio
|
||||
Richard Von Lehe
|
||||
Alex Vrubel
|
||||
Mike Walters
|
||||
Brian Webb
|
||||
@ -89,16 +108,3 @@ Mat Wellington
|
||||
Kendal Wells
|
||||
David Willis
|
||||
Dmitriy Zaitsev
|
||||
Andre Bernet
|
||||
Anthony Gomes
|
||||
Cliff Geerdes
|
||||
Jörg-D Rothfuchs
|
||||
Jonathan Rodgers
|
||||
Laurent Lalanne
|
||||
Patrick Huebner
|
||||
Rich von Lehe
|
||||
Stefan Cenkov
|
||||
Andrés Chavarría Krauser
|
||||
Bertrand Oresve
|
||||
Cosimo Corrado
|
||||
|
||||
|
1
Makefile
@ -881,6 +881,7 @@ help:
|
||||
@$(ECHO) " qt_sdk_install - Install the QT development tools"
|
||||
@$(ECHO) " nsis_install - Install the NSIS Unicode (Windows only)"
|
||||
@$(ECHO) " sdl_install - Install the SDL library (Windows only)"
|
||||
@$(ECHO) " mesawin_install - Install the OpenGL32 DLL (Windows only)"
|
||||
@$(ECHO) " openssl_install - Install the OpenSSL libraries (Windows only)"
|
||||
@$(ECHO) " uncrustify_install - Install the Uncrustify source code beautifier"
|
||||
@$(ECHO) " doxygen_install - Install the Doxygen documentation generator"
|
||||
|
87
WHATSNEW.txt
@ -1,25 +1,15 @@
|
||||
--- RELEASE-14.06-RC2 --- Peanuts Schnapps ---
|
||||
This Release Candidate fixes the following issues:
|
||||
*[OP-1378] - Check Limits for flight modes
|
||||
*[OP-1377] - Calibration config panel has Apply button even when not in Expert mode
|
||||
*[OP-1376] - Calibration results not saved to SD
|
||||
*[OP-1375] - Update Mag Ki and Kp default settings
|
||||
*[OP-1374] - Automatically enable the right PathFollower
|
||||
*[OP-1337] - Fixes for French translation
|
||||
|
||||
The full list of features, improvements and bugfixes in this release candidate is accessible here:
|
||||
http://progress.openpilot.org/issues/?filter=11462
|
||||
|
||||
--- RELEASE-14.06-RC1 --- Peanuts Schnapps ---
|
||||
--- RELEASE-14.06 --- Peanuts Schnapps ---
|
||||
This is the Mid 2014 release.
|
||||
This version still supports the CopterControl and CC3D.
|
||||
It includes several additions and changes aimed at gps/navigation functionalities
|
||||
(that are expected to be fully available on next release).
|
||||
This version supports the CopterControl, CC3D, Atom and the Revolution Flight controllers as well as the OPLink Modems.
|
||||
|
||||
Some additions in this release:
|
||||
- Addition of GPS assisted flight modes for revo: - Return To Base, Position hold, AutoCruise and Position Vario(LOS, FPV and NSEW);
|
||||
- Stabilization refactoring that enhance rate performances;
|
||||
- Sensor calibration has been redesigned for better usability;
|
||||
This release includes many additions, improvements and fixes, it is the result of many thousands of hours of development and testing.
|
||||
|
||||
Some key additions in this release:
|
||||
- Many additions and changes aimed at gps/navigation functionality for the Revolution platform including GPS assisted flight modes: Return To Base, Position Hold, AutoCruise and Position Vario(LOS, FPV and NSEW).
|
||||
- Stabilization refactoring and enhancements for even better flight performance.
|
||||
- Completely new sensor calibration routines and greatly enhanced GUI.
|
||||
- Additional 3rd Party Hardware support, notably the MS4525DO based airspeed sensors and WS281x LED drivers.
|
||||
- Performance improvements in both embedded firmware and GCS.
|
||||
|
||||
The full list of features, improvements and bugfixes in this release is accessible here:
|
||||
|
||||
@ -29,18 +19,20 @@ http://progress.openpilot.org/issues/?filter=11460
|
||||
* [OP-943] - Start using F4's Core Coupled RAM for more than just the IRQ handler stack
|
||||
* [OP-974] - Make Bootloader Version available while flight software is running
|
||||
* [OP-975] - Reconsider the calibration process
|
||||
* [OP-1063] - Multirotor Configuration
|
||||
* [OP-1068] - Add support for magnetometer calibration matrix in place of scaling parameters
|
||||
* [OP-1149] - Handle thermal bias calculation/calibration to gyro and accel
|
||||
* [OP-1150] - Create UI to allow users to perform board thermal calibration
|
||||
* [OP-1159] - Remove "Rev" checkboxes on input tab for channels on which it doesn't have an effect
|
||||
* [OP-1149] - handle thermal bias calculation/calibration to gyro and accel
|
||||
* [OP-1150] - Create UI to allow users to perform board thermal calibration
|
||||
* [OP-1159] - Remove "Rev" checkboxes on input tab for channels on which it doesn't have an affect
|
||||
* [OP-1161] - Add Alarm for Magnetometer if disturbed or uncalibrated
|
||||
* [OP-1174] - Beautify Uploader gadget popups
|
||||
* [OP-1194] - Scope gadget - plot and legend visibility state should be persisted between runs
|
||||
* [OP-1198] - Allow GCS gadgets to save/restore individual state
|
||||
* [OP-1216] - Refactor Flight Control Modules
|
||||
* [OP-1230] - Automatically load the correct firmware file when GCS is running in a development environment
|
||||
* [OP-1230] - automatically load the correct firmware file when GCS is running in a development environment
|
||||
* [OP-1233] - Add make options to skip qmake and build a specific GCS directory
|
||||
* [OP-1245] - Add GUI to control if, what, when and how to do flight side logging.
|
||||
* [OP-1247] - Remove Noise calibration from Revo calibration config widget
|
||||
* [OP-1250] - Add GPS Protocol configuration in the Hardware configuration panel
|
||||
* [OP-1258] - Update GCC ARM Embedded to 4.8-2014-q1
|
||||
* [OP-1259] - Cruise Control tweaks
|
||||
@ -54,23 +46,29 @@ http://progress.openpilot.org/issues/?filter=11460
|
||||
* [OP-1307] - Create a bare DiscoveryF4 target for debugging and development purposes
|
||||
* [OP-1308] - Set the same logic to CRITICAL Alarm and same logic to ERROR Alarm
|
||||
* [OP-1312] - Implement a PIOS WS281x driver
|
||||
* [OP-1319] - Fix minor spelling mistakes in fw code
|
||||
* [OP-1335] - ConfigTaskWidget - Add support to bind GComboBox to integer property
|
||||
* [OP-1339] - System Health panel improvement
|
||||
* [OP-1350] - TakeOff location handling to be used with RTH
|
||||
* [OP-1378] - Check Limits for flight modes
|
||||
* [OP-1342] - PFD widget emits lots of warning
|
||||
* [OP-1350] - TakeOff location handling to be used with RTB
|
||||
* [OP-1358] - Split board rotation into user set configuration and calibrated offset
|
||||
* [OP-1365] - Add instrumentation functions for flight code
|
||||
|
||||
* [OP-1374] - Automatically enable the right PathFollower
|
||||
* [OP-1390] - OpenGL support for older Graphics Cards
|
||||
* [OP-1413] - Disable Land flight mode
|
||||
** Bug
|
||||
* [OP-792] - 'Autotune' still showing up in flight mode settings in GCS
|
||||
* [OP-1026] - Provide some standard method of calibrating CPU speed and load measurement for boards
|
||||
* [OP-1033] - Data transfer errors on USB HID on F1 devices
|
||||
* [OP-1043] - Ground OPLinkMini refuses to connect to one Revo unless first connected to another Revo
|
||||
* [OP-1056] - GPS does not set home location when erased after lock has been established
|
||||
* [OP-1080] - Unreliable detection of board through OPLink
|
||||
* [OP-1100] - GCS plist for mac shows wrong associated filetypes, leftover from qtcreator
|
||||
* [OP-1100] - gcs plist for mac shows wrong associated filetypes, leftover from qtcreator
|
||||
* [OP-1131] - Firmware mismatch check is not done if Uploader gadget is not active
|
||||
* [OP-1172] - Some fonts are not defined in config files
|
||||
* [OP-1196] - Board rotation in GCS not shown correctly upon connection but correctly saved in memory
|
||||
* [OP-1212] - Fix Priority queue handling in telemetry
|
||||
* [OP-1212] - Fix Priority queue handling in telemetry
|
||||
* [OP-1226] - screen problems
|
||||
* [OP-1227] - High CPU load in ratitude mode on CopterControl
|
||||
* [OP-1232] - Setting high telemetry rates for periodic uavobject triggers eventsystem warning.
|
||||
* [OP-1235] - Some fixes for altitude estimation
|
||||
@ -84,9 +82,8 @@ http://progress.openpilot.org/issues/?filter=11460
|
||||
* [OP-1283] - SystemHealthGadgetWidget::updateAlarms misinterprets coordinates in SVG file
|
||||
* [OP-1284] - RTB flies into ground if base is high
|
||||
* [OP-1285] - Erase Settings ToolTip is wrong
|
||||
* [OP-1286] - GCS Map "Go To Place" doesn't work
|
||||
* [OP-1288] - GPS PositionHold immediately flies several meters away if Home is not close
|
||||
* [OP-1291] - Fix matlab import after UAVTalk changes
|
||||
* [OP-1291] - fix matlab import after UAVTalk changes
|
||||
* [OP-1294] - Fix stack sizes for CopterControl
|
||||
* [OP-1295] - Autoupdate not working
|
||||
* [OP-1296] - Altitude Hold causes copter to ascent at full throttle when far from home location
|
||||
@ -97,25 +94,40 @@ http://progress.openpilot.org/issues/?filter=11460
|
||||
* [OP-1314] - Fix Airspeed stack size
|
||||
* [OP-1315] - Unable to arm UAV when AirspeedSensorType is set to GroundspeedBaseWindEstimation
|
||||
* [OP-1323] - GCS font fixes
|
||||
* [OP-1325] - Fix event system warnings to be errors
|
||||
* [OP-1326] - Set AIrspeedSensor default back to "None"
|
||||
* [OP-1325] - fix event system warnings to be errors
|
||||
* [OP-1326] - set AIrspeedSensor default back to "None"
|
||||
* [OP-1327] - SystemAlarms must be non-acked
|
||||
* [OP-1329] - Various fixes to airspeed module
|
||||
* [OP-1330] - Cannot set homelocation.set=false when gps reception is optimal
|
||||
* [OP-1331] - Input and Output Channel Configuration alignments issues
|
||||
* [OP-1332] - PiOS alarms does not reset alarm state on timer overflow
|
||||
* [OP-1333] - Output Channel Configuration alignments issues
|
||||
* [OP-1333] - Output Channel Configuration alignments issues
|
||||
* [OP-1340] - Auto-update greyed out - not available
|
||||
* [OP-1343] - GCS Configuration - Input Channel ResponseTime not saved
|
||||
* [OP-1346] - Input Channel Response Time mismatch between GCS config screen and UAVObject
|
||||
* [OP-1347] - Flight logs settings - UI / segfault
|
||||
* [OP-1348] - Config Gadget flashes next panel when connecting/disconnecting board
|
||||
* [OP-1351] - GCS Calibration UI polishing
|
||||
* [OP-1352] - Headwind-improvements for FixedWingPathFollower
|
||||
* [OP-1353] - HITL Flightgear fails to set Position and velocity correctly
|
||||
* [OP-1354] - Current and voltage not shown in PFD
|
||||
* [OP-1355] - Magnetometer calibration and board rotation don't play along
|
||||
* [OP-1363] - Sanitychecks MUST check if magnetometers and GPS are enabled for any pathfollower modes (outdoor mode selected)
|
||||
* [OP-1371] - Sanitychecks overzealous: hitl/sitl broken
|
||||
* [OP-1355] - magnetometer calibration and board rotation don't play along
|
||||
* [OP-1363] - sanitychecks MUST check if magnetometers and GPS are enabled for any pathfollower modes (outdoor mode selected)
|
||||
* [OP-1371] - sanitychecks overzealous: hitl/sitl broken
|
||||
* [OP-1375] - Update Mag Ki and Kp default settings
|
||||
* [OP-1376] - Calibration results not saved to SD
|
||||
* [OP-1377] - Calibration config panel has Apply button even when not in Expert mode
|
||||
* [OP-1383] - GCS crashes when connected via serial port
|
||||
* [OP-1384] - Revo Board Rotation data is cleared to zero by other calibration steps
|
||||
* [OP-1389] - GCS Crashes exiting Flight side log window
|
||||
* [OP-1391] - System allows arming if current flight mode uses Thrust Control = AH or AV
|
||||
* [OP-1393] - SerialPlugin destructor generates valgrind error
|
||||
* [OP-1394] - Flight display widget - telemetry data does not zero on disconnection
|
||||
* [OP-1408] - Board rotation is not always saved during Revo calibration
|
||||
* [OP-1412] - INS13Outdoor Yaw Gyro drift
|
||||
* [OP-1415] - Repeated names in CREDITS.txt
|
||||
* [OP-1419] - GCS does not set Z magnetometer scale correctly on mag calibration
|
||||
* [OP-1421] - Cruise Control xml defaultvalue incorrect
|
||||
|
||||
** Tasks
|
||||
* [OP-1274] - Update FreeRTOS to 8.0
|
||||
@ -124,7 +136,6 @@ http://progress.openpilot.org/issues/?filter=11460
|
||||
* [OP-1263] - Move SDL out of Qt install
|
||||
* [OP-1309] - Stabilization refactoring
|
||||
|
||||
|
||||
--- RELEASE-14.01 --- Cruising Ratt ---
|
||||
This is the first 2014 software release.
|
||||
This version still supports the CopterControl and CC3D.
|
||||
|
@ -180,7 +180,7 @@ void RPY2Quaternion(const float rpy[3], float q[4])
|
||||
// ** Find Rbe, that rotates a vector from earth fixed to body frame, from quaternion **
|
||||
void Quaternion2R(float q[4], float Rbe[3][3])
|
||||
{
|
||||
float q0s = q[0] * q[0], q1s = q[1] * q[1], q2s = q[2] * q[2], q3s = q[3] * q[3];
|
||||
const float q0s = q[0] * q[0], q1s = q[1] * q[1], q2s = q[2] * q[2], q3s = q[3] * q[3];
|
||||
|
||||
Rbe[0][0] = q0s + q1s - q2s - q3s;
|
||||
Rbe[0][1] = 2 * (q[1] * q[2] + q[0] * q[3]);
|
||||
@ -193,6 +193,61 @@ void Quaternion2R(float q[4], float Rbe[3][3])
|
||||
Rbe[2][2] = q0s - q1s - q2s + q3s;
|
||||
}
|
||||
|
||||
|
||||
// ** Find first row of Rbe, that rotates a vector from earth fixed to body frame, from quaternion **
|
||||
// ** This vector corresponds to the fuselage/roll vector xB **
|
||||
void QuaternionC2xB(const float q0, const float q1, const float q2, const float q3, float x[3])
|
||||
{
|
||||
const float q0s = q0 * q0, q1s = q1 * q1, q2s = q2 * q2, q3s = q3 * q3;
|
||||
|
||||
x[0] = q0s + q1s - q2s - q3s;
|
||||
x[1] = 2 * (q1 * q2 + q0 * q3);
|
||||
x[2] = 2 * (q1 * q3 - q0 * q2);
|
||||
}
|
||||
|
||||
|
||||
void Quaternion2xB(const float q[4], float x[3])
|
||||
{
|
||||
QuaternionC2xB(q[0], q[1], q[2], q[3], x);
|
||||
}
|
||||
|
||||
|
||||
// ** Find second row of Rbe, that rotates a vector from earth fixed to body frame, from quaternion **
|
||||
// ** This vector corresponds to the spanwise/pitch vector yB **
|
||||
void QuaternionC2yB(const float q0, const float q1, const float q2, const float q3, float y[3])
|
||||
{
|
||||
const float q0s = q0 * q0, q1s = q1 * q1, q2s = q2 * q2, q3s = q3 * q3;
|
||||
|
||||
y[0] = 2 * (q1 * q2 - q0 * q3);
|
||||
y[1] = q0s - q1s + q2s - q3s;
|
||||
y[2] = 2 * (q2 * q3 + q0 * q1);
|
||||
}
|
||||
|
||||
|
||||
void Quaternion2yB(const float q[4], float y[3])
|
||||
{
|
||||
QuaternionC2yB(q[0], q[1], q[2], q[3], y);
|
||||
}
|
||||
|
||||
|
||||
// ** Find third row of Rbe, that rotates a vector from earth fixed to body frame, from quaternion **
|
||||
// ** This vector corresponds to the vertical/yaw vector zB **
|
||||
void QuaternionC2zB(const float q0, const float q1, const float q2, const float q3, float z[3])
|
||||
{
|
||||
const float q0s = q0 * q0, q1s = q1 * q1, q2s = q2 * q2, q3s = q3 * q3;
|
||||
|
||||
z[0] = 2 * (q1 * q3 + q0 * q2);
|
||||
z[1] = 2 * (q2 * q3 - q0 * q1);
|
||||
z[2] = q0s - q1s - q2s + q3s;
|
||||
}
|
||||
|
||||
|
||||
void Quaternion2zB(const float q[4], float z[3])
|
||||
{
|
||||
QuaternionC2zB(q[0], q[1], q[2], q[3], z);
|
||||
}
|
||||
|
||||
|
||||
// ****** Express LLA in a local NED Base Frame ********
|
||||
void LLA2Base(int32_t LLAi[3], double BaseECEF[3], float Rne[3][3], float NED[3])
|
||||
{
|
||||
|
@ -50,6 +50,21 @@ void RPY2Quaternion(const float rpy[3], float q[4]);
|
||||
// ** Find Rbe, that rotates a vector from earth fixed to body frame, from quaternion **
|
||||
void Quaternion2R(float q[4], float Rbe[3][3]);
|
||||
|
||||
// ** Find first row of Rbe, that rotates a vector from earth fixed to body frame, from quaternion **
|
||||
// ** This vector corresponds to the fuselage/roll vector xB **
|
||||
void QuaternionC2xB(const float q0, const float q1, const float q2, const float q3, float x[3]);
|
||||
void Quaternion2xB(const float q[4], float x[3]);
|
||||
|
||||
// ** Find second row of Rbe, that rotates a vector from earth fixed to body frame, from quaternion **
|
||||
// ** This vector corresponds to the spanwise/pitch vector yB **
|
||||
void QuaternionC2yB(const float q0, const float q1, const float q2, const float q3, float y[3]);
|
||||
void Quaternion2yB(const float q[4], float y[3]);
|
||||
|
||||
// ** Find third row of Rbe, that rotates a vector from earth fixed to body frame, from quaternion **
|
||||
// ** This vector corresponds to the vertical/yaw vector zB **
|
||||
void QuaternionC2zB(const float q0, const float q1, const float q2, const float q3, float z[3]);
|
||||
void Quaternion2zB(const float q[4], float z[3]);
|
||||
|
||||
// ****** Express LLA in a local NED Base Frame ********
|
||||
void LLA2Base(int32_t LLAi[3], double BaseECEF[3], float Rne[3][3], float NED[3]);
|
||||
|
||||
|
100
flight/libraries/math/butterworth.c
Normal file
@ -0,0 +1,100 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilot Math Utilities
|
||||
* @{
|
||||
* @addtogroup Butterworth low pass filter
|
||||
* @{
|
||||
*
|
||||
* @file butterworth.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief Direct form two of a second order Butterworth low pass filter
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "math.h"
|
||||
#include "butterworth.h"
|
||||
|
||||
/**
|
||||
* Initialization function for coefficients of a second order Butterworth biquadratic filter in direct from 2.
|
||||
* Note that b1 = 2 * b0 and b2 = b0 is use here and in the sequel.
|
||||
* @param[in] ff Cut-off frequency ratio
|
||||
* @param[out] filterPtr Pointer to filter coefficients
|
||||
* @returns Nothing
|
||||
*/
|
||||
void InitButterWorthDF2Filter(const float ff, struct ButterWorthDF2Filter *filterPtr)
|
||||
{
|
||||
const float ita = 1.0f / tanf(M_PI_F * ff);
|
||||
const float b0 = 1.0f / (1.0f + M_SQRT2_F * ita + ita * ita);
|
||||
const float a1 = 2.0f * b0 * (ita * ita - 1.0f);
|
||||
const float a2 = -b0 * (1.0f - M_SQRT2_F * ita + ita * ita);
|
||||
|
||||
filterPtr->b0 = b0;
|
||||
filterPtr->a1 = a1;
|
||||
filterPtr->a2 = a2;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Initialization function for intermediate values of a second order Butterworth biquadratic filter in direct from 2.
|
||||
* Obtained by solving a linear equation system.
|
||||
* @param[in] x0 Prescribed value
|
||||
* @param[in] filterPtr Pointer to filter coefficients
|
||||
* @param[out] wn1Ptr Pointer to first intermediate value
|
||||
* @param[out] wn2Ptr Pointer to second intermediate value
|
||||
* @returns Nothing
|
||||
*/
|
||||
void InitButterWorthDF2Values(const float x0, const struct ButterWorthDF2Filter *filterPtr, float *wn1Ptr, float *wn2Ptr)
|
||||
{
|
||||
const float b0 = filterPtr->b0;
|
||||
const float a1 = filterPtr->a1;
|
||||
const float a2 = filterPtr->a2;
|
||||
|
||||
const float a11 = 2.0f + a1;
|
||||
const float a12 = 1.0f + a2;
|
||||
const float a21 = 2.0f + a1 * a1 + a2;
|
||||
const float a22 = 1.0f + a1 * a2;
|
||||
const float det = a11 * a22 - a12 * a21;
|
||||
const float rhs1 = x0 / b0 - x0;
|
||||
const float rhs2 = x0 / b0 - x0 + a1 * x0;
|
||||
|
||||
*wn1Ptr = (a22 * rhs1 - a12 * rhs2) / det;
|
||||
*wn2Ptr = (-a21 * rhs1 + a11 * rhs2) / det;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Second order Butterworth biquadratic filter in direct from 2, such that only two values wn1=w[n-1] and wn2=w[n-2] need to be stored.
|
||||
* Function takes care of updating the values wn1 and wn2.
|
||||
* @param[in] xn New raw value
|
||||
* @param[in] filterPtr Pointer to filter coefficients
|
||||
* @param[out] wn1Ptr Pointer to first intermediate value
|
||||
* @param[out] wn2Ptr Pointer to second intermediate value
|
||||
* @returns Filtered value
|
||||
*/
|
||||
float FilterButterWorthDF2(const float xn, const struct ButterWorthDF2Filter *filterPtr, float *wn1Ptr, float *wn2Ptr)
|
||||
{
|
||||
const float wn = xn + filterPtr->a1 * (*wn1Ptr) + filterPtr->a2 * (*wn2Ptr);
|
||||
const float val = filterPtr->b0 * (wn + 2.0f * (*wn1Ptr) + (*wn2Ptr));
|
||||
|
||||
*wn2Ptr = *wn1Ptr;
|
||||
*wn1Ptr = wn;
|
||||
return val;
|
||||
}
|
@ -1,13 +1,13 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @addtogroup OpenPilot Math Utilities
|
||||
* @{
|
||||
* @addtogroup Attitude Attitude Module
|
||||
* @addtogroup Butterworth low pass filter
|
||||
* @{
|
||||
*
|
||||
* @file attitude.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
|
||||
* @brief Acquires sensor data and fuses it into attitude estimate for CC
|
||||
* @file butterworth.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief Direct form two of a second order Butterworth low pass filter
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
@ -27,11 +27,20 @@
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef ATTITUDE_H
|
||||
#define ATTITUDE_H
|
||||
|
||||
#include "openpilot.h"
|
||||
#ifndef BUTTERWORTH_H
|
||||
#define BUTTERWORTH_H
|
||||
|
||||
int32_t AttitudeInitialize(void);
|
||||
// Coefficients of second order Butterworth biquadratic filter in direct from 2
|
||||
struct ButterWorthDF2Filter {
|
||||
float b0;
|
||||
float a1;
|
||||
float a2;
|
||||
};
|
||||
|
||||
#endif // ATTITUDE_H
|
||||
// Function declarations
|
||||
void InitButterWorthDF2Filter(const float ff, struct ButterWorthDF2Filter *filterPtr);
|
||||
void InitButterWorthDF2Values(const float x0, const struct ButterWorthDF2Filter *filterPtr, float *wn1Ptr, float *wn2Ptr);
|
||||
float FilterButterWorthDF2(const float xn, const struct ButterWorthDF2Filter *filterPtr, float *wn1Ptr, float *wn2Ptr);
|
||||
|
||||
#endif
|
@ -265,7 +265,9 @@ FrameType_t GetCurrentFrameType()
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOX:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAH:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX:
|
||||
|
@ -44,7 +44,7 @@
|
||||
#include "baro_airspeed_ms4525do.h"
|
||||
#include "baro_airspeed_etasv3.h"
|
||||
#include "baro_airspeed_mpxv.h"
|
||||
#include "gps_airspeed.h"
|
||||
#include "imu_airspeed.h"
|
||||
#include "airspeedalarm.h"
|
||||
#include "taskinfo.h"
|
||||
|
||||
@ -99,7 +99,7 @@ int32_t AirspeedInitialize()
|
||||
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
HwSettingsOptionalModulesArrayGet(optionalModules);
|
||||
|
||||
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_AIRSPEED] == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
@ -136,7 +136,7 @@ MODULE_INITCALL(AirspeedInitialize, AirspeedStart);
|
||||
static void airspeedTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
AirspeedSettingsUpdatedCb(AirspeedSettingsHandle());
|
||||
bool gpsAirspeedInitialized = false;
|
||||
bool imuAirspeedInitialized = false;
|
||||
AirspeedSensorData airspeedData;
|
||||
AirspeedSensorGet(&airspeedData);
|
||||
|
||||
@ -164,9 +164,9 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
|
||||
AirspeedSensorSet(&airspeedData);
|
||||
break;
|
||||
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_GROUNDSPEEDBASEDWINDESTIMATION:
|
||||
if (!gpsAirspeedInitialized) {
|
||||
gpsAirspeedInitialized = true;
|
||||
gps_airspeedInitialize();
|
||||
if (!imuAirspeedInitialized) {
|
||||
imuAirspeedInitialized = true;
|
||||
imu_airspeedInitialize(&airspeedSettings);
|
||||
}
|
||||
break;
|
||||
}
|
||||
@ -192,7 +192,7 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
|
||||
break;
|
||||
#endif
|
||||
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_GROUNDSPEEDBASEDWINDESTIMATION:
|
||||
gps_airspeedGet(&airspeedData, &airspeedSettings);
|
||||
imu_airspeedGet(&airspeedData, &airspeedSettings);
|
||||
break;
|
||||
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_NONE:
|
||||
// no need to check so often until a sensor is enabled
|
||||
|
@ -1,170 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup AirspeedModule Airspeed Module
|
||||
* @brief Use GPS data to estimate airspeed
|
||||
* @{
|
||||
*
|
||||
* @file gps_airspeed.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief Airspeed module, handles temperature and pressure readings from BMP085
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "velocitystate.h"
|
||||
#include "attitudestate.h"
|
||||
#include "airspeedsensor.h"
|
||||
#include "airspeedsettings.h"
|
||||
#include "gps_airspeed.h"
|
||||
#include "CoordinateConversions.h"
|
||||
#include "airspeedalarm.h"
|
||||
#include <pios_math.h>
|
||||
|
||||
|
||||
// Private constants
|
||||
#define GPS_AIRSPEED_BIAS_KP 0.1f // Needs to be settable in a UAVO
|
||||
#define GPS_AIRSPEED_BIAS_KI 0.1f // Needs to be settable in a UAVO
|
||||
#define SAMPLING_DELAY_MS_GPS 100 // Needs to be settable in a UAVO
|
||||
#define GPS_AIRSPEED_TIME_CONSTANT_MS 500.0f // Needs to be settable in a UAVO
|
||||
|
||||
// Private types
|
||||
struct GPSGlobals {
|
||||
float RbeCol1_old[3];
|
||||
float gpsVelOld_N;
|
||||
float gpsVelOld_E;
|
||||
float gpsVelOld_D;
|
||||
float oldAirspeed;
|
||||
};
|
||||
|
||||
// Private variables
|
||||
static struct GPSGlobals *gps;
|
||||
|
||||
// Private functions
|
||||
|
||||
/*
|
||||
* Initialize function loads first data sets, and allocates memory for structure.
|
||||
*/
|
||||
void gps_airspeedInitialize()
|
||||
{
|
||||
// This method saves memory in case we don't use the GPS module.
|
||||
gps = (struct GPSGlobals *)pios_malloc(sizeof(struct GPSGlobals));
|
||||
|
||||
// GPS airspeed calculation variables
|
||||
VelocityStateInitialize();
|
||||
VelocityStateData gpsVelData;
|
||||
VelocityStateGet(&gpsVelData);
|
||||
|
||||
gps->gpsVelOld_N = gpsVelData.North;
|
||||
gps->gpsVelOld_E = gpsVelData.East;
|
||||
gps->gpsVelOld_D = gpsVelData.Down;
|
||||
|
||||
gps->oldAirspeed = 0.0f;
|
||||
|
||||
AttitudeStateData attData;
|
||||
AttitudeStateGet(&attData);
|
||||
|
||||
float Rbe[3][3];
|
||||
float q[4] = { attData.q1, attData.q2, attData.q3, attData.q4 };
|
||||
|
||||
// Calculate rotation matrix
|
||||
Quaternion2R(q, Rbe);
|
||||
|
||||
gps->RbeCol1_old[0] = Rbe[0][0];
|
||||
gps->RbeCol1_old[1] = Rbe[0][1];
|
||||
gps->RbeCol1_old[2] = Rbe[0][2];
|
||||
}
|
||||
|
||||
/*
|
||||
* Calculate airspeed as a function of GPS groundspeed and vehicle attitude.
|
||||
* From "IMU Wind Estimation (Theory)", by William Premerlani.
|
||||
* The idea is that V_gps=V_air+V_wind. If we assume wind constant, =>
|
||||
* V_gps_2-V_gps_1 = (V_air_2+V_wind_2) -(V_air_1+V_wind_1) = V_air_2 - V_air_1.
|
||||
* If we assume airspeed constant, => V_gps_2-V_gps_1 = |V|*(f_2 - f1),
|
||||
* where "f" is the fuselage vector in earth coordinates.
|
||||
* We then solve for |V| = |V_gps_2-V_gps_1|/ |f_2 - f1|.
|
||||
*/
|
||||
void gps_airspeedGet(AirspeedSensorData *airspeedData, AirspeedSettingsData *airspeedSettings)
|
||||
{
|
||||
float Rbe[3][3];
|
||||
|
||||
{ // Scoping to save memory. We really just need Rbe.
|
||||
AttitudeStateData attData;
|
||||
AttitudeStateGet(&attData);
|
||||
|
||||
float q[4] = { attData.q1, attData.q2, attData.q3, attData.q4 };
|
||||
|
||||
// Calculate rotation matrix
|
||||
Quaternion2R(q, Rbe);
|
||||
}
|
||||
|
||||
// Calculate the cos(angle) between the two fuselage basis vectors
|
||||
float cosDiff = (Rbe[0][0] * gps->RbeCol1_old[0]) + (Rbe[0][1] * gps->RbeCol1_old[1]) + (Rbe[0][2] * gps->RbeCol1_old[2]);
|
||||
|
||||
// If there's more than a 5 degree difference between two fuselage measurements, then we have sufficient delta to continue.
|
||||
if (fabsf(cosDiff) < cosf(DEG2RAD(5.0f))) {
|
||||
VelocityStateData gpsVelData;
|
||||
VelocityStateGet(&gpsVelData);
|
||||
|
||||
if (gpsVelData.North * gpsVelData.North + gpsVelData.East * gpsVelData.East + gpsVelData.Down * gpsVelData.Down < 1.0f) {
|
||||
airspeedData->CalibratedAirspeed = 0;
|
||||
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_ERROR);
|
||||
return; // do not calculate if gps velocity is insufficient...
|
||||
}
|
||||
|
||||
// Calculate the norm^2 of the difference between the two GPS vectors
|
||||
float normDiffGPS2 = powf(gpsVelData.North - gps->gpsVelOld_N, 2.0f) + powf(gpsVelData.East - gps->gpsVelOld_E, 2.0f) + powf(gpsVelData.Down - gps->gpsVelOld_D, 2.0f);
|
||||
|
||||
// Calculate the norm^2 of the difference between the two fuselage vectors
|
||||
float normDiffAttitude2 = powf(Rbe[0][0] - gps->RbeCol1_old[0], 2.0f) + powf(Rbe[0][1] - gps->RbeCol1_old[1], 2.0f) + powf(Rbe[0][2] - gps->RbeCol1_old[2], 2.0f);
|
||||
|
||||
// Airspeed magnitude is the ratio between the two difference norms
|
||||
float airspeed = sqrtf(normDiffGPS2 / normDiffAttitude2);
|
||||
if (!IS_REAL(airspeedData->CalibratedAirspeed)) {
|
||||
airspeedData->CalibratedAirspeed = 0;
|
||||
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_ERROR);
|
||||
} else {
|
||||
// need a low pass filter to filter out spikes in non coordinated maneuvers
|
||||
airspeedData->CalibratedAirspeed = (1.0f - airspeedSettings->GroundSpeedBasedEstimationLowPassAlpha) * gps->oldAirspeed + airspeedSettings->GroundSpeedBasedEstimationLowPassAlpha * airspeed;
|
||||
gps->oldAirspeed = airspeedData->CalibratedAirspeed;
|
||||
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_OK);
|
||||
}
|
||||
|
||||
// Save old variables for next pass
|
||||
gps->gpsVelOld_N = gpsVelData.North;
|
||||
gps->gpsVelOld_E = gpsVelData.East;
|
||||
gps->gpsVelOld_D = gpsVelData.Down;
|
||||
|
||||
gps->RbeCol1_old[0] = Rbe[0][0];
|
||||
gps->RbeCol1_old[1] = Rbe[0][1];
|
||||
gps->RbeCol1_old[2] = Rbe[0][2];
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
306
flight/modules/Airspeed/imu_airspeed.c
Normal file
@ -0,0 +1,306 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup AirspeedModule Airspeed Module
|
||||
* @brief Use attitude and velocity data to estimate airspeed
|
||||
* @{
|
||||
*
|
||||
* @file imu_airspeed.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief IMU based airspeed calculation
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "velocitystate.h"
|
||||
#include "attitudestate.h"
|
||||
#include "airspeedsensor.h"
|
||||
#include "airspeedsettings.h"
|
||||
#include "imu_airspeed.h"
|
||||
#include "CoordinateConversions.h"
|
||||
#include "butterworth.h"
|
||||
#include <pios_math.h>
|
||||
|
||||
|
||||
// Private constants
|
||||
#define EPS 1e-6f
|
||||
#define EPS_REORIENTATION 1e-10f
|
||||
#define EPS_VELOCITY 1.f
|
||||
|
||||
// Private types
|
||||
// structure with smoothed fuselage orientation, ground speed, wind vector and their changes in time
|
||||
struct IMUGlobals {
|
||||
// Butterworth filters
|
||||
struct ButterWorthDF2Filter filter;
|
||||
struct ButterWorthDF2Filter prefilter;
|
||||
float ff, ffV;
|
||||
|
||||
// storage variables for Butterworth filter
|
||||
float pn1, pn2;
|
||||
float yn1, yn2;
|
||||
float v1n1, v1n2;
|
||||
float v2n1, v2n2;
|
||||
float v3n1, v3n2;
|
||||
float Vw1n1, Vw1n2;
|
||||
float Vw2n1, Vw2n2;
|
||||
float Vw3n1, Vw3n2;
|
||||
float Vw1, Vw2, Vw3;
|
||||
|
||||
// storage variables for derivative calculation
|
||||
float pOld, yOld;
|
||||
float v1Old, v2Old, v3Old;
|
||||
};
|
||||
|
||||
|
||||
// Private variables
|
||||
static struct IMUGlobals *imu;
|
||||
|
||||
// Private functions
|
||||
// a simple square inline function based on multiplication faster than powf(x,2.0f)
|
||||
static inline float Sq(float x)
|
||||
{
|
||||
return x * x;
|
||||
}
|
||||
|
||||
// ****** find pitch, yaw from quaternion ********
|
||||
static void Quaternion2PY(const float q0, const float q1, const float q2, const float q3, float *pPtr, float *yPtr, bool principalArg)
|
||||
{
|
||||
float R13, R11, R12;
|
||||
const float q0s = q0 * q0;
|
||||
const float q1s = q1 * q1;
|
||||
const float q2s = q2 * q2;
|
||||
const float q3s = q3 * q3;
|
||||
|
||||
R13 = 2.0f * (q1 * q3 - q0 * q2);
|
||||
R11 = q0s + q1s - q2s - q3s;
|
||||
R12 = 2.0f * (q1 * q2 + q0 * q3);
|
||||
|
||||
*pPtr = asinf(-R13); // pitch always between -pi/2 to pi/2
|
||||
|
||||
const float y_ = atan2f(R12, R11);
|
||||
// use old yaw contained in y to add multiples of 2pi to have a continuous yaw if user does not want the principal argument
|
||||
// else simply copy atan2 result into result
|
||||
if (principalArg) {
|
||||
*yPtr = y_;
|
||||
} else {
|
||||
// calculate needed mutliples of 2pi to avoid jumps
|
||||
// number of cycles accumulated in old yaw
|
||||
const int32_t cycles = (int32_t)(*yPtr / M_2PI_F);
|
||||
// look for a jump by substracting the modulus, i.e. there is maximally one jump.
|
||||
// take slightly less than 2pi, because the jump will always be lower than 2pi
|
||||
const int32_t mod = (int32_t)((y_ - (*yPtr - cycles * M_2PI_F)) / (M_2PI_F * 0.8f));
|
||||
*yPtr = y_ + M_2PI_F * (cycles - mod);
|
||||
}
|
||||
}
|
||||
|
||||
static void PY2xB(const float p, const float y, float x[3])
|
||||
{
|
||||
const float cosp = cosf(p);
|
||||
|
||||
x[0] = cosp * cosf(y);
|
||||
x[1] = cosp * sinf(y);
|
||||
x[2] = -sinf(p);
|
||||
}
|
||||
|
||||
|
||||
static void PY2DeltaxB(const float p, const float y, const float xB[3], float x[3])
|
||||
{
|
||||
const float cosp = cosf(p);
|
||||
|
||||
x[0] = xB[0] - cosp * cosf(y);
|
||||
x[1] = xB[1] - cosp * sinf(y);
|
||||
x[2] = xB[2] - -sinf(p);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Initialize function loads first data sets, and allocates memory for structure.
|
||||
*/
|
||||
void imu_airspeedInitialize(const AirspeedSettingsData *airspeedSettings)
|
||||
{
|
||||
// pre-filter frequency rate
|
||||
const float ff = (float)(airspeedSettings->SamplePeriod) / 1000.0f / airspeedSettings->IMUBasedEstimationLowPassPeriod1;
|
||||
// filter frequency rate
|
||||
const float ffV = (float)(airspeedSettings->SamplePeriod) / 1000.0f / airspeedSettings->IMUBasedEstimationLowPassPeriod2;
|
||||
|
||||
// This method saves memory in case we don't use the module.
|
||||
imu = (struct IMUGlobals *)pios_malloc(sizeof(struct IMUGlobals));
|
||||
|
||||
// airspeed calculation variables
|
||||
VelocityStateInitialize();
|
||||
VelocityStateData velData;
|
||||
VelocityStateGet(&velData);
|
||||
|
||||
AttitudeStateData attData;
|
||||
AttitudeStateGet(&attData);
|
||||
|
||||
// initialize filters for given ff and ffV
|
||||
InitButterWorthDF2Filter(ffV, &(imu->filter));
|
||||
InitButterWorthDF2Filter(ff, &(imu->prefilter));
|
||||
imu->ffV = ffV;
|
||||
imu->ff = ff;
|
||||
|
||||
// get pitch and yaw from quarternion; principal argument for yaw
|
||||
Quaternion2PY(attData.q1, attData.q2, attData.q3, attData.q4, &(imu->pOld), &(imu->yOld), true);
|
||||
InitButterWorthDF2Values(imu->pOld, &(imu->prefilter), &(imu->pn1), &(imu->pn2));
|
||||
InitButterWorthDF2Values(imu->yOld, &(imu->prefilter), &(imu->yn1), &(imu->yn2));
|
||||
|
||||
// use current NED speed as vOld vector and as initial value for filter
|
||||
imu->v1Old = velData.North;
|
||||
imu->v2Old = velData.East;
|
||||
imu->v3Old = velData.Down;
|
||||
InitButterWorthDF2Values(imu->v1Old, &(imu->prefilter), &(imu->v1n1), &(imu->v1n2));
|
||||
InitButterWorthDF2Values(imu->v2Old, &(imu->prefilter), &(imu->v2n1), &(imu->v2n2));
|
||||
InitButterWorthDF2Values(imu->v3Old, &(imu->prefilter), &(imu->v3n1), &(imu->v3n2));
|
||||
|
||||
// initial guess for windspeed is zero
|
||||
imu->Vw3 = imu->Vw2 = imu->Vw1 = 0.0f;
|
||||
InitButterWorthDF2Values(0.0f, &(imu->filter), &(imu->Vw1n1), &(imu->Vw1n2));
|
||||
imu->Vw3n1 = imu->Vw2n1 = imu->Vw1n1;
|
||||
imu->Vw3n2 = imu->Vw2n2 = imu->Vw1n2;
|
||||
}
|
||||
|
||||
/*
|
||||
* Calculate airspeed as a function of groundspeed and vehicle attitude.
|
||||
* Adapted from "IMU Wind Estimation (Theory)", by William Premerlani.
|
||||
* The idea is that V_gps=V_air+V_wind. If we assume wind constant, =>
|
||||
* V_gps_2-V_gps_1 = (V_air_2+V_wind_2) -(V_air_1+V_wind_1) = V_air_2 - V_air_1.
|
||||
* If we assume airspeed constant, => V_gps_2-V_gps_1 = |V|*(f_2 - f1),
|
||||
* where "f" is the fuselage vector in earth coordinates.
|
||||
* We then solve for |V| = |V_gps_2-V_gps_1|/ |f_2 - f1|.
|
||||
* Adapted to: |V| = (V_gps_2-V_gps_1) dot (f2_-f_1) / |f_2 - f1|^2.
|
||||
*
|
||||
* See OP-1317 imu_wind_estimation.pdf for details on the adaptation
|
||||
* Need a low pass filter to filter out spikes in non coordinated maneuvers
|
||||
* A two step Butterworth second order filter is used. In the first step fuselage vector xB
|
||||
* and ground speed vector Vel are filtered. The fuselage vector is filtered through its pitch
|
||||
* and yaw to keep a unit length. After building the differenced dxB and dVel are produced and
|
||||
* the airspeed calculated. The calculated airspeed is filtered again with a Butterworth filter
|
||||
*/
|
||||
void imu_airspeedGet(AirspeedSensorData *airspeedData, const AirspeedSettingsData *airspeedSettings)
|
||||
{
|
||||
// pre-filter frequency rate
|
||||
const float ff = (float)(airspeedSettings->SamplePeriod) / 1000.0f / airspeedSettings->IMUBasedEstimationLowPassPeriod1;
|
||||
// filter frequency rate
|
||||
const float ffV = (float)(airspeedSettings->SamplePeriod) / 1000.0f / airspeedSettings->IMUBasedEstimationLowPassPeriod2;
|
||||
|
||||
// check for a change in filter frequency rate. if yes, then actualize filter constants and intermediate values
|
||||
if (fabsf(ffV - imu->ffV) > EPS) {
|
||||
InitButterWorthDF2Filter(ffV, &(imu->filter));
|
||||
InitButterWorthDF2Values(imu->Vw1, &(imu->filter), &(imu->Vw1n1), &(imu->Vw1n2));
|
||||
InitButterWorthDF2Values(imu->Vw2, &(imu->filter), &(imu->Vw2n1), &(imu->Vw2n2));
|
||||
InitButterWorthDF2Values(imu->Vw3, &(imu->filter), &(imu->Vw3n1), &(imu->Vw3n2));
|
||||
}
|
||||
if (fabsf(ff - imu->ff) > EPS) {
|
||||
InitButterWorthDF2Filter(ff, &(imu->prefilter));
|
||||
InitButterWorthDF2Values(imu->pOld, &(imu->prefilter), &(imu->pn1), &(imu->pn2));
|
||||
InitButterWorthDF2Values(imu->yOld, &(imu->prefilter), &(imu->yn1), &(imu->yn2));
|
||||
InitButterWorthDF2Values(imu->v1Old, &(imu->prefilter), &(imu->v1n1), &(imu->v1n2));
|
||||
InitButterWorthDF2Values(imu->v2Old, &(imu->prefilter), &(imu->v2n1), &(imu->v2n2));
|
||||
InitButterWorthDF2Values(imu->v3Old, &(imu->prefilter), &(imu->v3n1), &(imu->v3n2));
|
||||
}
|
||||
|
||||
float normVel2;
|
||||
float normDiffAttitude2;
|
||||
float dvdtDotdfdt;
|
||||
|
||||
float xB[3];
|
||||
// get values and conduct smoothing of ground speed and orientation independently of the calculation of airspeed
|
||||
{ // Scoping to save memory
|
||||
AttitudeStateData attData;
|
||||
AttitudeStateGet(&attData);
|
||||
VelocityStateData velData;
|
||||
VelocityStateGet(&velData);
|
||||
float p = imu->pOld, y = imu->yOld;
|
||||
float dxB[3];
|
||||
|
||||
// get pitch and roll Euler angles from quaternion
|
||||
// do not calculate the principlal argument of yaw, i.e. use old yaw to add multiples of 2pi to have a continuous yaw
|
||||
Quaternion2PY(attData.q1, attData.q2, attData.q3, attData.q4, &p, &y, false);
|
||||
|
||||
// filter pitch and roll Euler angles instead of fuselage vector to guarantee a unit length at all times
|
||||
p = FilterButterWorthDF2(p, &(imu->prefilter), &(imu->pn1), &(imu->pn2));
|
||||
y = FilterButterWorthDF2(y, &(imu->prefilter), &(imu->yn1), &(imu->yn2));
|
||||
// transform pitch and yaw into fuselage vector xB and xBold
|
||||
PY2xB(p, y, xB);
|
||||
// calculate change in fuselage vector by substraction of old value
|
||||
PY2DeltaxB(imu->pOld, imu->yOld, xB, dxB);
|
||||
|
||||
// filter ground speed from VelocityState
|
||||
const float fv1n = FilterButterWorthDF2(velData.North, &(imu->prefilter), &(imu->v1n1), &(imu->v1n2));
|
||||
const float fv2n = FilterButterWorthDF2(velData.East, &(imu->prefilter), &(imu->v2n1), &(imu->v2n2));
|
||||
const float fv3n = FilterButterWorthDF2(velData.Down, &(imu->prefilter), &(imu->v3n1), &(imu->v3n2));
|
||||
|
||||
// calculate norm of ground speed
|
||||
normVel2 = Sq(fv1n) + Sq(fv2n) + Sq(fv3n);
|
||||
// calculate norm of orientation change
|
||||
normDiffAttitude2 = Sq(dxB[0]) + Sq(dxB[1]) + Sq(dxB[2]);
|
||||
// cauclate scalar product between groundspeed change and orientation change
|
||||
dvdtDotdfdt = (fv1n - imu->v1Old) * dxB[0] + (fv2n - imu->v2Old) * dxB[1] + (fv3n - imu->v3Old) * dxB[2];
|
||||
|
||||
// actualise old values
|
||||
imu->pOld = p;
|
||||
imu->yOld = y;
|
||||
imu->v1Old = fv1n;
|
||||
imu->v2Old = fv2n;
|
||||
imu->v3Old = fv3n;
|
||||
}
|
||||
|
||||
// Some reorientation needed to be able to calculate airspeed, calculate only for sufficient velocity
|
||||
// a negative scalar product is a clear sign that we are not really able to calculate the airspeed
|
||||
// NOTE: normVel2 check against EPS_VELOCITY might make problems during hovering maneuvers in fixed wings
|
||||
if (normDiffAttitude2 > EPS_REORIENTATION && normVel2 > EPS_VELOCITY && dvdtDotdfdt > 0.f) {
|
||||
// Airspeed modulus: |v| = dv/dt * dxB/dt / |dxB/dt|^2
|
||||
// airspeed is always REAL because normDiffAttitude2 > EPS_REORIENTATION > 0 and REAL dvdtDotdfdt
|
||||
const float airspeed = dvdtDotdfdt / normDiffAttitude2;
|
||||
|
||||
// groundspeed = airspeed + wind ---> wind = groundspeed - airspeed
|
||||
const float wind[3] = { imu->v1Old - xB[0] * airspeed,
|
||||
imu->v2Old - xB[1] * airspeed,
|
||||
imu->v3Old - xB[2] * airspeed };
|
||||
// filter raw wind
|
||||
imu->Vw1 = FilterButterWorthDF2(wind[0], &(imu->filter), &(imu->Vw1n1), &(imu->Vw1n2));
|
||||
imu->Vw2 = FilterButterWorthDF2(wind[1], &(imu->filter), &(imu->Vw2n1), &(imu->Vw2n2));
|
||||
imu->Vw3 = FilterButterWorthDF2(wind[2], &(imu->filter), &(imu->Vw3n1), &(imu->Vw3n2));
|
||||
} // else leave wind estimation unchanged
|
||||
|
||||
{ // Scoping to save memory
|
||||
// airspeed = groundspeed - wind
|
||||
const float Vair[3] = {
|
||||
imu->v1Old - imu->Vw1,
|
||||
imu->v2Old - imu->Vw2,
|
||||
imu->v3Old - imu->Vw3
|
||||
};
|
||||
|
||||
// project airspeed into fuselage vector
|
||||
airspeedData->CalibratedAirspeed = Vair[0] * xB[0] + Vair[1] * xB[1] + Vair[2] * xB[2];
|
||||
}
|
||||
|
||||
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE;
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_AIRSPEED);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -3,10 +3,10 @@
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup AirspeedModule Airspeed Module
|
||||
* @brief Calculate airspeed as a function of the difference between sequential GPS velocity and attitude measurements
|
||||
* @brief Calculate airspeed as a function of the difference between sequential ground velocity and attitude measurements
|
||||
* @{
|
||||
*
|
||||
* @file gps_airspeed.h
|
||||
* @file imu_airspeed.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief Airspeed module, reads temperature and pressure from BMP085
|
||||
*
|
||||
@ -28,13 +28,13 @@
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef GPS_AIRSPEED_H
|
||||
#define GPS_AIRSPEED_H
|
||||
#ifndef IMU_AIRSPEED_H
|
||||
#define IMU_AIRSPEED_H
|
||||
|
||||
void gps_airspeedInitialize();
|
||||
void gps_airspeedGet(AirspeedSensorData *airspeedData, AirspeedSettingsData *airspeedSettings);
|
||||
void imu_airspeedInitialize(const AirspeedSettingsData *airspeedSettings);
|
||||
void imu_airspeedGet(AirspeedSensorData *airspeedData, const AirspeedSettingsData *airspeedSettings);
|
||||
|
||||
#endif // GPS_AIRSPEED_H
|
||||
#endif // IMU_AIRSPEED_H
|
||||
|
||||
/**
|
||||
* @}
|
@ -1,1348 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup Attitude Copter Control Attitude Estimation
|
||||
* @brief Acquires sensor data and computes attitude estimate
|
||||
* Specifically updates the the @ref AttitudeState "AttitudeState" and @ref AttitudeRaw "AttitudeRaw" settings objects
|
||||
* @{
|
||||
*
|
||||
* @file attitude.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Module to handle all comms to the AHRS on a periodic basis.
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
******************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/**
|
||||
* Input objects: None, takes sensor data via pios
|
||||
* Output objects: @ref AttitudeRaw @ref AttitudeState
|
||||
*
|
||||
* This module computes an attitude estimate from the sensor data
|
||||
*
|
||||
* The module executes in its own thread.
|
||||
*
|
||||
* UAVObjects are automatically generated by the UAVObjectGenerator from
|
||||
* the object definition XML file.
|
||||
*
|
||||
* Modules have no API, all communication to other modules is done through UAVObjects.
|
||||
* However modules may use the API exposed by shared libraries.
|
||||
* See the OpenPilot wiki for more details.
|
||||
* http://www.openpilot.org/OpenPilot_Application_Architecture
|
||||
*
|
||||
*/
|
||||
|
||||
#include <openpilot.h>
|
||||
#include <pios_struct_helper.h>
|
||||
#include "attitude.h"
|
||||
#include "accelsensor.h"
|
||||
#include "accelstate.h"
|
||||
#include "airspeedsensor.h"
|
||||
#include "airspeedstate.h"
|
||||
#include "attitudestate.h"
|
||||
#include "attitudesettings.h"
|
||||
#include "barosensor.h"
|
||||
#include "flightstatus.h"
|
||||
#include "gpspositionsensor.h"
|
||||
#include "gpsvelocitysensor.h"
|
||||
#include "gyrostate.h"
|
||||
#include "gyrosensor.h"
|
||||
#include "homelocation.h"
|
||||
#include "magsensor.h"
|
||||
#include "magstate.h"
|
||||
#include "positionstate.h"
|
||||
#include "ekfconfiguration.h"
|
||||
#include "ekfstatevariance.h"
|
||||
#include "revocalibration.h"
|
||||
#include "revosettings.h"
|
||||
#include "velocitystate.h"
|
||||
#include "taskinfo.h"
|
||||
|
||||
#include "CoordinateConversions.h"
|
||||
|
||||
// Private constants
|
||||
#define STACK_SIZE_BYTES 2048
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3)
|
||||
#define FAILSAFE_TIMEOUT_MS 10
|
||||
|
||||
#define CALIBRATION_DELAY 4000
|
||||
#define CALIBRATION_DURATION 6000
|
||||
// low pass filter configuration to calculate offset
|
||||
// of barometric altitude sensor
|
||||
// reasoning: updates at: 10 Hz, tau= 300 s settle time
|
||||
// exp(-(1/f) / tau ) ~=~ 0.9997
|
||||
#define BARO_OFFSET_LOWPASS_ALPHA 0.9997f
|
||||
|
||||
// simple IAS to TAS aproximation - 2% increase per 1000ft
|
||||
// since we do not have flowing air temperature information
|
||||
#define IAS2TAS(alt) (1.0f + (0.02f * (alt) / 304.8f))
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static xTaskHandle attitudeTaskHandle;
|
||||
|
||||
static xQueueHandle gyroQueue;
|
||||
static xQueueHandle accelQueue;
|
||||
static xQueueHandle magQueue;
|
||||
static xQueueHandle airspeedQueue;
|
||||
static xQueueHandle baroQueue;
|
||||
static xQueueHandle gpsQueue;
|
||||
static xQueueHandle gpsVelQueue;
|
||||
|
||||
static AttitudeSettingsData attitudeSettings;
|
||||
static HomeLocationData homeLocation;
|
||||
static RevoCalibrationData revoCalibration;
|
||||
static EKFConfigurationData ekfConfiguration;
|
||||
static RevoSettingsData revoSettings;
|
||||
static FlightStatusData flightStatus;
|
||||
const uint32_t SENSOR_QUEUE_SIZE = 10;
|
||||
|
||||
static bool volatile variance_error = true;
|
||||
static bool volatile initialization_required = true;
|
||||
static uint32_t volatile running_algorithm = 0xffffffff; // we start with no algorithm running
|
||||
static float rollPitchBiasRate = 0;
|
||||
|
||||
// Accel filtering
|
||||
static float accel_alpha = 0;
|
||||
static bool accel_filter_enabled = false;
|
||||
static float accels_filtered[3];
|
||||
static float grot_filtered[3];
|
||||
|
||||
// Private functions
|
||||
static void AttitudeTask(void *parameters);
|
||||
|
||||
static int32_t updateAttitudeComplementary(bool first_run);
|
||||
static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode);
|
||||
static void settingsUpdatedCb(UAVObjEvent *objEv);
|
||||
|
||||
static int32_t getNED(GPSPositionSensorData *gpsPosition, float *NED);
|
||||
|
||||
static void magOffsetEstimation(MagSensorData *mag);
|
||||
|
||||
// check for invalid values
|
||||
static inline bool invalid(float data)
|
||||
{
|
||||
if (isnan(data) || isinf(data)) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// check for invalid variance values
|
||||
static inline bool invalid_var(float data)
|
||||
{
|
||||
if (invalid(data)) {
|
||||
return true;
|
||||
}
|
||||
if (data < 1e-15f) { // var should not be close to zero. And not negative either.
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* API for sensor fusion algorithms:
|
||||
* Configure(xQueueHandle gyro, xQueueHandle accel, xQueueHandle mag, xQueueHandle baro)
|
||||
* Stores all the queues the algorithm will pull data from
|
||||
* FinalizeSensors() -- before saving the sensors modifies them based on internal state (gyro bias)
|
||||
* Update() -- queries queues and updates the attitude estiamte
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* Initialise the module. Called before the start function
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AttitudeInitialize(void)
|
||||
{
|
||||
GyroSensorInitialize();
|
||||
GyroStateInitialize();
|
||||
AccelSensorInitialize();
|
||||
AccelStateInitialize();
|
||||
MagSensorInitialize();
|
||||
MagStateInitialize();
|
||||
AirspeedSensorInitialize();
|
||||
AirspeedStateInitialize();
|
||||
BaroSensorInitialize();
|
||||
GPSPositionSensorInitialize();
|
||||
GPSVelocitySensorInitialize();
|
||||
AttitudeSettingsInitialize();
|
||||
AttitudeStateInitialize();
|
||||
PositionStateInitialize();
|
||||
VelocityStateInitialize();
|
||||
RevoSettingsInitialize();
|
||||
RevoCalibrationInitialize();
|
||||
EKFConfigurationInitialize();
|
||||
EKFStateVarianceInitialize();
|
||||
FlightStatusInitialize();
|
||||
|
||||
// Initialize this here while we aren't setting the homelocation in GPS
|
||||
HomeLocationInitialize();
|
||||
|
||||
// Initialize quaternion
|
||||
AttitudeStateData attitude;
|
||||
AttitudeStateGet(&attitude);
|
||||
attitude.q1 = 1.0f;
|
||||
attitude.q2 = 0.0f;
|
||||
attitude.q3 = 0.0f;
|
||||
attitude.q4 = 0.0f;
|
||||
AttitudeStateSet(&attitude);
|
||||
|
||||
AttitudeSettingsConnectCallback(&settingsUpdatedCb);
|
||||
RevoSettingsConnectCallback(&settingsUpdatedCb);
|
||||
RevoCalibrationConnectCallback(&settingsUpdatedCb);
|
||||
HomeLocationConnectCallback(&settingsUpdatedCb);
|
||||
EKFConfigurationConnectCallback(&settingsUpdatedCb);
|
||||
FlightStatusConnectCallback(&settingsUpdatedCb);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Start the task. Expects all objects to be initialized by this point.
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AttitudeStart(void)
|
||||
{
|
||||
// Create the queues for the sensors
|
||||
gyroQueue = xQueueCreate(1, sizeof(UAVObjEvent));
|
||||
accelQueue = xQueueCreate(1, sizeof(UAVObjEvent));
|
||||
magQueue = xQueueCreate(1, sizeof(UAVObjEvent));
|
||||
airspeedQueue = xQueueCreate(1, sizeof(UAVObjEvent));
|
||||
baroQueue = xQueueCreate(1, sizeof(UAVObjEvent));
|
||||
gpsQueue = xQueueCreate(1, sizeof(UAVObjEvent));
|
||||
gpsVelQueue = xQueueCreate(1, sizeof(UAVObjEvent));
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(AttitudeTask, "Attitude", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &attitudeTaskHandle);
|
||||
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_ATTITUDE, attitudeTaskHandle);
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE);
|
||||
#endif
|
||||
|
||||
GyroSensorConnectQueue(gyroQueue);
|
||||
AccelSensorConnectQueue(accelQueue);
|
||||
MagSensorConnectQueue(magQueue);
|
||||
AirspeedSensorConnectQueue(airspeedQueue);
|
||||
BaroSensorConnectQueue(baroQueue);
|
||||
GPSPositionSensorConnectQueue(gpsQueue);
|
||||
GPSVelocitySensorConnectQueue(gpsVelQueue);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(AttitudeInitialize, AttitudeStart);
|
||||
|
||||
/**
|
||||
* Module thread, should not return.
|
||||
*/
|
||||
static void AttitudeTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE);
|
||||
|
||||
// Force settings update to make sure rotation loaded
|
||||
settingsUpdatedCb(NULL);
|
||||
|
||||
// Wait for all the sensors be to read
|
||||
vTaskDelay(100);
|
||||
|
||||
// Main task loop - TODO: make it run as delayed callback
|
||||
while (1) {
|
||||
int32_t ret_val = -1;
|
||||
|
||||
bool first_run = false;
|
||||
if (initialization_required) {
|
||||
initialization_required = false;
|
||||
first_run = true;
|
||||
}
|
||||
|
||||
// This function blocks on data queue
|
||||
switch (running_algorithm) {
|
||||
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARY:
|
||||
ret_val = updateAttitudeComplementary(first_run);
|
||||
break;
|
||||
case REVOSETTINGS_FUSIONALGORITHM_INS13GPSOUTDOOR:
|
||||
ret_val = updateAttitudeINSGPS(first_run, true);
|
||||
break;
|
||||
case REVOSETTINGS_FUSIONALGORITHM_INS13INDOOR:
|
||||
ret_val = updateAttitudeINSGPS(first_run, false);
|
||||
break;
|
||||
default:
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
break;
|
||||
}
|
||||
|
||||
if (ret_val != 0) {
|
||||
initialization_required = true;
|
||||
}
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
static inline void apply_accel_filter(const float *raw, float *filtered)
|
||||
{
|
||||
if (accel_filter_enabled) {
|
||||
filtered[0] = filtered[0] * accel_alpha + raw[0] * (1 - accel_alpha);
|
||||
filtered[1] = filtered[1] * accel_alpha + raw[1] * (1 - accel_alpha);
|
||||
filtered[2] = filtered[2] * accel_alpha + raw[2] * (1 - accel_alpha);
|
||||
} else {
|
||||
filtered[0] = raw[0];
|
||||
filtered[1] = raw[1];
|
||||
filtered[2] = raw[2];
|
||||
}
|
||||
}
|
||||
|
||||
float accel_mag;
|
||||
float qmag;
|
||||
float attitudeDt;
|
||||
float mag_err[3];
|
||||
|
||||
static int32_t updateAttitudeComplementary(bool first_run)
|
||||
{
|
||||
UAVObjEvent ev;
|
||||
GyroSensorData gyroSensorData;
|
||||
GyroStateData gyroStateData;
|
||||
AccelSensorData accelSensorData;
|
||||
static int32_t timeval;
|
||||
float dT;
|
||||
static uint8_t init = 0;
|
||||
static float gyro_bias[3] = { 0, 0, 0 };
|
||||
static bool magCalibrated = true;
|
||||
static uint32_t initStartupTime = 0;
|
||||
|
||||
// Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe
|
||||
if (xQueueReceive(gyroQueue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE ||
|
||||
xQueueReceive(accelQueue, &ev, 1 / portTICK_RATE_MS) != pdTRUE) {
|
||||
// When one of these is updated so should the other
|
||||
// Do not set attitude timeout warnings in simulation mode
|
||||
if (!AttitudeStateReadOnly()) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_WARNING);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
AccelSensorGet(&accelSensorData);
|
||||
|
||||
// TODO: put in separate filter
|
||||
AccelStateData accelState;
|
||||
accelState.x = accelSensorData.x;
|
||||
accelState.y = accelSensorData.y;
|
||||
accelState.z = accelSensorData.z;
|
||||
AccelStateSet(&accelState);
|
||||
|
||||
// During initialization and
|
||||
if (first_run) {
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
// To initialize we need a valid mag reading
|
||||
if (xQueueReceive(magQueue, &ev, 0 / portTICK_RATE_MS) != pdTRUE) {
|
||||
return -1;
|
||||
}
|
||||
MagSensorData magData;
|
||||
MagSensorGet(&magData);
|
||||
#else
|
||||
MagSensorData magData;
|
||||
magData.x = 100.0f;
|
||||
magData.y = 0.0f;
|
||||
magData.z = 0.0f;
|
||||
#endif
|
||||
float magBias[3];
|
||||
RevoCalibrationmag_biasArrayGet(magBias);
|
||||
// don't trust Mag for initial orientation if it has not been calibrated
|
||||
if (magBias[0] < 1e-6f && magBias[1] < 1e-6f && magBias[2] < 1e-6f) {
|
||||
magCalibrated = false;
|
||||
magData.x = 100.0f;
|
||||
magData.y = 0.0f;
|
||||
magData.z = 0.0f;
|
||||
}
|
||||
AttitudeStateData attitudeState;
|
||||
AttitudeStateGet(&attitudeState);
|
||||
init = 0;
|
||||
|
||||
// Set initial attitude. Use accels to determine roll and pitch, rotate magnetic measurement accordingly,
|
||||
// so pseudo "north" vector can be estimated even if the board is not level
|
||||
attitudeState.Roll = atan2f(-accelSensorData.y, -accelSensorData.z);
|
||||
float zn = cosf(attitudeState.Roll) * magData.z + sinf(attitudeState.Roll) * magData.y;
|
||||
float yn = cosf(attitudeState.Roll) * magData.y - sinf(attitudeState.Roll) * magData.z;
|
||||
|
||||
// rotate accels z vector according to roll
|
||||
float azn = cosf(attitudeState.Roll) * accelSensorData.z + sinf(attitudeState.Roll) * accelSensorData.y;
|
||||
attitudeState.Pitch = atan2f(accelSensorData.x, -azn);
|
||||
|
||||
float xn = cosf(attitudeState.Pitch) * magData.x + sinf(attitudeState.Pitch) * zn;
|
||||
|
||||
attitudeState.Yaw = atan2f(-yn, xn);
|
||||
// TODO: This is still a hack
|
||||
// Put this in a proper generic function in CoordinateConversion.c
|
||||
// should take 4 vectors: g (0,0,-9.81), accels, Be (or 1,0,0 if no home loc) and magnetometers (or 1,0,0 if no mags)
|
||||
// should calculate the rotation in 3d space using proper cross product math
|
||||
// SUBTODO: formulate the math required
|
||||
|
||||
attitudeState.Roll = RAD2DEG(attitudeState.Roll);
|
||||
attitudeState.Pitch = RAD2DEG(attitudeState.Pitch);
|
||||
attitudeState.Yaw = RAD2DEG(attitudeState.Yaw);
|
||||
|
||||
RPY2Quaternion(&attitudeState.Roll, &attitudeState.q1);
|
||||
AttitudeStateSet(&attitudeState);
|
||||
|
||||
timeval = PIOS_DELAY_GetRaw();
|
||||
|
||||
// wait calibration_delay only at powerup
|
||||
if (xTaskGetTickCount() < 3000) {
|
||||
initStartupTime = 0;
|
||||
} else {
|
||||
initStartupTime = xTaskGetTickCount() - CALIBRATION_DELAY;
|
||||
}
|
||||
|
||||
// Zero gyro bias
|
||||
// This is really needed after updating calibration settings.
|
||||
gyro_bias[0] = 0.0f;
|
||||
gyro_bias[1] = 0.0f;
|
||||
gyro_bias[2] = 0.0f;
|
||||
return 0;
|
||||
}
|
||||
|
||||
if ((xTaskGetTickCount() - initStartupTime < CALIBRATION_DURATION + CALIBRATION_DELAY) &&
|
||||
(xTaskGetTickCount() - initStartupTime > CALIBRATION_DELAY)) {
|
||||
// For first CALIBRATION_DURATION seconds after CALIBRATION_DELAY from startup
|
||||
// Zero gyro bias assuming it is steady, smoothing the gyro input value applying rollPitchBiasRate.
|
||||
attitudeSettings.AccelKp = 1.0f;
|
||||
attitudeSettings.AccelKi = 0.0f;
|
||||
attitudeSettings.YawBiasRate = 0.23f;
|
||||
accel_filter_enabled = false;
|
||||
rollPitchBiasRate = 0.01f;
|
||||
attitudeSettings.MagKp = magCalibrated ? 1.0f : 0.0f;
|
||||
init = 0;
|
||||
} else if ((attitudeSettings.ZeroDuringArming == ATTITUDESETTINGS_ZERODURINGARMING_TRUE) && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) {
|
||||
attitudeSettings.AccelKp = 1.0f;
|
||||
attitudeSettings.AccelKi = 0.0f;
|
||||
attitudeSettings.YawBiasRate = 0.23f;
|
||||
accel_filter_enabled = false;
|
||||
rollPitchBiasRate = 0.01f;
|
||||
attitudeSettings.MagKp = magCalibrated ? 1.0f : 0.0f;
|
||||
init = 0;
|
||||
} else if (init == 0) {
|
||||
// Reload settings (all the rates)
|
||||
AttitudeSettingsGet(&attitudeSettings);
|
||||
rollPitchBiasRate = 0.0f;
|
||||
if (accel_alpha > 0.0f) {
|
||||
accel_filter_enabled = true;
|
||||
}
|
||||
init = 1;
|
||||
}
|
||||
|
||||
GyroSensorGet(&gyroSensorData);
|
||||
gyroStateData.x = gyroSensorData.x;
|
||||
gyroStateData.y = gyroSensorData.y;
|
||||
gyroStateData.z = gyroSensorData.z;
|
||||
|
||||
// Compute the dT using the cpu clock
|
||||
dT = PIOS_DELAY_DiffuS(timeval) / 1000000.0f;
|
||||
timeval = PIOS_DELAY_GetRaw();
|
||||
|
||||
float q[4];
|
||||
|
||||
AttitudeStateData attitudeState;
|
||||
AttitudeStateGet(&attitudeState);
|
||||
|
||||
float grot[3];
|
||||
float accel_err[3];
|
||||
|
||||
// Get the current attitude estimate
|
||||
quat_copy(&attitudeState.q1, q);
|
||||
|
||||
// Apply smoothing to accel values, to reduce vibration noise before main calculations.
|
||||
apply_accel_filter((const float *)&accelSensorData.x, accels_filtered);
|
||||
|
||||
// Rotate gravity to body frame and cross with accels
|
||||
grot[0] = -(2.0f * (q[1] * q[3] - q[0] * q[2]));
|
||||
grot[1] = -(2.0f * (q[2] * q[3] + q[0] * q[1]));
|
||||
grot[2] = -(q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]);
|
||||
|
||||
apply_accel_filter(grot, grot_filtered);
|
||||
|
||||
CrossProduct((const float *)accels_filtered, (const float *)grot_filtered, accel_err);
|
||||
|
||||
// Account for accel magnitude
|
||||
accel_mag = accels_filtered[0] * accels_filtered[0] + accels_filtered[1] * accels_filtered[1] + accels_filtered[2] * accels_filtered[2];
|
||||
accel_mag = sqrtf(accel_mag);
|
||||
|
||||
float grot_mag;
|
||||
if (accel_filter_enabled) {
|
||||
grot_mag = sqrtf(grot_filtered[0] * grot_filtered[0] + grot_filtered[1] * grot_filtered[1] + grot_filtered[2] * grot_filtered[2]);
|
||||
} else {
|
||||
grot_mag = 1.0f;
|
||||
}
|
||||
|
||||
// TODO! check grot_mag & accel vector magnitude values for correctness.
|
||||
|
||||
accel_err[0] /= (accel_mag * grot_mag);
|
||||
accel_err[1] /= (accel_mag * grot_mag);
|
||||
accel_err[2] /= (accel_mag * grot_mag);
|
||||
|
||||
|
||||
if (xQueueReceive(magQueue, &ev, 0) != pdTRUE) {
|
||||
// Rotate gravity to body frame and cross with accels
|
||||
float brot[3];
|
||||
float Rbe[3][3];
|
||||
MagSensorData mag;
|
||||
|
||||
Quaternion2R(q, Rbe);
|
||||
MagSensorGet(&mag);
|
||||
|
||||
// TODO: separate filter!
|
||||
if (revoCalibration.MagBiasNullingRate > 0) {
|
||||
magOffsetEstimation(&mag);
|
||||
}
|
||||
MagStateData mags;
|
||||
mags.x = mag.x;
|
||||
mags.y = mag.y;
|
||||
mags.z = mag.z;
|
||||
MagStateSet(&mags);
|
||||
|
||||
// If the mag is producing bad data don't use it (normally bad calibration)
|
||||
if (!isnan(mag.x) && !isinf(mag.x) && !isnan(mag.y) && !isinf(mag.y) && !isnan(mag.z) && !isinf(mag.z)) {
|
||||
rot_mult(Rbe, homeLocation.Be, brot);
|
||||
|
||||
float mag_len = sqrtf(mag.x * mag.x + mag.y * mag.y + mag.z * mag.z);
|
||||
mag.x /= mag_len;
|
||||
mag.y /= mag_len;
|
||||
mag.z /= mag_len;
|
||||
|
||||
float bmag = sqrtf(brot[0] * brot[0] + brot[1] * brot[1] + brot[2] * brot[2]);
|
||||
brot[0] /= bmag;
|
||||
brot[1] /= bmag;
|
||||
brot[2] /= bmag;
|
||||
|
||||
// Only compute if neither vector is null
|
||||
if (bmag < 1.0f || mag_len < 1.0f) {
|
||||
mag_err[0] = mag_err[1] = mag_err[2] = 0.0f;
|
||||
} else {
|
||||
CrossProduct((const float *)&mag.x, (const float *)brot, mag_err);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
mag_err[0] = mag_err[1] = mag_err[2] = 0.0f;
|
||||
}
|
||||
|
||||
// Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s
|
||||
// Correct rates based on integral coefficient
|
||||
gyroStateData.x -= gyro_bias[0];
|
||||
gyroStateData.y -= gyro_bias[1];
|
||||
gyroStateData.z -= gyro_bias[2];
|
||||
|
||||
gyro_bias[0] -= accel_err[0] * attitudeSettings.AccelKi - (gyroStateData.x) * rollPitchBiasRate;
|
||||
gyro_bias[1] -= accel_err[1] * attitudeSettings.AccelKi - (gyroStateData.y) * rollPitchBiasRate;
|
||||
gyro_bias[2] -= -mag_err[2] * attitudeSettings.MagKi - (gyroStateData.z) * rollPitchBiasRate;
|
||||
|
||||
// save gyroscope state
|
||||
GyroStateSet(&gyroStateData);
|
||||
|
||||
// Correct rates based on proportional coefficient
|
||||
gyroStateData.x += accel_err[0] * attitudeSettings.AccelKp / dT;
|
||||
gyroStateData.y += accel_err[1] * attitudeSettings.AccelKp / dT;
|
||||
gyroStateData.z += accel_err[2] * attitudeSettings.AccelKp / dT + mag_err[2] * attitudeSettings.MagKp / dT;
|
||||
|
||||
// Work out time derivative from INSAlgo writeup
|
||||
// Also accounts for the fact that gyros are in deg/s
|
||||
float qdot[4];
|
||||
qdot[0] = DEG2RAD(-q[1] * gyroStateData.x - q[2] * gyroStateData.y - q[3] * gyroStateData.z) * dT / 2;
|
||||
qdot[1] = DEG2RAD(q[0] * gyroStateData.x - q[3] * gyroStateData.y + q[2] * gyroStateData.z) * dT / 2;
|
||||
qdot[2] = DEG2RAD(q[3] * gyroStateData.x + q[0] * gyroStateData.y - q[1] * gyroStateData.z) * dT / 2;
|
||||
qdot[3] = DEG2RAD(-q[2] * gyroStateData.x + q[1] * gyroStateData.y + q[0] * gyroStateData.z) * dT / 2;
|
||||
|
||||
// Take a time step
|
||||
q[0] = q[0] + qdot[0];
|
||||
q[1] = q[1] + qdot[1];
|
||||
q[2] = q[2] + qdot[2];
|
||||
q[3] = q[3] + qdot[3];
|
||||
|
||||
if (q[0] < 0.0f) {
|
||||
q[0] = -q[0];
|
||||
q[1] = -q[1];
|
||||
q[2] = -q[2];
|
||||
q[3] = -q[3];
|
||||
}
|
||||
|
||||
// Renomalize
|
||||
qmag = sqrtf(q[0] * q[0] + q[1] * q[1] + q[2] * q[2] + q[3] * q[3]);
|
||||
q[0] = q[0] / qmag;
|
||||
q[1] = q[1] / qmag;
|
||||
q[2] = q[2] / qmag;
|
||||
q[3] = q[3] / qmag;
|
||||
|
||||
// If quaternion has become inappropriately short or is nan reinit.
|
||||
// THIS SHOULD NEVER ACTUALLY HAPPEN
|
||||
if ((fabsf(qmag) < 1.0e-3f) || isnan(qmag)) {
|
||||
q[0] = 1.0f;
|
||||
q[1] = 0.0f;
|
||||
q[2] = 0.0f;
|
||||
q[3] = 0.0f;
|
||||
}
|
||||
|
||||
quat_copy(q, &attitudeState.q1);
|
||||
|
||||
// Convert into eueler degrees (makes assumptions about RPY order)
|
||||
Quaternion2RPY(&attitudeState.q1, &attitudeState.Roll);
|
||||
|
||||
AttitudeStateSet(&attitudeState);
|
||||
|
||||
// Flush these queues for avoid errors
|
||||
xQueueReceive(baroQueue, &ev, 0);
|
||||
if (xQueueReceive(gpsQueue, &ev, 0) == pdTRUE && homeLocation.Set == HOMELOCATION_SET_TRUE) {
|
||||
float NED[3];
|
||||
// Transform the GPS position into NED coordinates
|
||||
GPSPositionSensorData gpsPosition;
|
||||
GPSPositionSensorGet(&gpsPosition);
|
||||
getNED(&gpsPosition, NED);
|
||||
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
positionState.North = NED[0];
|
||||
positionState.East = NED[1];
|
||||
positionState.Down = NED[2];
|
||||
PositionStateSet(&positionState);
|
||||
}
|
||||
|
||||
if (xQueueReceive(gpsVelQueue, &ev, 0) == pdTRUE) {
|
||||
// Transform the GPS position into NED coordinates
|
||||
GPSVelocitySensorData gpsVelocity;
|
||||
GPSVelocitySensorGet(&gpsVelocity);
|
||||
|
||||
VelocityStateData velocityState;
|
||||
VelocityStateGet(&velocityState);
|
||||
velocityState.North = gpsVelocity.North;
|
||||
velocityState.East = gpsVelocity.East;
|
||||
velocityState.Down = gpsVelocity.Down;
|
||||
VelocityStateSet(&velocityState);
|
||||
}
|
||||
|
||||
if (xQueueReceive(airspeedQueue, &ev, 0) == pdTRUE) {
|
||||
// Calculate true airspeed from indicated airspeed
|
||||
AirspeedSensorData airspeedSensor;
|
||||
AirspeedSensorGet(&airspeedSensor);
|
||||
|
||||
AirspeedStateData airspeed;
|
||||
AirspeedStateGet(&airspeed);
|
||||
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
|
||||
if (airspeedSensor.SensorConnected == AIRSPEEDSENSOR_SENSORCONNECTED_TRUE) {
|
||||
// we have airspeed available
|
||||
airspeed.CalibratedAirspeed = airspeedSensor.CalibratedAirspeed;
|
||||
airspeed.TrueAirspeed = (airspeedSensor.TrueAirspeed < 0.f) ? airspeed.CalibratedAirspeed *IAS2TAS(homeLocation.Altitude - positionState.Down) : airspeedSensor.TrueAirspeed;
|
||||
AirspeedStateSet(&airspeed);
|
||||
}
|
||||
}
|
||||
|
||||
if (!init && flightStatus.Armed == FLIGHTSTATUS_ARMED_DISARMED) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
|
||||
} else if (variance_error) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE);
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#include "insgps.h"
|
||||
int32_t ins_failed = 0;
|
||||
extern struct NavStruct Nav;
|
||||
int32_t init_stage = 0;
|
||||
|
||||
/**
|
||||
* @brief Use the INSGPS fusion algorithm in either indoor or outdoor mode (use GPS)
|
||||
* @params[in] first_run This is the first run so trigger reinitialization
|
||||
* @params[in] outdoor_mode If true use the GPS for position, if false weakly pull to (0,0)
|
||||
* @return 0 for success, -1 for failure
|
||||
*/
|
||||
static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode)
|
||||
{
|
||||
UAVObjEvent ev;
|
||||
GyroSensorData gyroSensorData;
|
||||
AccelSensorData accelSensorData;
|
||||
MagStateData magData;
|
||||
AirspeedSensorData airspeedData;
|
||||
BaroSensorData baroData;
|
||||
GPSPositionSensorData gpsData;
|
||||
GPSVelocitySensorData gpsVelData;
|
||||
|
||||
static bool mag_updated = false;
|
||||
static bool baro_updated;
|
||||
static bool airspeed_updated;
|
||||
static bool gps_updated;
|
||||
static bool gps_vel_updated;
|
||||
|
||||
static bool value_error = false;
|
||||
|
||||
static float baroOffset = 0.0f;
|
||||
|
||||
static uint32_t ins_last_time = 0;
|
||||
static bool inited;
|
||||
|
||||
float NED[3] = { 0.0f, 0.0f, 0.0f };
|
||||
float vel[3] = { 0.0f, 0.0f, 0.0f };
|
||||
float zeros[3] = { 0.0f, 0.0f, 0.0f };
|
||||
|
||||
// Perform the update
|
||||
uint16_t sensors = 0;
|
||||
float dT;
|
||||
|
||||
// Wait until the gyro and accel object is updated, if a timeout then go to failsafe
|
||||
if ((xQueueReceive(gyroQueue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE) ||
|
||||
(xQueueReceive(accelQueue, &ev, 1 / portTICK_RATE_MS) != pdTRUE)) {
|
||||
// Do not set attitude timeout warnings in simulation mode
|
||||
if (!AttitudeStateReadOnly()) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_WARNING);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
if (inited) {
|
||||
mag_updated = 0;
|
||||
baro_updated = 0;
|
||||
airspeed_updated = 0;
|
||||
gps_updated = 0;
|
||||
gps_vel_updated = 0;
|
||||
}
|
||||
|
||||
if (first_run) {
|
||||
inited = false;
|
||||
init_stage = 0;
|
||||
|
||||
mag_updated = 0;
|
||||
baro_updated = 0;
|
||||
airspeed_updated = 0;
|
||||
gps_updated = 0;
|
||||
gps_vel_updated = 0;
|
||||
|
||||
ins_last_time = PIOS_DELAY_GetRaw();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
mag_updated |= (xQueueReceive(magQueue, &ev, 0 / portTICK_RATE_MS) == pdTRUE);
|
||||
baro_updated |= xQueueReceive(baroQueue, &ev, 0 / portTICK_RATE_MS) == pdTRUE;
|
||||
airspeed_updated |= xQueueReceive(airspeedQueue, &ev, 0 / portTICK_RATE_MS) == pdTRUE;
|
||||
|
||||
// Check if we are running simulation
|
||||
if (!GPSPositionSensorReadOnly()) {
|
||||
gps_updated |= (xQueueReceive(gpsQueue, &ev, 0 / portTICK_RATE_MS) == pdTRUE) && outdoor_mode;
|
||||
} else {
|
||||
gps_updated |= pdTRUE && outdoor_mode;
|
||||
}
|
||||
|
||||
if (!GPSVelocitySensorReadOnly()) {
|
||||
gps_vel_updated |= (xQueueReceive(gpsVelQueue, &ev, 0 / portTICK_RATE_MS) == pdTRUE) && outdoor_mode;
|
||||
} else {
|
||||
gps_vel_updated |= pdTRUE && outdoor_mode;
|
||||
}
|
||||
|
||||
// Get most recent data
|
||||
GyroSensorGet(&gyroSensorData);
|
||||
AccelSensorGet(&accelSensorData);
|
||||
// TODO: separate filter!
|
||||
if (mag_updated) {
|
||||
MagSensorData mags;
|
||||
MagSensorGet(&mags);
|
||||
if (revoCalibration.MagBiasNullingRate > 0) {
|
||||
magOffsetEstimation(&mags);
|
||||
}
|
||||
magData.x = mags.x;
|
||||
magData.y = mags.y;
|
||||
magData.z = mags.z;
|
||||
MagStateSet(&magData);
|
||||
} else {
|
||||
MagStateGet(&magData);
|
||||
}
|
||||
|
||||
BaroSensorGet(&baroData);
|
||||
AirspeedSensorGet(&airspeedData);
|
||||
GPSPositionSensorGet(&gpsData);
|
||||
GPSVelocitySensorGet(&gpsVelData);
|
||||
|
||||
// TODO: put in separate filter
|
||||
AccelStateData accelState;
|
||||
accelState.x = accelSensorData.x;
|
||||
accelState.y = accelSensorData.y;
|
||||
accelState.z = accelSensorData.z;
|
||||
AccelStateSet(&accelState);
|
||||
|
||||
|
||||
value_error = false;
|
||||
// safety checks
|
||||
if (invalid(gyroSensorData.x) ||
|
||||
invalid(gyroSensorData.y) ||
|
||||
invalid(gyroSensorData.z) ||
|
||||
invalid(accelSensorData.x) ||
|
||||
invalid(accelSensorData.y) ||
|
||||
invalid(accelSensorData.z)) {
|
||||
// cannot run process update, raise error!
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (invalid(magData.x) ||
|
||||
invalid(magData.y) ||
|
||||
invalid(magData.z)) {
|
||||
// magnetometers can be ignored for a while
|
||||
mag_updated = false;
|
||||
value_error = true;
|
||||
}
|
||||
|
||||
// Don't require HomeLocation.Set to be true but at least require a mag configuration (allows easily
|
||||
// switching between indoor and outdoor mode with Set = false)
|
||||
if ((homeLocation.Be[0] * homeLocation.Be[0] + homeLocation.Be[1] * homeLocation.Be[1] + homeLocation.Be[2] * homeLocation.Be[2] < 1e-5f)) {
|
||||
mag_updated = false;
|
||||
value_error = true;
|
||||
}
|
||||
|
||||
if (invalid(baroData.Altitude)) {
|
||||
baro_updated = false;
|
||||
value_error = true;
|
||||
}
|
||||
|
||||
if (invalid(airspeedData.CalibratedAirspeed)) {
|
||||
airspeed_updated = false;
|
||||
value_error = true;
|
||||
}
|
||||
|
||||
if (invalid(gpsData.Altitude)) {
|
||||
gps_updated = false;
|
||||
value_error = true;
|
||||
}
|
||||
|
||||
if (invalid_var(ekfConfiguration.R.GPSPosNorth) ||
|
||||
invalid_var(ekfConfiguration.R.GPSPosEast) ||
|
||||
invalid_var(ekfConfiguration.R.GPSPosDown) ||
|
||||
invalid_var(ekfConfiguration.R.GPSVelNorth) ||
|
||||
invalid_var(ekfConfiguration.R.GPSVelEast) ||
|
||||
invalid_var(ekfConfiguration.R.GPSVelDown)) {
|
||||
gps_updated = false;
|
||||
value_error = true;
|
||||
}
|
||||
|
||||
if (invalid(gpsVelData.North) ||
|
||||
invalid(gpsVelData.East) ||
|
||||
invalid(gpsVelData.Down)) {
|
||||
gps_vel_updated = false;
|
||||
value_error = true;
|
||||
}
|
||||
|
||||
// Discard airspeed if sensor not connected
|
||||
if (airspeedData.SensorConnected != AIRSPEEDSENSOR_SENSORCONNECTED_TRUE) {
|
||||
airspeed_updated = false;
|
||||
}
|
||||
|
||||
// Have a minimum requirement for gps usage
|
||||
if ((gpsData.Satellites < 7) ||
|
||||
(gpsData.PDOP > 4.0f) ||
|
||||
(gpsData.Latitude == 0 && gpsData.Longitude == 0) ||
|
||||
(homeLocation.Set != HOMELOCATION_SET_TRUE)) {
|
||||
gps_updated = false;
|
||||
gps_vel_updated = false;
|
||||
}
|
||||
|
||||
if (!inited) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
|
||||
} else if (value_error) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else if (variance_error) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else if (outdoor_mode && gpsData.Satellites < 7) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE);
|
||||
}
|
||||
|
||||
dT = PIOS_DELAY_DiffuS(ins_last_time) / 1.0e6f;
|
||||
ins_last_time = PIOS_DELAY_GetRaw();
|
||||
|
||||
// This should only happen at start up or at mode switches
|
||||
if (dT > 0.01f) {
|
||||
dT = 0.01f;
|
||||
} else if (dT <= 0.001f) {
|
||||
dT = 0.001f;
|
||||
}
|
||||
|
||||
if (!inited && mag_updated && baro_updated && (gps_updated || !outdoor_mode) && !variance_error) {
|
||||
// Don't initialize until all sensors are read
|
||||
if (init_stage == 0) {
|
||||
// Reset the INS algorithm
|
||||
INSGPSInit();
|
||||
INSSetMagVar((float[3]) { ekfConfiguration.R.MagX,
|
||||
ekfConfiguration.R.MagY,
|
||||
ekfConfiguration.R.MagZ }
|
||||
);
|
||||
INSSetAccelVar((float[3]) { ekfConfiguration.Q.AccelX,
|
||||
ekfConfiguration.Q.AccelY,
|
||||
ekfConfiguration.Q.AccelZ }
|
||||
);
|
||||
INSSetGyroVar((float[3]) { ekfConfiguration.Q.GyroX,
|
||||
ekfConfiguration.Q.GyroY,
|
||||
ekfConfiguration.Q.GyroZ }
|
||||
);
|
||||
INSSetGyroBiasVar((float[3]) { ekfConfiguration.Q.GyroDriftX,
|
||||
ekfConfiguration.Q.GyroDriftY,
|
||||
ekfConfiguration.Q.GyroDriftZ }
|
||||
);
|
||||
INSSetBaroVar(ekfConfiguration.R.BaroZ);
|
||||
|
||||
// Initialize the gyro bias
|
||||
float gyro_bias[3] = { 0.0f, 0.0f, 0.0f };
|
||||
INSSetGyroBias(gyro_bias);
|
||||
|
||||
float pos[3] = { 0.0f, 0.0f, 0.0f };
|
||||
|
||||
if (outdoor_mode) {
|
||||
GPSPositionSensorData gpsPosition;
|
||||
GPSPositionSensorGet(&gpsPosition);
|
||||
|
||||
// Transform the GPS position into NED coordinates
|
||||
getNED(&gpsPosition, pos);
|
||||
|
||||
// Initialize barometric offset to current GPS NED coordinate
|
||||
baroOffset = -pos[2] - baroData.Altitude;
|
||||
} else {
|
||||
// Initialize barometric offset to homelocation altitude
|
||||
baroOffset = -baroData.Altitude;
|
||||
pos[2] = -(baroData.Altitude + baroOffset);
|
||||
}
|
||||
|
||||
// xQueueReceive(magQueue, &ev, 100 / portTICK_RATE_MS);
|
||||
// MagSensorGet(&magData);
|
||||
|
||||
AttitudeStateData attitudeState;
|
||||
AttitudeStateGet(&attitudeState);
|
||||
|
||||
// Set initial attitude. Use accels to determine roll and pitch, rotate magnetic measurement accordingly,
|
||||
// so pseudo "north" vector can be estimated even if the board is not level
|
||||
attitudeState.Roll = atan2f(-accelSensorData.y, -accelSensorData.z);
|
||||
float zn = cosf(attitudeState.Roll) * magData.z + sinf(attitudeState.Roll) * magData.y;
|
||||
float yn = cosf(attitudeState.Roll) * magData.y - sinf(attitudeState.Roll) * magData.z;
|
||||
|
||||
// rotate accels z vector according to roll
|
||||
float azn = cosf(attitudeState.Roll) * accelSensorData.z + sinf(attitudeState.Roll) * accelSensorData.y;
|
||||
attitudeState.Pitch = atan2f(accelSensorData.x, -azn);
|
||||
|
||||
float xn = cosf(attitudeState.Pitch) * magData.x + sinf(attitudeState.Pitch) * zn;
|
||||
|
||||
attitudeState.Yaw = atan2f(-yn, xn);
|
||||
// TODO: This is still a hack
|
||||
// Put this in a proper generic function in CoordinateConversion.c
|
||||
// should take 4 vectors: g (0,0,-9.81), accels, Be (or 1,0,0 if no home loc) and magnetometers (or 1,0,0 if no mags)
|
||||
// should calculate the rotation in 3d space using proper cross product math
|
||||
// SUBTODO: formulate the math required
|
||||
|
||||
attitudeState.Roll = RAD2DEG(attitudeState.Roll);
|
||||
attitudeState.Pitch = RAD2DEG(attitudeState.Pitch);
|
||||
attitudeState.Yaw = RAD2DEG(attitudeState.Yaw);
|
||||
|
||||
RPY2Quaternion(&attitudeState.Roll, &attitudeState.q1);
|
||||
AttitudeStateSet(&attitudeState);
|
||||
|
||||
float q[4] = { attitudeState.q1, attitudeState.q2, attitudeState.q3, attitudeState.q4 };
|
||||
INSSetState(pos, zeros, q, zeros, zeros);
|
||||
|
||||
INSResetP(cast_struct_to_array(ekfConfiguration.P, ekfConfiguration.P.AttitudeQ1));
|
||||
} else {
|
||||
// Run prediction a bit before any corrections
|
||||
|
||||
// Because the sensor module remove the bias we need to add it
|
||||
// back in here so that the INS algorithm can track it correctly
|
||||
float gyros[3] = { DEG2RAD(gyroSensorData.x), DEG2RAD(gyroSensorData.y), DEG2RAD(gyroSensorData.z) };
|
||||
INSStatePrediction(gyros, &accelSensorData.x, dT);
|
||||
|
||||
AttitudeStateData attitude;
|
||||
AttitudeStateGet(&attitude);
|
||||
attitude.q1 = Nav.q[0];
|
||||
attitude.q2 = Nav.q[1];
|
||||
attitude.q3 = Nav.q[2];
|
||||
attitude.q4 = Nav.q[3];
|
||||
Quaternion2RPY(&attitude.q1, &attitude.Roll);
|
||||
AttitudeStateSet(&attitude);
|
||||
}
|
||||
|
||||
init_stage++;
|
||||
if (init_stage > 10) {
|
||||
inited = true;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!inited) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Because the sensor module remove the bias we need to add it
|
||||
// back in here so that the INS algorithm can track it correctly
|
||||
float gyros[3] = { DEG2RAD(gyroSensorData.x), DEG2RAD(gyroSensorData.y), DEG2RAD(gyroSensorData.z) };
|
||||
|
||||
// Advance the state estimate
|
||||
INSStatePrediction(gyros, &accelSensorData.x, dT);
|
||||
|
||||
// Copy the attitude into the UAVO
|
||||
AttitudeStateData attitude;
|
||||
AttitudeStateGet(&attitude);
|
||||
attitude.q1 = Nav.q[0];
|
||||
attitude.q2 = Nav.q[1];
|
||||
attitude.q3 = Nav.q[2];
|
||||
attitude.q4 = Nav.q[3];
|
||||
Quaternion2RPY(&attitude.q1, &attitude.Roll);
|
||||
AttitudeStateSet(&attitude);
|
||||
|
||||
// Advance the covariance estimate
|
||||
INSCovariancePrediction(dT);
|
||||
|
||||
if (mag_updated) {
|
||||
sensors |= MAG_SENSORS;
|
||||
}
|
||||
|
||||
if (baro_updated) {
|
||||
sensors |= BARO_SENSOR;
|
||||
}
|
||||
|
||||
INSSetMagNorth(homeLocation.Be);
|
||||
|
||||
if (gps_updated && outdoor_mode) {
|
||||
INSSetPosVelVar((float[3]) { ekfConfiguration.R.GPSPosNorth,
|
||||
ekfConfiguration.R.GPSPosEast,
|
||||
ekfConfiguration.R.GPSPosDown },
|
||||
(float[3]) { ekfConfiguration.R.GPSVelNorth,
|
||||
ekfConfiguration.R.GPSVelEast,
|
||||
ekfConfiguration.R.GPSVelDown }
|
||||
);
|
||||
sensors |= POS_SENSORS;
|
||||
|
||||
if (0) { // Old code to take horizontal velocity from GPS Position update
|
||||
sensors |= HORIZ_SENSORS;
|
||||
vel[0] = gpsData.Groundspeed * cosf(DEG2RAD(gpsData.Heading));
|
||||
vel[1] = gpsData.Groundspeed * sinf(DEG2RAD(gpsData.Heading));
|
||||
vel[2] = 0.0f;
|
||||
}
|
||||
// Transform the GPS position into NED coordinates
|
||||
getNED(&gpsData, NED);
|
||||
|
||||
// Track barometric altitude offset with a low pass filter
|
||||
baroOffset = BARO_OFFSET_LOWPASS_ALPHA * baroOffset +
|
||||
(1.0f - BARO_OFFSET_LOWPASS_ALPHA)
|
||||
* (-NED[2] - baroData.Altitude);
|
||||
} else if (!outdoor_mode) {
|
||||
INSSetPosVelVar((float[3]) { ekfConfiguration.FakeR.FakeGPSPosIndoor,
|
||||
ekfConfiguration.FakeR.FakeGPSPosIndoor,
|
||||
ekfConfiguration.FakeR.FakeGPSPosIndoor },
|
||||
(float[3]) { ekfConfiguration.FakeR.FakeGPSVelIndoor,
|
||||
ekfConfiguration.FakeR.FakeGPSVelIndoor,
|
||||
ekfConfiguration.FakeR.FakeGPSVelIndoor }
|
||||
);
|
||||
vel[0] = vel[1] = vel[2] = 0.0f;
|
||||
NED[0] = NED[1] = 0.0f;
|
||||
NED[2] = -(baroData.Altitude + baroOffset);
|
||||
sensors |= HORIZ_SENSORS | HORIZ_POS_SENSORS;
|
||||
sensors |= POS_SENSORS | VERT_SENSORS;
|
||||
}
|
||||
|
||||
if (gps_vel_updated && outdoor_mode) {
|
||||
sensors |= HORIZ_SENSORS | VERT_SENSORS;
|
||||
vel[0] = gpsVelData.North;
|
||||
vel[1] = gpsVelData.East;
|
||||
vel[2] = gpsVelData.Down;
|
||||
}
|
||||
|
||||
// Copy the position into the UAVO
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
positionState.North = Nav.Pos[0];
|
||||
positionState.East = Nav.Pos[1];
|
||||
positionState.Down = Nav.Pos[2];
|
||||
PositionStateSet(&positionState);
|
||||
|
||||
// airspeed correction needs current positionState
|
||||
if (airspeed_updated) {
|
||||
// we have airspeed available
|
||||
AirspeedStateData airspeed;
|
||||
AirspeedStateGet(&airspeed);
|
||||
|
||||
airspeed.CalibratedAirspeed = airspeedData.CalibratedAirspeed;
|
||||
airspeed.TrueAirspeed = (airspeedData.TrueAirspeed < 0.f) ? airspeed.CalibratedAirspeed *IAS2TAS(homeLocation.Altitude - positionState.Down) : airspeedData.TrueAirspeed;
|
||||
|
||||
AirspeedStateSet(&airspeed);
|
||||
|
||||
if (!gps_vel_updated && !gps_updated) {
|
||||
// feed airspeed into EKF, treat wind as 1e2 variance
|
||||
sensors |= HORIZ_SENSORS | VERT_SENSORS;
|
||||
INSSetPosVelVar((float[3]) { ekfConfiguration.FakeR.FakeGPSPosIndoor,
|
||||
ekfConfiguration.FakeR.FakeGPSPosIndoor,
|
||||
ekfConfiguration.FakeR.FakeGPSPosIndoor },
|
||||
(float[3]) { ekfConfiguration.FakeR.FakeGPSVelAirspeed,
|
||||
ekfConfiguration.FakeR.FakeGPSVelAirspeed,
|
||||
ekfConfiguration.FakeR.FakeGPSVelAirspeed }
|
||||
);
|
||||
// rotate airspeed vector into NED frame - airspeed is measured in X axis only
|
||||
float R[3][3];
|
||||
Quaternion2R(Nav.q, R);
|
||||
float vtas[3] = { airspeed.TrueAirspeed, 0.0f, 0.0f };
|
||||
rot_mult(R, vtas, vel);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* TODO: Need to add a general sanity check for all the inputs to make sure their kosher
|
||||
* although probably should occur within INS itself
|
||||
*/
|
||||
if (sensors) {
|
||||
INSCorrection(&magData.x, NED, vel, (baroData.Altitude + baroOffset), sensors);
|
||||
}
|
||||
|
||||
// Copy the velocity into the UAVO
|
||||
VelocityStateData velocityState;
|
||||
VelocityStateGet(&velocityState);
|
||||
velocityState.North = Nav.Vel[0];
|
||||
velocityState.East = Nav.Vel[1];
|
||||
velocityState.Down = Nav.Vel[2];
|
||||
VelocityStateSet(&velocityState);
|
||||
|
||||
GyroStateData gyroState;
|
||||
gyroState.x = RAD2DEG(gyros[0] - RAD2DEG(Nav.gyro_bias[0]));
|
||||
gyroState.y = RAD2DEG(gyros[1] - RAD2DEG(Nav.gyro_bias[1]));
|
||||
gyroState.z = RAD2DEG(gyros[2] - RAD2DEG(Nav.gyro_bias[2]));
|
||||
GyroStateSet(&gyroState);
|
||||
|
||||
EKFStateVarianceData vardata;
|
||||
EKFStateVarianceGet(&vardata);
|
||||
INSGetP(cast_struct_to_array(vardata.P, vardata.P.AttitudeQ1));
|
||||
EKFStateVarianceSet(&vardata);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Convert the GPS LLA position into NED coordinates
|
||||
* @note this method uses a taylor expansion around the home coordinates
|
||||
* to convert to NED which allows it to be done with all floating
|
||||
* calculations
|
||||
* @param[in] Current GPS coordinates
|
||||
* @param[out] NED frame coordinates
|
||||
* @returns 0 for success, -1 for failure
|
||||
*/
|
||||
float T[3];
|
||||
static int32_t getNED(GPSPositionSensorData *gpsPosition, float *NED)
|
||||
{
|
||||
float dL[3] = { DEG2RAD((gpsPosition->Latitude - homeLocation.Latitude) / 10.0e6f),
|
||||
DEG2RAD((gpsPosition->Longitude - homeLocation.Longitude) / 10.0e6f),
|
||||
(gpsPosition->Altitude + gpsPosition->GeoidSeparation - homeLocation.Altitude) };
|
||||
|
||||
NED[0] = T[0] * dL[0];
|
||||
NED[1] = T[1] * dL[1];
|
||||
NED[2] = T[2] * dL[2];
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void settingsUpdatedCb(UAVObjEvent *ev)
|
||||
{
|
||||
if (ev == NULL || ev->obj == FlightStatusHandle()) {
|
||||
FlightStatusGet(&flightStatus);
|
||||
}
|
||||
if (ev == NULL || ev->obj == RevoCalibrationHandle()) {
|
||||
RevoCalibrationGet(&revoCalibration);
|
||||
}
|
||||
// change of these settings require reinitialization of the EKF
|
||||
// when an error flag has been risen, we also listen to flightStatus updates,
|
||||
// since we are waiting for the system to get disarmed so we can reinitialize safely.
|
||||
if (ev == NULL ||
|
||||
ev->obj == EKFConfigurationHandle() ||
|
||||
ev->obj == RevoSettingsHandle() ||
|
||||
(variance_error == true && ev->obj == FlightStatusHandle())
|
||||
) {
|
||||
bool error = false;
|
||||
|
||||
EKFConfigurationGet(&ekfConfiguration);
|
||||
int t;
|
||||
for (t = 0; t < EKFCONFIGURATION_P_NUMELEM; t++) {
|
||||
if (invalid_var(cast_struct_to_array(ekfConfiguration.P, ekfConfiguration.P.AttitudeQ1)[t])) {
|
||||
error = true;
|
||||
}
|
||||
}
|
||||
for (t = 0; t < EKFCONFIGURATION_Q_NUMELEM; t++) {
|
||||
if (invalid_var(cast_struct_to_array(ekfConfiguration.Q, ekfConfiguration.Q.AccelX)[t])) {
|
||||
error = true;
|
||||
}
|
||||
}
|
||||
for (t = 0; t < EKFCONFIGURATION_R_NUMELEM; t++) {
|
||||
if (invalid_var(cast_struct_to_array(ekfConfiguration.R, ekfConfiguration.R.BaroZ)[t])) {
|
||||
error = true;
|
||||
}
|
||||
}
|
||||
|
||||
RevoSettingsGet(&revoSettings);
|
||||
|
||||
// Reinitialization of the EKF is not desired during flight.
|
||||
// It will be delayed until the board is disarmed by raising the error flag.
|
||||
// We will not prevent the initial initialization though, since the board could be in always armed mode.
|
||||
if (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED && !initialization_required) {
|
||||
error = true;
|
||||
}
|
||||
|
||||
if (error) {
|
||||
variance_error = true;
|
||||
} else {
|
||||
// trigger reinitialization - possibly with new algorithm
|
||||
running_algorithm = revoSettings.FusionAlgorithm;
|
||||
variance_error = false;
|
||||
initialization_required = true;
|
||||
}
|
||||
}
|
||||
if (ev == NULL || ev->obj == HomeLocationHandle()) {
|
||||
HomeLocationGet(&homeLocation);
|
||||
// Compute matrix to convert deltaLLA to NED
|
||||
float lat, alt;
|
||||
lat = DEG2RAD(homeLocation.Latitude / 10.0e6f);
|
||||
alt = homeLocation.Altitude;
|
||||
|
||||
T[0] = alt + 6.378137E6f;
|
||||
T[1] = cosf(lat) * (alt + 6.378137E6f);
|
||||
T[2] = -1.0f;
|
||||
|
||||
// TODO: convert positionState to new reference frame and gracefully update EKF state!
|
||||
// needed for long range flights where the reference coordinate is adjusted in flight
|
||||
}
|
||||
if (ev == NULL || ev->obj == AttitudeSettingsHandle()) {
|
||||
AttitudeSettingsGet(&attitudeSettings);
|
||||
|
||||
// Calculate accel filter alpha, in the same way as for gyro data in stabilization module.
|
||||
const float fakeDt = 0.0015f;
|
||||
if (attitudeSettings.AccelTau < 0.0001f) {
|
||||
accel_alpha = 0; // not trusting this to resolve to 0
|
||||
accel_filter_enabled = false;
|
||||
} else {
|
||||
accel_alpha = expf(-fakeDt / attitudeSettings.AccelTau);
|
||||
accel_filter_enabled = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Perform an update of the @ref MagBias based on
|
||||
* Magmeter Offset Cancellation: Theory and Implementation,
|
||||
* revisited William Premerlani, October 14, 2011
|
||||
*/
|
||||
static void magOffsetEstimation(MagSensorData *mag)
|
||||
{
|
||||
#if 0
|
||||
// Constants, to possibly go into a UAVO
|
||||
static const float MIN_NORM_DIFFERENCE = 50;
|
||||
|
||||
static float B2[3] = { 0, 0, 0 };
|
||||
|
||||
MagBiasData magBias;
|
||||
MagBiasGet(&magBias);
|
||||
|
||||
// Remove the current estimate of the bias
|
||||
mag->x -= magBias.x;
|
||||
mag->y -= magBias.y;
|
||||
mag->z -= magBias.z;
|
||||
|
||||
// First call
|
||||
if (B2[0] == 0 && B2[1] == 0 && B2[2] == 0) {
|
||||
B2[0] = mag->x;
|
||||
B2[1] = mag->y;
|
||||
B2[2] = mag->z;
|
||||
return;
|
||||
}
|
||||
|
||||
float B1[3] = { mag->x, mag->y, mag->z };
|
||||
float norm_diff = sqrtf(powf(B2[0] - B1[0], 2) + powf(B2[1] - B1[1], 2) + powf(B2[2] - B1[2], 2));
|
||||
if (norm_diff > MIN_NORM_DIFFERENCE) {
|
||||
float norm_b1 = sqrtf(B1[0] * B1[0] + B1[1] * B1[1] + B1[2] * B1[2]);
|
||||
float norm_b2 = sqrtf(B2[0] * B2[0] + B2[1] * B2[1] + B2[2] * B2[2]);
|
||||
float scale = cal.MagBiasNullingRate * (norm_b2 - norm_b1) / norm_diff;
|
||||
float b_error[3] = { (B2[0] - B1[0]) * scale, (B2[1] - B1[1]) * scale, (B2[2] - B1[2]) * scale };
|
||||
|
||||
magBias.x += b_error[0];
|
||||
magBias.y += b_error[1];
|
||||
magBias.z += b_error[2];
|
||||
|
||||
MagBiasSet(&magBias);
|
||||
|
||||
// Store this value to compare against next update
|
||||
B2[0] = B1[0]; B2[1] = B1[1]; B2[2] = B1[2];
|
||||
}
|
||||
#else // if 0
|
||||
static float magBias[3] = { 0 };
|
||||
|
||||
// Remove the current estimate of the bias
|
||||
mag->x -= magBias[0];
|
||||
mag->y -= magBias[1];
|
||||
mag->z -= magBias[2];
|
||||
|
||||
AttitudeStateData attitude;
|
||||
AttitudeStateGet(&attitude);
|
||||
|
||||
const float Rxy = sqrtf(homeLocation.Be[0] * homeLocation.Be[0] + homeLocation.Be[1] * homeLocation.Be[1]);
|
||||
const float Rz = homeLocation.Be[2];
|
||||
|
||||
const float rate = revoCalibration.MagBiasNullingRate;
|
||||
float Rot[3][3];
|
||||
float B_e[3];
|
||||
float xy[2];
|
||||
float delta[3];
|
||||
|
||||
// Get the rotation matrix
|
||||
Quaternion2R(&attitude.q1, Rot);
|
||||
|
||||
// Rotate the mag into the NED frame
|
||||
B_e[0] = Rot[0][0] * mag->x + Rot[1][0] * mag->y + Rot[2][0] * mag->z;
|
||||
B_e[1] = Rot[0][1] * mag->x + Rot[1][1] * mag->y + Rot[2][1] * mag->z;
|
||||
B_e[2] = Rot[0][2] * mag->x + Rot[1][2] * mag->y + Rot[2][2] * mag->z;
|
||||
|
||||
float cy = cosf(DEG2RAD(attitude.Yaw));
|
||||
float sy = sinf(DEG2RAD(attitude.Yaw));
|
||||
|
||||
xy[0] = cy * B_e[0] + sy * B_e[1];
|
||||
xy[1] = -sy * B_e[0] + cy * B_e[1];
|
||||
|
||||
float xy_norm = sqrtf(xy[0] * xy[0] + xy[1] * xy[1]);
|
||||
|
||||
delta[0] = -rate * (xy[0] / xy_norm * Rxy - xy[0]);
|
||||
delta[1] = -rate * (xy[1] / xy_norm * Rxy - xy[1]);
|
||||
delta[2] = -rate * (Rz - B_e[2]);
|
||||
|
||||
if (!isnan(delta[0]) && !isinf(delta[0]) &&
|
||||
!isnan(delta[1]) && !isinf(delta[1]) &&
|
||||
!isnan(delta[2]) && !isinf(delta[2])) {
|
||||
magBias[0] += delta[0];
|
||||
magBias[1] += delta[1];
|
||||
magBias[2] += delta[2];
|
||||
}
|
||||
#endif // if 0
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -64,7 +64,8 @@ static int32_t alt_ds_pres = 0;
|
||||
static int alt_ds_count = 0;
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
pios_hmc5x83_dev_t mag_handle = 0;
|
||||
int32_t mag_test;
|
||||
static float mag_bias[3] = { 0, 0, 0 };
|
||||
static float mag_scale[3] = { 1, 1, 1 };
|
||||
@ -108,7 +109,7 @@ int32_t MagBaroInitialize()
|
||||
#endif
|
||||
|
||||
if (magbaroEnabled) {
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
MagSensorInitialize();
|
||||
#endif
|
||||
|
||||
@ -127,15 +128,16 @@ MODULE_INITCALL(MagBaroInitialize, MagBaroStart);
|
||||
/**
|
||||
* Module thread, should not return.
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
static const struct pios_hmc5883_cfg pios_hmc5883_cfg = {
|
||||
#ifdef PIOS_HMC5883_HAS_GPIOS
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = 0,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5883_ODR_15,
|
||||
.Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5883_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5883_MODE_CONTINUOUS,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_15,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
};
|
||||
#endif
|
||||
|
||||
@ -148,9 +150,9 @@ static void magbaroTask(__attribute__((unused)) void *parameters)
|
||||
PIOS_BMP085_Init();
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
MagSensorData mag;
|
||||
PIOS_HMC5883_Init(&pios_hmc5883_cfg);
|
||||
mag_handle = PIOS_HMC5x83_Init(&pios_hmc5x83_cfg, PIOS_I2C_MAIN_ADAPTER, 0);
|
||||
uint32_t mag_update_time = PIOS_DELAY_GetRaw();
|
||||
#endif
|
||||
|
||||
@ -197,10 +199,10 @@ static void magbaroTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_BMP085) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
if (PIOS_HMC5883_NewDataAvailable() || PIOS_DELAY_DiffuS(mag_update_time) > 100000) {
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
if (PIOS_HMC5x83_NewDataAvailable(mag_handle) || PIOS_DELAY_DiffuS(mag_update_time) > 100000) {
|
||||
int16_t values[3];
|
||||
PIOS_HMC5883_ReadMag(values);
|
||||
PIOS_HMC5x83_ReadMag(mag_handle, values);
|
||||
float mags[3] = { (float)values[1] * mag_scale[0] - mag_bias[0],
|
||||
(float)values[0] * mag_scale[1] - mag_bias[1],
|
||||
-(float)values[2] * mag_scale[2] - mag_bias[2] };
|
||||
|
@ -687,8 +687,8 @@ static bool nmeaProcessGPGSV(__attribute__((unused)) GPSPositionSensorData *GpsD
|
||||
|
||||
// Get sat info
|
||||
gsv_partial.PRN[sat_index] = atoi(param[parIdx++]);
|
||||
gsv_partial.Elevation[sat_index] = NMEA_real_to_float(param[parIdx++]);
|
||||
gsv_partial.Azimuth[sat_index] = NMEA_real_to_float(param[parIdx++]);
|
||||
gsv_partial.Elevation[sat_index] = atoi(param[parIdx++]);
|
||||
gsv_partial.Azimuth[sat_index] = atoi(param[parIdx++]);
|
||||
gsv_partial.SNR[sat_index] = atoi(param[parIdx++]);
|
||||
#ifdef NMEA_DEBUG_GSV
|
||||
DEBUG_MSG(" %d", gsv_partial.PRN[sat_index]);
|
||||
|
@ -32,10 +32,11 @@
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS_UBX_PARSER)
|
||||
#include "inc/UBX.h"
|
||||
#include "inc/GPS.h"
|
||||
|
||||
#include "UBX.h"
|
||||
#include "GPS.h"
|
||||
|
||||
// If a PVT sentence is received in the last UBX_PVT_TIMEOUT (ms) timeframe it disables VELNED/POSLLH/SOL/TIMEUTC
|
||||
#define UBX_PVT_TIMEOUT (1000)
|
||||
// parse incoming character stream for messages in UBX binary format
|
||||
|
||||
int parse_ubx_stream(uint8_t c, char *gps_rx_buffer, GPSPositionSensorData *GpsData, struct GPS_RX_STATS *gpsRxStats)
|
||||
@ -251,6 +252,47 @@ void parse_ubx_nav_velned(struct UBX_NAV_VELNED *velned, GPSPositionSensorData *
|
||||
}
|
||||
}
|
||||
|
||||
void parse_ubx_nav_pvt(struct UBX_NAV_PVT *pvt, GPSPositionSensorData *GpsPosition)
|
||||
{
|
||||
GPSVelocitySensorData GpsVelocity;
|
||||
|
||||
check_msgtracker(pvt->iTOW, (ALL_RECEIVED));
|
||||
|
||||
GpsVelocity.North = (float)pvt->velN * 0.001f;
|
||||
GpsVelocity.East = (float)pvt->velE * 0.001f;
|
||||
GpsVelocity.Down = (float)pvt->velD * 0.001f;
|
||||
GPSVelocitySensorSet(&GpsVelocity);
|
||||
|
||||
GpsPosition->Groundspeed = (float)pvt->gSpeed * 0.001f;
|
||||
GpsPosition->Heading = (float)pvt->heading * 1.0e-5f;
|
||||
GpsPosition->Altitude = (float)pvt->hMSL * 0.001f;
|
||||
GpsPosition->GeoidSeparation = (float)(pvt->height - pvt->hMSL) * 0.001f;
|
||||
GpsPosition->Latitude = pvt->lat;
|
||||
GpsPosition->Longitude = pvt->lon;
|
||||
GpsPosition->Satellites = pvt->numSV;
|
||||
GpsPosition->PDOP = pvt->pDOP * 0.01f;
|
||||
if (pvt->flags & PVT_FLAGS_GNSSFIX_OK) {
|
||||
GpsPosition->Status = pvt->fixType == PVT_FIX_TYPE_3D ?
|
||||
GPSPOSITIONSENSOR_STATUS_FIX3D : GPSPOSITIONSENSOR_STATUS_FIX2D;
|
||||
} else {
|
||||
GpsPosition->Status = GPSPOSITIONSENSOR_STATUS_NOFIX;
|
||||
}
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
if (pvt->valid & PVT_VALID_VALIDTIME) {
|
||||
// Time is valid, set GpsTime
|
||||
GPSTimeData GpsTime;
|
||||
|
||||
GpsTime.Year = pvt->year;
|
||||
GpsTime.Month = pvt->month;
|
||||
GpsTime.Day = pvt->day;
|
||||
GpsTime.Hour = pvt->hour;
|
||||
GpsTime.Minute = pvt->min;
|
||||
GpsTime.Second = pvt->sec;
|
||||
|
||||
GPSTimeSet(&GpsTime);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
void parse_ubx_nav_timeutc(struct UBX_NAV_TIMEUTC *timeutc)
|
||||
{
|
||||
@ -283,8 +325,8 @@ void parse_ubx_nav_svinfo(struct UBX_NAV_SVINFO *svinfo)
|
||||
svdata.SatsInView = 0;
|
||||
for (chan = 0; chan < svinfo->numCh; chan++) {
|
||||
if (svdata.SatsInView < GPSSATELLITES_PRN_NUMELEM) {
|
||||
svdata.Azimuth[svdata.SatsInView] = (float)svinfo->sv[chan].azim;
|
||||
svdata.Elevation[svdata.SatsInView] = (float)svinfo->sv[chan].elev;
|
||||
svdata.Azimuth[svdata.SatsInView] = svinfo->sv[chan].azim;
|
||||
svdata.Elevation[svdata.SatsInView] = svinfo->sv[chan].elev;
|
||||
svdata.PRN[svdata.SatsInView] = svinfo->sv[chan].svid;
|
||||
svdata.SNR[svdata.SatsInView] = svinfo->sv[chan].cno;
|
||||
svdata.SatsInView++;
|
||||
@ -292,8 +334,8 @@ void parse_ubx_nav_svinfo(struct UBX_NAV_SVINFO *svinfo)
|
||||
}
|
||||
// fill remaining slots (if any)
|
||||
for (chan = svdata.SatsInView; chan < GPSSATELLITES_PRN_NUMELEM; chan++) {
|
||||
svdata.Azimuth[chan] = (float)0.0f;
|
||||
svdata.Elevation[chan] = (float)0.0f;
|
||||
svdata.Azimuth[chan] = 0;
|
||||
svdata.Elevation[chan] = 0;
|
||||
svdata.PRN[chan] = 0;
|
||||
svdata.SNR[chan] = 0;
|
||||
}
|
||||
@ -308,26 +350,51 @@ void parse_ubx_nav_svinfo(struct UBX_NAV_SVINFO *svinfo)
|
||||
uint32_t parse_ubx_message(struct UBXPacket *ubx, GPSPositionSensorData *GpsPosition)
|
||||
{
|
||||
uint32_t id = 0;
|
||||
static uint32_t lastPvtTime = 0;
|
||||
static bool ubxInitialized = false;
|
||||
|
||||
if (!ubxInitialized) {
|
||||
// initialize dop values. If no DOP sentence is received it is safer to initialize them to a high value rather than 0.
|
||||
GpsPosition->HDOP = 99.99f;
|
||||
GpsPosition->PDOP = 99.99f;
|
||||
GpsPosition->VDOP = 99.99f;
|
||||
ubxInitialized = true;
|
||||
}
|
||||
// is it using PVT?
|
||||
bool usePvt = (lastPvtTime) && (PIOS_DELAY_GetuSSince(lastPvtTime) < UBX_PVT_TIMEOUT * 1000);
|
||||
|
||||
switch (ubx->header.class) {
|
||||
case UBX_CLASS_NAV:
|
||||
if (!usePvt) {
|
||||
// Set of messages to be decoded when not using pvt
|
||||
switch (ubx->header.id) {
|
||||
case UBX_ID_POSLLH:
|
||||
parse_ubx_nav_posllh(&ubx->payload.nav_posllh, GpsPosition);
|
||||
break;
|
||||
case UBX_ID_SOL:
|
||||
parse_ubx_nav_sol(&ubx->payload.nav_sol, GpsPosition);
|
||||
break;
|
||||
case UBX_ID_VELNED:
|
||||
parse_ubx_nav_velned(&ubx->payload.nav_velned, GpsPosition);
|
||||
break;
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
case UBX_ID_TIMEUTC:
|
||||
parse_ubx_nav_timeutc(&ubx->payload.nav_timeutc);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
// messages used always
|
||||
switch (ubx->header.id) {
|
||||
case UBX_ID_POSLLH:
|
||||
parse_ubx_nav_posllh(&ubx->payload.nav_posllh, GpsPosition);
|
||||
break;
|
||||
case UBX_ID_DOP:
|
||||
parse_ubx_nav_dop(&ubx->payload.nav_dop, GpsPosition);
|
||||
break;
|
||||
case UBX_ID_SOL:
|
||||
parse_ubx_nav_sol(&ubx->payload.nav_sol, GpsPosition);
|
||||
break;
|
||||
case UBX_ID_VELNED:
|
||||
parse_ubx_nav_velned(&ubx->payload.nav_velned, GpsPosition);
|
||||
|
||||
case UBX_ID_PVT:
|
||||
parse_ubx_nav_pvt(&ubx->payload.nav_pvt, GpsPosition);
|
||||
lastPvtTime = PIOS_DELAY_GetuS();
|
||||
break;
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
case UBX_ID_TIMEUTC:
|
||||
parse_ubx_nav_timeutc(&ubx->payload.nav_timeutc);
|
||||
break;
|
||||
case UBX_ID_SVINFO:
|
||||
parse_ubx_nav_svinfo(&ubx->payload.nav_svinfo);
|
||||
break;
|
||||
@ -335,6 +402,7 @@ uint32_t parse_ubx_message(struct UBXPacket *ubx, GPSPositionSensorData *GpsPosi
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
if (msgtracker.msg_received == ALL_RECEIVED) {
|
||||
GPSPositionSensorSet(GpsPosition);
|
||||
msgtracker.msg_received = NONE_RECEIVED;
|
||||
|
@ -51,6 +51,7 @@
|
||||
#define UBX_ID_VELNED 0x12
|
||||
#define UBX_ID_TIMEUTC 0x21
|
||||
#define UBX_ID_SVINFO 0x30
|
||||
#define UBX_ID_PVT 0x07
|
||||
|
||||
// private structures
|
||||
|
||||
@ -156,6 +157,59 @@ struct UBX_NAV_TIMEUTC {
|
||||
uint8_t valid; // Validity Flags
|
||||
};
|
||||
|
||||
#define PVT_VALID_VALIDDATE 0x01
|
||||
#define PVT_VALID_VALIDTIME 0x02
|
||||
#define PVT_VALID_FULLYRESOLVED 0x04
|
||||
|
||||
#define PVT_FIX_TYPE_NO_FIX 0
|
||||
#define PVT_FIX_TYPE_DEAD_RECKON 0x01 // Dead Reckoning only
|
||||
#define PVT_FIX_TYPE_2D 0x02 // 2D-Fix
|
||||
#define PVT_FIX_TYPE_3D 0x03 // 3D-Fix
|
||||
#define PVT_FIX_TYPE_GNSS_DEAD_RECKON 0x04 // GNSS + dead reckoning combined
|
||||
#define PVT_FIX_TYPE_TIME_ONLY 0x05 // Time only fix
|
||||
|
||||
#define PVT_FLAGS_GNSSFIX_OK (1 << 0)
|
||||
#define PVT_FLAGS_DIFFSOLN (1 << 1)
|
||||
#define PVT_FLAGS_PSMSTATE_ENABLED (1 << 2)
|
||||
#define PVT_FLAGS_PSMSTATE_ACQUISITION (2 << 2)
|
||||
#define PVT_FLAGS_PSMSTATE_TRACKING (3 << 2)
|
||||
#define PVT_FLAGS_PSMSTATE_PO_TRACKING (4 << 2)
|
||||
#define PVT_FLAGS_PSMSTATE_INACTIVE (5 << 2)
|
||||
|
||||
// PVT Navigation Position Velocity Time Solution
|
||||
struct UBX_NAV_PVT {
|
||||
uint32_t iTOW;
|
||||
uint16_t year;
|
||||
uint8_t month;
|
||||
uint8_t day;
|
||||
uint8_t hour;
|
||||
uint8_t min;
|
||||
uint8_t sec;
|
||||
uint8_t valid;
|
||||
uint32_t tAcc;
|
||||
int32_t nano;
|
||||
uint8_t fixType;
|
||||
uint8_t flags;
|
||||
uint8_t reserved1;
|
||||
uint8_t numSV;
|
||||
int32_t lon;
|
||||
int32_t lat;
|
||||
int32_t height;
|
||||
int32_t hMSL;
|
||||
uint32_t hAcc;
|
||||
uint32_t vAcc;
|
||||
int32_t velN;
|
||||
int32_t velE;
|
||||
int32_t velD;
|
||||
int32_t gSpeed;
|
||||
int32_t heading;
|
||||
uint32_t sAcc;
|
||||
uint32_t headingAcc;
|
||||
uint16_t pDOP;
|
||||
uint16_t reserved2;
|
||||
uint32_t reserved3;
|
||||
} __attribute__((packed));
|
||||
|
||||
// Space Vehicle (SV) Information
|
||||
|
||||
// Single SV information block
|
||||
@ -198,6 +252,7 @@ typedef union {
|
||||
struct UBX_NAV_DOP nav_dop;
|
||||
struct UBX_NAV_SOL nav_sol;
|
||||
struct UBX_NAV_VELNED nav_velned;
|
||||
struct UBX_NAV_PVT nav_pvt;
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
struct UBX_NAV_TIMEUTC nav_timeutc;
|
||||
struct UBX_NAV_SVINFO nav_svinfo;
|
||||
|
@ -35,6 +35,7 @@
|
||||
#include <accessorydesired.h>
|
||||
#include <flightstatus.h>
|
||||
#include <flightmodesettings.h>
|
||||
#include <stabilizationdesired.h>
|
||||
|
||||
// Private constants
|
||||
#define ARMED_THRESHOLD 0.50f
|
||||
@ -267,6 +268,8 @@ static bool okToArm(void)
|
||||
}
|
||||
}
|
||||
|
||||
StabilizationDesiredStabilizationModeData stabDesired;
|
||||
|
||||
uint8_t flightMode;
|
||||
FlightStatusFlightModeGet(&flightMode);
|
||||
switch (flightMode) {
|
||||
@ -277,8 +280,14 @@ static bool okToArm(void)
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
|
||||
return true;
|
||||
|
||||
// Prevent arming if unsafe due to the current Thrust Mode
|
||||
StabilizationDesiredStabilizationModeGet(&stabDesired);
|
||||
if (stabDesired.Thrust == STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD ||
|
||||
stabDesired.Thrust == STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEVARIO) {
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
|
@ -69,19 +69,24 @@
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3)
|
||||
#define SENSOR_PERIOD 2
|
||||
|
||||
#define ZERO_ROT_ANGLE 0.00001f
|
||||
// Private types
|
||||
|
||||
|
||||
// Private functions
|
||||
static void SensorsTask(void *parameters);
|
||||
static void settingsUpdatedCb(UAVObjEvent *objEv);
|
||||
// static void magOffsetEstimation(MagSensorData *mag);
|
||||
|
||||
// Private variables
|
||||
static xTaskHandle sensorsTaskHandle;
|
||||
RevoCalibrationData cal;
|
||||
AccelGyroSettingsData agcal;
|
||||
|
||||
#ifdef PIOS_INCLUDE_HMC5X83
|
||||
#include <pios_hmc5x83.h>
|
||||
extern pios_hmc5x83_dev_t onboard_mag;
|
||||
#endif
|
||||
|
||||
// These values are initialized by settings but can be updated by the attitude algorithm
|
||||
|
||||
static float mag_bias[3] = { 0, 0, 0 };
|
||||
@ -200,8 +205,8 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
mag_test = PIOS_HMC5883_Test();
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
mag_test = PIOS_HMC5x83_Test(onboard_mag);
|
||||
#else
|
||||
mag_test = 0;
|
||||
#endif
|
||||
@ -409,11 +414,11 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
|
||||
// Because most crafts wont get enough information from gravity to zero yaw gyro, we try
|
||||
// and make it average zero (weakly)
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
MagSensorData mag;
|
||||
if (PIOS_HMC5883_NewDataAvailable() || PIOS_DELAY_DiffuS(mag_update_time) > 150000) {
|
||||
if (PIOS_HMC5x83_NewDataAvailable(onboard_mag) || PIOS_DELAY_DiffuS(mag_update_time) > 150000) {
|
||||
int16_t values[3];
|
||||
PIOS_HMC5883_ReadMag(values);
|
||||
PIOS_HMC5x83_ReadMag(onboard_mag, values);
|
||||
float mags[3] = { (float)values[1] - mag_bias[0],
|
||||
(float)values[0] - mag_bias[1],
|
||||
-(float)values[2] - mag_bias[2] };
|
||||
@ -428,7 +433,7 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
|
||||
MagSensorSet(&mag);
|
||||
mag_update_time = PIOS_DELAY_GetRaw();
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_HMC5883) */
|
||||
#endif /* if defined(PIOS_INCLUDE_HMC5X83) */
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS);
|
||||
@ -461,20 +466,35 @@ static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent *objEv)
|
||||
AttitudeSettingsGet(&attitudeSettings);
|
||||
|
||||
// Indicates not to expend cycles on rotation
|
||||
if (fabsf(attitudeSettings.BoardRotation.Roll) < 0.00001f
|
||||
&& fabsf(attitudeSettings.BoardRotation.Pitch) < 0.00001f &&
|
||||
fabsf(attitudeSettings.BoardRotation.Yaw) < 0.00001f) {
|
||||
if (fabsf(attitudeSettings.BoardRotation.Roll) < ZERO_ROT_ANGLE
|
||||
&& fabsf(attitudeSettings.BoardRotation.Pitch) < ZERO_ROT_ANGLE &&
|
||||
fabsf(attitudeSettings.BoardRotation.Yaw) < ZERO_ROT_ANGLE) {
|
||||
rotate = 0;
|
||||
} else {
|
||||
rotate = 1;
|
||||
}
|
||||
float rotationQuat[4];
|
||||
|
||||
const float rpy[3] = { attitudeSettings.BoardRotation.Roll,
|
||||
attitudeSettings.BoardRotation.Pitch,
|
||||
attitudeSettings.BoardRotation.Yaw };
|
||||
RPY2Quaternion(rpy, rotationQuat);
|
||||
Quaternion2R(rotationQuat, R);
|
||||
|
||||
float rotationQuat[4];
|
||||
RPY2Quaternion(rpy, rotationQuat);
|
||||
|
||||
if (fabsf(attitudeSettings.BoardLevelTrim.Roll) > ZERO_ROT_ANGLE ||
|
||||
fabsf(attitudeSettings.BoardLevelTrim.Pitch) > ZERO_ROT_ANGLE) {
|
||||
float trimQuat[4];
|
||||
float sumQuat[4];
|
||||
rotate = 1;
|
||||
|
||||
const float trimRpy[3] = { attitudeSettings.BoardLevelTrim.Roll, attitudeSettings.BoardLevelTrim.Pitch, 0.0f };
|
||||
RPY2Quaternion(trimRpy, trimQuat);
|
||||
|
||||
quat_mult(rotationQuat, trimQuat, sumQuat);
|
||||
Quaternion2R(sumQuat, R);
|
||||
} else {
|
||||
Quaternion2R(rotationQuat, R);
|
||||
}
|
||||
matrix_mult_3x3f((float(*)[3])cast_struct_to_array(cal.mag_transform, cal.mag_transform.r0c0), R, mag_transform);
|
||||
}
|
||||
/**
|
||||
|
@ -221,7 +221,7 @@ static filterResult complementaryFilter(struct data *this, float gyro[3], float
|
||||
|
||||
// During initialization and
|
||||
if (this->first_run) {
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
// wait until mags have been updated
|
||||
if (!this->magUpdated) {
|
||||
return FILTERRESULT_ERROR;
|
||||
|
@ -205,6 +205,15 @@ static filterResult filter(stateFilter *self, stateEstimation *state)
|
||||
|
||||
this->work.updated |= state->updated;
|
||||
|
||||
// check magnetometer alarm, discard any magnetometer readings if not OK
|
||||
// during initialization phase (but let them through afterwards)
|
||||
SystemAlarmsAlarmData alarms;
|
||||
SystemAlarmsAlarmGet(&alarms);
|
||||
if (alarms.Magnetometer != SYSTEMALARMS_ALARM_OK && !this->inited) {
|
||||
UNSET_MASK(state->updated, SENSORUPDATES_mag);
|
||||
UNSET_MASK(this->work.updated, SENSORUPDATES_mag);
|
||||
}
|
||||
|
||||
// Get most recent data
|
||||
IMPORT_SENSOR_IF_UPDATED(gyro, 3);
|
||||
IMPORT_SENSOR_IF_UPDATED(accel, 3);
|
||||
@ -349,11 +358,7 @@ static filterResult filter(stateFilter *self, stateEstimation *state)
|
||||
INSCovariancePrediction(dT);
|
||||
|
||||
if (IS_SET(this->work.updated, SENSORUPDATES_mag)) {
|
||||
SystemAlarmsAlarmData alarms;
|
||||
SystemAlarmsAlarmGet(&alarms);
|
||||
if (alarms.Magnetometer == SYSTEMALARMS_ALARM_OK) {
|
||||
sensors |= MAG_SENSORS;
|
||||
}
|
||||
sensors |= MAG_SENSORS;
|
||||
}
|
||||
|
||||
if (IS_SET(this->work.updated, SENSORUPDATES_baro)) {
|
||||
|
@ -83,6 +83,7 @@
|
||||
// Private functions
|
||||
static void updatePIDs(UAVObjEvent *ev);
|
||||
static uint8_t update(float *var, float val);
|
||||
static uint8_t updateUint8(uint8_t *var, float val);
|
||||
static float scale(float val, float inMin, float inMax, float outMin, float outMax);
|
||||
|
||||
/**
|
||||
@ -226,6 +227,9 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
case TXPIDSETTINGS_PIDS_ROLLRATEILIMIT:
|
||||
needsUpdateBank |= update(&bank.RollRatePID.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLRATERESP:
|
||||
needsUpdateBank |= update(&bank.ManualRate.Roll, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLATTITUDEKP:
|
||||
needsUpdateBank |= update(&bank.RollPI.Kp, value);
|
||||
break;
|
||||
@ -235,6 +239,9 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
case TXPIDSETTINGS_PIDS_ROLLATTITUDEILIMIT:
|
||||
needsUpdateBank |= update(&bank.RollPI.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLATTITUDERESP:
|
||||
needsUpdateBank |= updateUint8(&bank.RollMax, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATEKP:
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.Kp, value);
|
||||
break;
|
||||
@ -247,6 +254,9 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATEILIMIT:
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHRATERESP:
|
||||
needsUpdateBank |= update(&bank.ManualRate.Pitch, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHATTITUDEKP:
|
||||
needsUpdateBank |= update(&bank.PitchPI.Kp, value);
|
||||
break;
|
||||
@ -256,6 +266,9 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
case TXPIDSETTINGS_PIDS_PITCHATTITUDEILIMIT:
|
||||
needsUpdateBank |= update(&bank.PitchPI.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_PITCHATTITUDERESP:
|
||||
needsUpdateBank |= updateUint8(&bank.PitchMax, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHRATEKP:
|
||||
needsUpdateBank |= update(&bank.RollRatePID.Kp, value);
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.Kp, value);
|
||||
@ -272,6 +285,10 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
needsUpdateBank |= update(&bank.RollRatePID.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.PitchRatePID.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHRATERESP:
|
||||
needsUpdateBank |= update(&bank.ManualRate.Roll, value);
|
||||
needsUpdateBank |= update(&bank.ManualRate.Pitch, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDEKP:
|
||||
needsUpdateBank |= update(&bank.RollPI.Kp, value);
|
||||
needsUpdateBank |= update(&bank.PitchPI.Kp, value);
|
||||
@ -284,6 +301,10 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
needsUpdateBank |= update(&bank.RollPI.ILimit, value);
|
||||
needsUpdateBank |= update(&bank.PitchPI.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDERESP:
|
||||
needsUpdateBank |= updateUint8(&bank.RollMax, value);
|
||||
needsUpdateBank |= updateUint8(&bank.PitchMax, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWRATEKP:
|
||||
needsUpdateBank |= update(&bank.YawRatePID.Kp, value);
|
||||
break;
|
||||
@ -296,6 +317,9 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
case TXPIDSETTINGS_PIDS_YAWRATEILIMIT:
|
||||
needsUpdateBank |= update(&bank.YawRatePID.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWRATERESP:
|
||||
needsUpdateBank |= update(&bank.ManualRate.Yaw, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWATTITUDEKP:
|
||||
needsUpdateBank |= update(&bank.YawPI.Kp, value);
|
||||
break;
|
||||
@ -305,6 +329,9 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
case TXPIDSETTINGS_PIDS_YAWATTITUDEILIMIT:
|
||||
needsUpdateBank |= update(&bank.YawPI.ILimit, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_YAWATTITUDERESP:
|
||||
needsUpdateBank |= updateUint8(&bank.YawMax, value);
|
||||
break;
|
||||
case TXPIDSETTINGS_PIDS_GYROTAU:
|
||||
needsUpdateStab |= update(&stab.GyroTau, value);
|
||||
break;
|
||||
@ -389,6 +416,21 @@ static uint8_t update(float *var, float val)
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Updates var using val if needed.
|
||||
* \returns 1 if updated, 0 otherwise
|
||||
*/
|
||||
static uint8_t updateUint8(uint8_t *var, float val)
|
||||
{
|
||||
uint8_t roundedVal = (uint8_t)roundf(val);
|
||||
|
||||
if (*var != roundedVal) {
|
||||
*var = roundedVal;
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
@ -190,7 +190,8 @@ static void vtolPathFollowerTask(__attribute__((unused)) void *parameters)
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_HEXA) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX)
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_OCTO)
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP)
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_TRI)) {
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_TRI) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_HEXAH)
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_OCTOX)) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE, SYSTEMALARMS_ALARM_WARNING);
|
||||
vTaskDelay(1000);
|
||||
continue;
|
||||
|
@ -49,6 +49,9 @@ static xSemaphoreHandle mutex = 0;
|
||||
#endif
|
||||
|
||||
static bool logging_enabled = false;
|
||||
#define MAX_CONSECUTIVE_FAILS_COUNT 10
|
||||
static bool log_is_full = false;
|
||||
static uint8_t fails_count = 0;
|
||||
static uint16_t flightnum = 0;
|
||||
static uint16_t lognum = 0;
|
||||
static DebugLogEntryData *buffer = 0;
|
||||
@ -56,8 +59,16 @@ static DebugLogEntryData *buffer = 0;
|
||||
static DebugLogEntryData staticbuffer;
|
||||
#endif
|
||||
|
||||
/* Private Function Prototypes */
|
||||
#define LOG_ENTRY_MAX_DATA_SIZE (sizeof(((DebugLogEntryData *)0)->Data))
|
||||
#define LOG_ENTRY_HEADER_SIZE (sizeof(DebugLogEntryData) - LOG_ENTRY_MAX_DATA_SIZE)
|
||||
// build the obj_id as a DEBUGLOGENTRY ID with least significant byte zeroed and filled with flight number
|
||||
#define LOG_GET_FLIGHT_OBJID(x) ((DEBUGLOGENTRY_OBJID & ~0xFF) | (x & 0xFF))
|
||||
|
||||
static uint32_t used_buffer_space = 0;
|
||||
|
||||
/* Private Function Prototypes */
|
||||
static void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data);
|
||||
static bool write_current_buffer();
|
||||
/**
|
||||
* @brief Initialize the log facility
|
||||
*/
|
||||
@ -75,9 +86,12 @@ void PIOS_DEBUGLOG_Initialize()
|
||||
return;
|
||||
}
|
||||
mutexlock();
|
||||
lognum = 0;
|
||||
flightnum = 0;
|
||||
while (PIOS_FLASHFS_ObjLoad(pios_user_fs_id, flightnum * 256, lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) {
|
||||
lognum = 0;
|
||||
flightnum = 0;
|
||||
fails_count = 0;
|
||||
used_buffer_space = 0;
|
||||
log_is_full = false;
|
||||
while (PIOS_FLASHFS_ObjLoad(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) {
|
||||
flightnum++;
|
||||
}
|
||||
mutexunlock();
|
||||
@ -90,6 +104,11 @@ void PIOS_DEBUGLOG_Initialize()
|
||||
*/
|
||||
void PIOS_DEBUGLOG_Enable(uint8_t enabled)
|
||||
{
|
||||
// increase the flight num as soon as logging is disabled
|
||||
if (logging_enabled && !enabled) {
|
||||
flightnum++;
|
||||
lognum = 0;
|
||||
}
|
||||
logging_enabled = enabled;
|
||||
}
|
||||
|
||||
@ -103,30 +122,13 @@ void PIOS_DEBUGLOG_Enable(uint8_t enabled)
|
||||
*/
|
||||
void PIOS_DEBUGLOG_UAVObject(uint32_t objid, uint16_t instid, size_t size, uint8_t *data)
|
||||
{
|
||||
if (!logging_enabled || !buffer) {
|
||||
if (!logging_enabled || !buffer || log_is_full) {
|
||||
return;
|
||||
}
|
||||
mutexlock();
|
||||
buffer->Flight = flightnum;
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
buffer->FlightTime = xTaskGetTickCount() * portTICK_RATE_MS;
|
||||
#else
|
||||
buffer->FlightTime = 0;
|
||||
#endif
|
||||
buffer->Entry = lognum;
|
||||
buffer->Type = DEBUGLOGENTRY_TYPE_UAVOBJECT;
|
||||
buffer->ObjectID = objid;
|
||||
buffer->InstanceID = instid;
|
||||
if (size > sizeof(buffer->Data)) {
|
||||
size = sizeof(buffer->Data);
|
||||
}
|
||||
buffer->Size = size;
|
||||
memset(buffer->Data, 0xff, sizeof(buffer->Data));
|
||||
memcpy(buffer->Data, data, size);
|
||||
|
||||
if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, flightnum * 256, lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) {
|
||||
lognum++;
|
||||
}
|
||||
enqueue_data(objid, instid, size, data);
|
||||
|
||||
mutexunlock();
|
||||
}
|
||||
/**
|
||||
@ -137,27 +139,30 @@ void PIOS_DEBUGLOG_UAVObject(uint32_t objid, uint16_t instid, size_t size, uint8
|
||||
*/
|
||||
void PIOS_DEBUGLOG_Printf(char *format, ...)
|
||||
{
|
||||
if (!logging_enabled || !buffer) {
|
||||
if (!logging_enabled || !buffer || log_is_full) {
|
||||
return;
|
||||
}
|
||||
|
||||
va_list args;
|
||||
va_start(args, format);
|
||||
mutexlock();
|
||||
// flush any pending buffer before writing debug text
|
||||
if (used_buffer_space) {
|
||||
write_current_buffer();
|
||||
}
|
||||
memset(buffer->Data, 0xff, sizeof(buffer->Data));
|
||||
vsnprintf((char *)buffer->Data, sizeof(buffer->Data), (char *)format, args);
|
||||
buffer->Flight = flightnum;
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
buffer->FlightTime = xTaskGetTickCount() * portTICK_RATE_MS;
|
||||
#else
|
||||
buffer->FlightTime = 0;
|
||||
#endif
|
||||
|
||||
buffer->FlightTime = PIOS_DELAY_GetuS();
|
||||
|
||||
buffer->Entry = lognum;
|
||||
buffer->Type = DEBUGLOGENTRY_TYPE_TEXT;
|
||||
buffer->ObjectID = 0;
|
||||
buffer->InstanceID = 0;
|
||||
buffer->Size = strlen((const char *)buffer->Data);
|
||||
|
||||
if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, flightnum * 256, lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) {
|
||||
if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) {
|
||||
lognum++;
|
||||
}
|
||||
mutexunlock();
|
||||
@ -179,7 +184,7 @@ void PIOS_DEBUGLOG_Printf(char *format, ...)
|
||||
int32_t PIOS_DEBUGLOG_Read(void *mybuffer, uint16_t flight, uint16_t inst)
|
||||
{
|
||||
PIOS_Assert(mybuffer);
|
||||
return PIOS_FLASHFS_ObjLoad(pios_user_fs_id, flight * 256, inst, (uint8_t *)mybuffer, sizeof(DebugLogEntryData));
|
||||
return PIOS_FLASHFS_ObjLoad(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flight), inst, (uint8_t *)mybuffer, sizeof(DebugLogEntryData));
|
||||
}
|
||||
|
||||
/**
|
||||
@ -214,11 +219,68 @@ void PIOS_DEBUGLOG_Format(void)
|
||||
{
|
||||
mutexlock();
|
||||
PIOS_FLASHFS_Format(pios_user_fs_id);
|
||||
lognum = 0;
|
||||
flightnum = 0;
|
||||
lognum = 0;
|
||||
flightnum = 0;
|
||||
log_is_full = false;
|
||||
fails_count = 0;
|
||||
used_buffer_space = 0;
|
||||
mutexunlock();
|
||||
}
|
||||
|
||||
void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data)
|
||||
{
|
||||
DebugLogEntryData *entry;
|
||||
|
||||
// start a new block
|
||||
if (!used_buffer_space) {
|
||||
entry = buffer;
|
||||
memset(buffer->Data, 0xff, sizeof(buffer->Data));
|
||||
used_buffer_space += size;
|
||||
} else {
|
||||
// if an instance is being filled and there is enough space, does enqueues new data.
|
||||
if (used_buffer_space + size + LOG_ENTRY_HEADER_SIZE > LOG_ENTRY_MAX_DATA_SIZE) {
|
||||
buffer->Type = DEBUGLOGENTRY_TYPE_MULTIPLEUAVOBJECTS;
|
||||
if (!write_current_buffer()) {
|
||||
return;
|
||||
}
|
||||
entry = buffer;
|
||||
memset(buffer->Data, 0xff, sizeof(buffer->Data));
|
||||
used_buffer_space += size;
|
||||
} else {
|
||||
entry = (DebugLogEntryData *)&buffer->Data[used_buffer_space];
|
||||
used_buffer_space += size + LOG_ENTRY_HEADER_SIZE;
|
||||
}
|
||||
}
|
||||
|
||||
entry->Flight = flightnum;
|
||||
entry->FlightTime = PIOS_DELAY_GetuS();
|
||||
entry->Entry = lognum;
|
||||
entry->Type = DEBUGLOGENTRY_TYPE_UAVOBJECT;
|
||||
entry->ObjectID = objid;
|
||||
entry->InstanceID = instid;
|
||||
if (size > sizeof(buffer->Data)) {
|
||||
size = sizeof(buffer->Data);
|
||||
}
|
||||
entry->Size = size;
|
||||
|
||||
memcpy(entry->Data, data, size);
|
||||
}
|
||||
|
||||
bool write_current_buffer()
|
||||
{
|
||||
// not enough space, write the block and start a new one
|
||||
if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) {
|
||||
lognum++;
|
||||
fails_count = 0;
|
||||
used_buffer_space = 0;
|
||||
} else {
|
||||
if (fails_count++ > MAX_CONSECUTIVE_FAILS_COUNT) {
|
||||
log_is_full = true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
|
@ -75,13 +75,16 @@ struct jedec_flash_dev {
|
||||
enum pios_jedec_dev_magic magic;
|
||||
};
|
||||
|
||||
#define FLASH_FAST_PRESCALER PIOS_SPI_PRESCALER_2
|
||||
#define FLASH_PRESCALER PIOS_SPI_PRESCALER_4
|
||||
|
||||
// ! Private functions
|
||||
static int32_t PIOS_Flash_Jedec_Validate(struct jedec_flash_dev *flash_dev);
|
||||
static struct jedec_flash_dev *PIOS_Flash_Jedec_alloc(void);
|
||||
|
||||
static int32_t PIOS_Flash_Jedec_ReadID(struct jedec_flash_dev *flash_dev);
|
||||
static int32_t PIOS_Flash_Jedec_ReadStatus(struct jedec_flash_dev *flash_dev);
|
||||
static int32_t PIOS_Flash_Jedec_ClaimBus(struct jedec_flash_dev *flash_dev);
|
||||
static int32_t PIOS_Flash_Jedec_ClaimBus(struct jedec_flash_dev *flash_dev, bool fast);
|
||||
static int32_t PIOS_Flash_Jedec_ReleaseBus(struct jedec_flash_dev *flash_dev);
|
||||
static int32_t PIOS_Flash_Jedec_WriteEnable(struct jedec_flash_dev *flash_dev);
|
||||
static int32_t PIOS_Flash_Jedec_Busy(struct jedec_flash_dev *flash_dev);
|
||||
@ -166,12 +169,12 @@ int32_t PIOS_Flash_Jedec_Init(uintptr_t *flash_id, uint32_t spi_id, uint32_t sla
|
||||
* @brief Claim the SPI bus for flash use and assert CS pin
|
||||
* @return 0 for sucess, -1 for failure to get semaphore
|
||||
*/
|
||||
static int32_t PIOS_Flash_Jedec_ClaimBus(struct jedec_flash_dev *flash_dev)
|
||||
static int32_t PIOS_Flash_Jedec_ClaimBus(struct jedec_flash_dev *flash_dev, bool fast)
|
||||
{
|
||||
if (PIOS_SPI_ClaimBus(flash_dev->spi_id) < 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
PIOS_SPI_SetClockSpeed(flash_dev->spi_id, fast ? FLASH_FAST_PRESCALER : FLASH_PRESCALER);
|
||||
PIOS_SPI_RC_PinSet(flash_dev->spi_id, flash_dev->slave_num, 0);
|
||||
flash_dev->claimed = true;
|
||||
|
||||
@ -209,7 +212,7 @@ static int32_t PIOS_Flash_Jedec_Busy(struct jedec_flash_dev *flash_dev)
|
||||
*/
|
||||
static int32_t PIOS_Flash_Jedec_WriteEnable(struct jedec_flash_dev *flash_dev)
|
||||
{
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev) != 0) {
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev, true) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -226,7 +229,7 @@ static int32_t PIOS_Flash_Jedec_WriteEnable(struct jedec_flash_dev *flash_dev)
|
||||
*/
|
||||
static int32_t PIOS_Flash_Jedec_ReadStatus(struct jedec_flash_dev *flash_dev)
|
||||
{
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev) < 0) {
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev, true) < 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -247,7 +250,7 @@ static int32_t PIOS_Flash_Jedec_ReadStatus(struct jedec_flash_dev *flash_dev)
|
||||
*/
|
||||
static int32_t PIOS_Flash_Jedec_ReadID(struct jedec_flash_dev *flash_dev)
|
||||
{
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev) < 0) {
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev, true) < 0) {
|
||||
return -2;
|
||||
}
|
||||
|
||||
@ -354,7 +357,7 @@ static int32_t PIOS_Flash_Jedec_EraseSector(uintptr_t flash_id, uint32_t addr)
|
||||
return ret;
|
||||
}
|
||||
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev) != 0) {
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev, true) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -368,7 +371,7 @@ static int32_t PIOS_Flash_Jedec_EraseSector(uintptr_t flash_id, uint32_t addr)
|
||||
// Keep polling when bus is busy too
|
||||
while (PIOS_Flash_Jedec_Busy(flash_dev) != 0) {
|
||||
#if defined(FLASH_FREERTOS)
|
||||
vTaskDelay(1);
|
||||
vTaskDelay(2);
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -394,7 +397,7 @@ static int32_t PIOS_Flash_Jedec_EraseChip(uintptr_t flash_id)
|
||||
return ret;
|
||||
}
|
||||
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev) != 0) {
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev, true) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -455,16 +458,14 @@ static int32_t PIOS_Flash_Jedec_WriteData(uintptr_t flash_id, uint32_t addr, uin
|
||||
if (((addr & 0xff) + len) > 0x100) {
|
||||
return -3;
|
||||
}
|
||||
|
||||
if ((ret = PIOS_Flash_Jedec_WriteEnable(flash_dev)) != 0) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Execute write page command and clock in address. Keep CS asserted */
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev) != 0) {
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev, true) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (PIOS_SPI_TransferBlock(flash_dev->spi_id, out, NULL, sizeof(out), NULL) < 0) {
|
||||
PIOS_Flash_Jedec_ReleaseBus(flash_dev);
|
||||
return -1;
|
||||
@ -486,7 +487,7 @@ static int32_t PIOS_Flash_Jedec_WriteData(uintptr_t flash_id, uint32_t addr, uin
|
||||
#else
|
||||
|
||||
// Query status this way to prevent accel chip locking us out
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev) < 0) {
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev, true) < 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -536,13 +537,12 @@ static int32_t PIOS_Flash_Jedec_WriteChunks(uintptr_t flash_id, uint32_t addr, s
|
||||
if (((addr & 0xff) + len) > 0x100) {
|
||||
return -3;
|
||||
}
|
||||
|
||||
if ((ret = PIOS_Flash_Jedec_WriteEnable(flash_dev)) != 0) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Execute write page command and clock in address. Keep CS asserted */
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev) != 0) {
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev, true) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -582,17 +582,29 @@ static int32_t PIOS_Flash_Jedec_ReadData(uintptr_t flash_id, uint32_t addr, uint
|
||||
if (PIOS_Flash_Jedec_Validate(flash_dev) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev) == -1) {
|
||||
bool fast_read = flash_dev->cfg->fast_read != 0;
|
||||
if (PIOS_Flash_Jedec_ClaimBus(flash_dev, fast_read) == -1) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Execute read command and clock in address. Keep CS asserted */
|
||||
uint8_t out[] = { JEDEC_READ_DATA, (addr >> 16) & 0xff, (addr >> 8) & 0xff, addr & 0xff };
|
||||
|
||||
if (PIOS_SPI_TransferBlock(flash_dev->spi_id, out, NULL, sizeof(out), NULL) < 0) {
|
||||
PIOS_Flash_Jedec_ReleaseBus(flash_dev);
|
||||
return -2;
|
||||
if (!fast_read) {
|
||||
uint8_t out[] = { JEDEC_READ_DATA, (addr >> 16) & 0xff, (addr >> 8) & 0xff, addr & 0xff };
|
||||
if (PIOS_SPI_TransferBlock(flash_dev->spi_id, out, NULL, sizeof(out), NULL) < 0) {
|
||||
PIOS_Flash_Jedec_ReleaseBus(flash_dev);
|
||||
return -2;
|
||||
}
|
||||
} else {
|
||||
uint8_t cmdlen = flash_dev->cfg->fast_read_dummy_bytes + 4;
|
||||
uint8_t out[cmdlen];
|
||||
memset(out, 0x0, cmdlen);
|
||||
out[0] = flash_dev->cfg->fast_read;
|
||||
out[1] = (addr >> 16) & 0xff;
|
||||
out[2] = (addr >> 8) & 0xff;
|
||||
out[3] = addr & 0xff;
|
||||
if (PIOS_SPI_TransferBlock(flash_dev->spi_id, out, NULL, cmdlen, NULL) < 0) {
|
||||
PIOS_Flash_Jedec_ReleaseBus(flash_dev);
|
||||
return -2;
|
||||
}
|
||||
}
|
||||
|
||||
/* Copy the transfer data to the buffer */
|
||||
|
@ -1,425 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_HMC5883 HMC5883 Functions
|
||||
* @brief Deals with the hardware interface to the magnetometers
|
||||
* @{
|
||||
* @file pios_hmc5883.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief HMC5883 Magnetic Sensor Functions from AHRS
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "pios.h"
|
||||
|
||||
#ifdef PIOS_INCLUDE_HMC5883
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Local Types */
|
||||
|
||||
/* Local Variables */
|
||||
volatile bool pios_hmc5883_data_ready;
|
||||
|
||||
static int32_t PIOS_HMC5883_Config(const struct pios_hmc5883_cfg *cfg);
|
||||
static int32_t PIOS_HMC5883_Read(uint8_t address, uint8_t *buffer, uint8_t len);
|
||||
static int32_t PIOS_HMC5883_Write(uint8_t address, uint8_t buffer);
|
||||
|
||||
static const struct pios_hmc5883_cfg *dev_cfg;
|
||||
|
||||
/**
|
||||
* @brief Initialize the HMC5883 magnetometer sensor.
|
||||
* @return none
|
||||
*/
|
||||
void PIOS_HMC5883_Init(const struct pios_hmc5883_cfg *cfg)
|
||||
{
|
||||
dev_cfg = cfg; // store config before enabling interrupt
|
||||
|
||||
#ifdef PIOS_HMC5883_HAS_GPIOS
|
||||
PIOS_EXTI_Init(cfg->exti_cfg);
|
||||
#endif
|
||||
|
||||
int32_t val = PIOS_HMC5883_Config(cfg);
|
||||
|
||||
PIOS_Assert(val == 0);
|
||||
|
||||
pios_hmc5883_data_ready = false;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initialize the HMC5883 magnetometer sensor
|
||||
* \return none
|
||||
* \param[in] PIOS_HMC5883_ConfigTypeDef struct to be used to configure sensor.
|
||||
*
|
||||
* CTRL_REGA: Control Register A
|
||||
* Read Write
|
||||
* Default value: 0x10
|
||||
* 7:5 0 These bits must be cleared for correct operation.
|
||||
* 4:2 DO2-DO0: Data Output Rate Bits
|
||||
* DO2 | DO1 | DO0 | Minimum Data Output Rate (Hz)
|
||||
* ------------------------------------------------------
|
||||
* 0 | 0 | 0 | 0.75
|
||||
* 0 | 0 | 1 | 1.5
|
||||
* 0 | 1 | 0 | 3
|
||||
* 0 | 1 | 1 | 7.5
|
||||
* 1 | 0 | 0 | 15 (default)
|
||||
* 1 | 0 | 1 | 30
|
||||
* 1 | 1 | 0 | 75
|
||||
* 1 | 1 | 1 | Not Used
|
||||
* 1:0 MS1-MS0: Measurement Configuration Bits
|
||||
* MS1 | MS0 | MODE
|
||||
* ------------------------------
|
||||
* 0 | 0 | Normal
|
||||
* 0 | 1 | Positive Bias
|
||||
* 1 | 0 | Negative Bias
|
||||
* 1 | 1 | Not Used
|
||||
*
|
||||
* CTRL_REGB: Control RegisterB
|
||||
* Read Write
|
||||
* Default value: 0x20
|
||||
* 7:5 GN2-GN0: Gain Configuration Bits.
|
||||
* GN2 | GN1 | GN0 | Mag Input | Gain | Output Range
|
||||
* | | | Range[Ga] | [LSB/mGa] |
|
||||
* ------------------------------------------------------
|
||||
* 0 | 0 | 0 | ±0.88Ga | 1370 | 0xF8000x07FF (-2048:2047)
|
||||
* 0 | 0 | 1 | ±1.3Ga (def) | 1090 | 0xF8000x07FF (-2048:2047)
|
||||
* 0 | 1 | 0 | ±1.9Ga | 820 | 0xF8000x07FF (-2048:2047)
|
||||
* 0 | 1 | 1 | ±2.5Ga | 660 | 0xF8000x07FF (-2048:2047)
|
||||
* 1 | 0 | 0 | ±4.0Ga | 440 | 0xF8000x07FF (-2048:2047)
|
||||
* 1 | 0 | 1 | ±4.7Ga | 390 | 0xF8000x07FF (-2048:2047)
|
||||
* 1 | 1 | 0 | ±5.6Ga | 330 | 0xF8000x07FF (-2048:2047)
|
||||
* 1 | 1 | 1 | ±8.1Ga | 230 | 0xF8000x07FF (-2048:2047)
|
||||
* |Not recommended|
|
||||
*
|
||||
* 4:0 CRB4-CRB: 0 This bit must be cleared for correct operation.
|
||||
*
|
||||
* _MODE_REG: Mode Register
|
||||
* Read Write
|
||||
* Default value: 0x02
|
||||
* 7:2 0 These bits must be cleared for correct operation.
|
||||
* 1:0 MD1-MD0: Mode Select Bits
|
||||
* MS1 | MS0 | MODE
|
||||
* ------------------------------
|
||||
* 0 | 0 | Continuous-Conversion Mode.
|
||||
* 0 | 1 | Single-Conversion Mode
|
||||
* 1 | 0 | Negative Bias
|
||||
* 1 | 1 | Sleep Mode
|
||||
*/
|
||||
static uint8_t CTRLB = 0x00;
|
||||
static int32_t PIOS_HMC5883_Config(const struct pios_hmc5883_cfg *cfg)
|
||||
{
|
||||
uint8_t CTRLA = 0x00;
|
||||
uint8_t MODE = 0x00;
|
||||
|
||||
CTRLB = 0;
|
||||
|
||||
CTRLA |= (uint8_t)(cfg->M_ODR | cfg->Meas_Conf);
|
||||
CTRLB |= (uint8_t)(cfg->Gain);
|
||||
MODE |= (uint8_t)(cfg->Mode);
|
||||
|
||||
// CRTL_REGA
|
||||
if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A, CTRLA) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
// CRTL_REGB
|
||||
if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B, CTRLB) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Mode register
|
||||
if (PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, MODE) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read current X, Z, Y values (in that order)
|
||||
* \param[out] int16_t array of size 3 to store X, Z, and Y magnetometer readings
|
||||
* \return 0 for success or -1 for failure
|
||||
*/
|
||||
int32_t PIOS_HMC5883_ReadMag(int16_t out[3])
|
||||
{
|
||||
pios_hmc5883_data_ready = false;
|
||||
uint8_t buffer[6];
|
||||
int32_t temp;
|
||||
int32_t sensitivity;
|
||||
|
||||
if (PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_XMSB_REG, buffer, 6) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
switch (CTRLB & 0xE0) {
|
||||
case 0x00:
|
||||
sensitivity = PIOS_HMC5883_Sensitivity_0_88Ga;
|
||||
break;
|
||||
case 0x20:
|
||||
sensitivity = PIOS_HMC5883_Sensitivity_1_3Ga;
|
||||
break;
|
||||
case 0x40:
|
||||
sensitivity = PIOS_HMC5883_Sensitivity_1_9Ga;
|
||||
break;
|
||||
case 0x60:
|
||||
sensitivity = PIOS_HMC5883_Sensitivity_2_5Ga;
|
||||
break;
|
||||
case 0x80:
|
||||
sensitivity = PIOS_HMC5883_Sensitivity_4_0Ga;
|
||||
break;
|
||||
case 0xA0:
|
||||
sensitivity = PIOS_HMC5883_Sensitivity_4_7Ga;
|
||||
break;
|
||||
case 0xC0:
|
||||
sensitivity = PIOS_HMC5883_Sensitivity_5_6Ga;
|
||||
break;
|
||||
case 0xE0:
|
||||
sensitivity = PIOS_HMC5883_Sensitivity_8_1Ga;
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
for (int i = 0; i < 3; i++) {
|
||||
temp = ((int16_t)((uint16_t)buffer[2 * i] << 8)
|
||||
+ buffer[2 * i + 1]) * 1000 / sensitivity;
|
||||
out[i] = temp;
|
||||
}
|
||||
// Data reads out as X,Z,Y
|
||||
temp = out[2];
|
||||
out[2] = out[1];
|
||||
out[1] = temp;
|
||||
|
||||
// This should not be necessary but for some reason it is coming out of continuous conversion mode
|
||||
PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, PIOS_HMC5883_MODE_CONTINUOUS);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Read the identification bytes from the HMC5883 sensor
|
||||
* \param[out] uint8_t array of size 4 to store HMC5883 ID.
|
||||
* \return 0 if successful, -1 if not
|
||||
*/
|
||||
uint8_t PIOS_HMC5883_ReadID(uint8_t out[4])
|
||||
{
|
||||
uint8_t retval = PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_IDA_REG, out, 3);
|
||||
|
||||
out[3] = '\0';
|
||||
return retval;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Tells whether new magnetometer readings are available
|
||||
* \return true if new data is available
|
||||
* \return false if new data is not available
|
||||
*/
|
||||
bool PIOS_HMC5883_NewDataAvailable(void)
|
||||
{
|
||||
return pios_hmc5883_data_ready;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Reads one or more bytes into a buffer
|
||||
* \param[in] address HMC5883 register address (depends on size)
|
||||
* \param[out] buffer destination buffer
|
||||
* \param[in] len number of bytes which should be read
|
||||
* \return 0 if operation was successful
|
||||
* \return -1 if error during I2C transfer
|
||||
* \return -2 if unable to claim i2c device
|
||||
*/
|
||||
static int32_t PIOS_HMC5883_Read(uint8_t address, uint8_t *buffer, uint8_t len)
|
||||
{
|
||||
uint8_t addr_buffer[] = {
|
||||
address,
|
||||
};
|
||||
|
||||
const struct pios_i2c_txn txn_list[] = {
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = PIOS_HMC5883_I2C_ADDR,
|
||||
.rw = PIOS_I2C_TXN_WRITE,
|
||||
.len = sizeof(addr_buffer),
|
||||
.buf = addr_buffer,
|
||||
}
|
||||
,
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = PIOS_HMC5883_I2C_ADDR,
|
||||
.rw = PIOS_I2C_TXN_READ,
|
||||
.len = len,
|
||||
.buf = buffer,
|
||||
}
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Writes one or more bytes to the HMC5883
|
||||
* \param[in] address Register address
|
||||
* \param[in] buffer source buffer
|
||||
* \return 0 if operation was successful
|
||||
* \return -1 if error during I2C transfer
|
||||
* \return -2 if unable to claim i2c device
|
||||
*/
|
||||
static int32_t PIOS_HMC5883_Write(uint8_t address, uint8_t buffer)
|
||||
{
|
||||
uint8_t data[] = {
|
||||
address,
|
||||
buffer,
|
||||
};
|
||||
|
||||
const struct pios_i2c_txn txn_list[] = {
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = PIOS_HMC5883_I2C_ADDR,
|
||||
.rw = PIOS_I2C_TXN_WRITE,
|
||||
.len = sizeof(data),
|
||||
.buf = data,
|
||||
}
|
||||
,
|
||||
};
|
||||
|
||||
;
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Run self-test operation. Do not call this during operational use!!
|
||||
* \return 0 if success, -1 if test failed
|
||||
*/
|
||||
int32_t PIOS_HMC5883_Test(void)
|
||||
{
|
||||
int32_t failed = 0;
|
||||
uint8_t registers[3] = { 0, 0, 0 };
|
||||
uint8_t status;
|
||||
uint8_t ctrl_a_read;
|
||||
uint8_t ctrl_b_read;
|
||||
uint8_t mode_read;
|
||||
int16_t values[3];
|
||||
|
||||
|
||||
/* Verify that ID matches (HMC5883 ID is null-terminated ASCII string "H43") */
|
||||
char id[4];
|
||||
|
||||
PIOS_HMC5883_ReadID((uint8_t *)id);
|
||||
if ((id[0] != 'H') || (id[1] != '4') || (id[2] != '3')) { // Expect H43
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Backup existing configuration */
|
||||
if (PIOS_HMC5883_Read(PIOS_HMC5883_CONFIG_REG_A, registers, 3) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Stop the device and read out last value */
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, PIOS_HMC5883_MODE_IDLE) != 0) {
|
||||
return -1;
|
||||
}
|
||||
if (PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_STATUS_REG, &status, 1) != 0) {
|
||||
return -1;
|
||||
}
|
||||
if (PIOS_HMC5883_ReadMag(values) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/*
|
||||
* Put HMC5883 into self test mode
|
||||
* This is done by placing measurement config into positive (0x01) or negative (0x10) bias
|
||||
* and then placing the mode register into single-measurement mode. This causes the HMC5883
|
||||
* to create an artificial magnetic field of ~1.1 Gauss.
|
||||
*
|
||||
* If gain were PIOS_HMC5883_GAIN_2_5, for example, X and Y will read around +766 LSB
|
||||
* (1.16 Ga * 660 LSB/Ga) and Z would read around +713 LSB (1.08 Ga * 660 LSB/Ga)
|
||||
*
|
||||
* Changing measurement config back to PIOS_HMC5883_MEASCONF_NORMAL will leave self-test mode.
|
||||
*/
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A, PIOS_HMC5883_MEASCONF_BIAS_POS | PIOS_HMC5883_ODR_15) != 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B, PIOS_HMC5883_GAIN_8_1) != 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, PIOS_HMC5883_MODE_SINGLE) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Must wait for value to be updated */
|
||||
PIOS_DELAY_WaitmS(200);
|
||||
|
||||
if (PIOS_HMC5883_ReadMag(values) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/*
|
||||
if(abs(values[0] - 766) > 20)
|
||||
failed |= 1;
|
||||
if(abs(values[1] - 766) > 20)
|
||||
failed |= 1;
|
||||
if(abs(values[2] - 713) > 20)
|
||||
failed |= 1;
|
||||
*/
|
||||
|
||||
PIOS_HMC5883_Read(PIOS_HMC5883_CONFIG_REG_A, &ctrl_a_read, 1);
|
||||
PIOS_HMC5883_Read(PIOS_HMC5883_CONFIG_REG_B, &ctrl_b_read, 1);
|
||||
PIOS_HMC5883_Read(PIOS_HMC5883_MODE_REG, &mode_read, 1);
|
||||
PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_STATUS_REG, &status, 1);
|
||||
|
||||
|
||||
/* Restore backup configuration */
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A, registers[0]) != 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B, registers[1]) != 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, registers[2]) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
return failed;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief IRQ Handler
|
||||
*/
|
||||
bool PIOS_HMC5883_IRQHandler(void)
|
||||
{
|
||||
pios_hmc5883_data_ready = true;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_HMC5883 */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
557
flight/pios/common/pios_hmc5x83.c
Normal file
@ -0,0 +1,557 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_HMC5x83 HMC5x83 Functions
|
||||
* @brief Deals with the hardware interface to the magnetometers
|
||||
* @{
|
||||
* @file pios_hmc5x83.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief HMC5x83 Magnetic Sensor Functions from AHRS
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "pios.h"
|
||||
#include <pios_hmc5x83.h>
|
||||
#include <pios_mem.h>
|
||||
|
||||
#ifdef PIOS_INCLUDE_HMC5X83
|
||||
|
||||
#define PIOS_HMC5X83_MAGIC 0x4d783833
|
||||
/* Global Variables */
|
||||
|
||||
/* Local Types */
|
||||
|
||||
typedef struct {
|
||||
uint32_t magic;
|
||||
const struct pios_hmc5x83_cfg *cfg;
|
||||
uint32_t port_id;
|
||||
uint8_t slave_num;
|
||||
uint8_t CTRLB;
|
||||
volatile bool data_ready;
|
||||
} pios_hmc5x83_dev_data_t;
|
||||
|
||||
static int32_t PIOS_HMC5x83_Config(pios_hmc5x83_dev_data_t *dev);
|
||||
|
||||
/**
|
||||
* Allocate the device setting structure
|
||||
* @return pios_hmc5x83_dev_data_t pointer to newly created structure
|
||||
*/
|
||||
pios_hmc5x83_dev_data_t *dev_alloc()
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = (pios_hmc5x83_dev_data_t *)pios_malloc(sizeof(pios_hmc5x83_dev_data_t));
|
||||
|
||||
PIOS_DEBUG_Assert(dev);
|
||||
memset(dev, 0x00, sizeof(pios_hmc5x83_dev_data_t));
|
||||
dev->magic = PIOS_HMC5X83_MAGIC;
|
||||
return dev;
|
||||
}
|
||||
|
||||
/**
|
||||
* Validate a pios_hmc5x83_dev_t handler and return the related pios_hmc5x83_dev_data_t pointer
|
||||
* @param dev device handler
|
||||
* @return the device data structure
|
||||
*/
|
||||
pios_hmc5x83_dev_data_t *dev_validate(pios_hmc5x83_dev_t dev)
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev_data = (pios_hmc5x83_dev_data_t *)dev;
|
||||
|
||||
PIOS_DEBUG_Assert(dev_data->magic == PIOS_HMC5X83_MAGIC);
|
||||
return dev_data;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initialize the HMC5x83 magnetometer sensor.
|
||||
* @return none
|
||||
*/
|
||||
pios_hmc5x83_dev_t PIOS_HMC5x83_Init(const struct pios_hmc5x83_cfg *cfg, uint32_t port_id, uint8_t slave_num)
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = dev_alloc();
|
||||
|
||||
dev->cfg = cfg; // store config before enabling interrupt
|
||||
dev->port_id = port_id;
|
||||
dev->slave_num = slave_num;
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
PIOS_EXTI_Init(cfg->exti_cfg);
|
||||
#endif
|
||||
|
||||
int32_t val = PIOS_HMC5x83_Config(dev);
|
||||
PIOS_Assert(val == 0);
|
||||
|
||||
dev->data_ready = false;
|
||||
return (pios_hmc5x83_dev_t)dev;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initialize the HMC5x83 magnetometer sensor
|
||||
* \return none
|
||||
* \param[in] pios_hmc5x83_dev_data_t device config to be used.
|
||||
* \param[in] PIOS_HMC5x83_ConfigTypeDef struct to be used to configure sensor.
|
||||
*
|
||||
* CTRL_REGA: Control Register A
|
||||
* Read Write
|
||||
* Default value: 0x10
|
||||
* 7:5 0 These bits must be cleared for correct operation.
|
||||
* 4:2 DO2-DO0: Data Output Rate Bits
|
||||
* DO2 | DO1 | DO0 | Minimum Data Output Rate (Hz)
|
||||
* ------------------------------------------------------
|
||||
* 0 | 0 | 0 | 0.75
|
||||
* 0 | 0 | 1 | 1.5
|
||||
* 0 | 1 | 0 | 3
|
||||
* 0 | 1 | 1 | 7.5
|
||||
* 1 | 0 | 0 | 15 (default)
|
||||
* 1 | 0 | 1 | 30
|
||||
* 1 | 1 | 0 | 75
|
||||
* 1 | 1 | 1 | Not Used
|
||||
* 1:0 MS1-MS0: Measurement Configuration Bits
|
||||
* MS1 | MS0 | MODE
|
||||
* ------------------------------
|
||||
* 0 | 0 | Normal
|
||||
* 0 | 1 | Positive Bias
|
||||
* 1 | 0 | Negative Bias
|
||||
* 1 | 1 | Not Used
|
||||
*
|
||||
* CTRL_REGB: Control RegisterB
|
||||
* Read Write
|
||||
* Default value: 0x20
|
||||
* 7:5 GN2-GN0: Gain Configuration Bits.
|
||||
* GN2 | GN1 | GN0 | Mag Input | Gain | Output Range
|
||||
* | | | Range[Ga] | [LSB/mGa] |
|
||||
* ------------------------------------------------------
|
||||
* 0 | 0 | 0 | ±0.88Ga | 1370 | 0xF8000x07FF (-2048:2047)
|
||||
* 0 | 0 | 1 | ±1.3Ga (def) | 1090 | 0xF8000x07FF (-2048:2047)
|
||||
* 0 | 1 | 0 | ±1.9Ga | 820 | 0xF8000x07FF (-2048:2047)
|
||||
* 0 | 1 | 1 | ±2.5Ga | 660 | 0xF8000x07FF (-2048:2047)
|
||||
* 1 | 0 | 0 | ±4.0Ga | 440 | 0xF8000x07FF (-2048:2047)
|
||||
* 1 | 0 | 1 | ±4.7Ga | 390 | 0xF8000x07FF (-2048:2047)
|
||||
* 1 | 1 | 0 | ±5.6Ga | 330 | 0xF8000x07FF (-2048:2047)
|
||||
* 1 | 1 | 1 | ±8.1Ga | 230 | 0xF8000x07FF (-2048:2047)
|
||||
* |Not recommended|
|
||||
*
|
||||
* 4:0 CRB4-CRB: 0 This bit must be cleared for correct operation.
|
||||
*
|
||||
* _MODE_REG: Mode Register
|
||||
* Read Write
|
||||
* Default value: 0x02
|
||||
* 7:2 0 These bits must be cleared for correct operation.
|
||||
* 1:0 MD1-MD0: Mode Select Bits
|
||||
* MS1 | MS0 | MODE
|
||||
* ------------------------------
|
||||
* 0 | 0 | Continuous-Conversion Mode.
|
||||
* 0 | 1 | Single-Conversion Mode
|
||||
* 1 | 0 | Negative Bias
|
||||
* 1 | 1 | Sleep Mode
|
||||
*/
|
||||
static int32_t PIOS_HMC5x83_Config(pios_hmc5x83_dev_data_t *dev)
|
||||
{
|
||||
uint8_t CTRLA = 0x00;
|
||||
uint8_t MODE = 0x00;
|
||||
|
||||
const struct pios_hmc5x83_cfg *cfg = dev->cfg;
|
||||
|
||||
dev->CTRLB = 0;
|
||||
|
||||
CTRLA |= (uint8_t)(cfg->M_ODR | cfg->Meas_Conf);
|
||||
CTRLA |= cfg->TempCompensation ? PIOS_HMC5x83_CTRLA_TEMP : 0;
|
||||
dev->CTRLB |= (uint8_t)(cfg->Gain);
|
||||
MODE |= (uint8_t)(cfg->Mode);
|
||||
|
||||
// CRTL_REGA
|
||||
if (cfg->Driver->Write((pios_hmc5x83_dev_t)dev, PIOS_HMC5x83_CONFIG_REG_A, CTRLA) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
// CRTL_REGB
|
||||
if (cfg->Driver->Write((pios_hmc5x83_dev_t)dev, PIOS_HMC5x83_CONFIG_REG_B, dev->CTRLB) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Mode register
|
||||
if (cfg->Driver->Write((pios_hmc5x83_dev_t)dev, PIOS_HMC5x83_MODE_REG, MODE) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read current X, Z, Y values (in that order)
|
||||
* \param[in] dev device handler
|
||||
* \param[out] int16_t array of size 3 to store X, Z, and Y magnetometer readings
|
||||
* \return 0 for success or -1 for failure
|
||||
*/
|
||||
int32_t PIOS_HMC5x83_ReadMag(pios_hmc5x83_dev_t handler, int16_t out[3])
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
|
||||
dev->data_ready = false;
|
||||
uint8_t buffer[6];
|
||||
int32_t temp;
|
||||
int32_t sensitivity;
|
||||
|
||||
if (dev->cfg->Driver->Read(handler, PIOS_HMC5x83_DATAOUT_XMSB_REG, buffer, 6) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
switch (dev->CTRLB & 0xE0) {
|
||||
case 0x00:
|
||||
sensitivity = PIOS_HMC5x83_Sensitivity_0_88Ga;
|
||||
break;
|
||||
case 0x20:
|
||||
sensitivity = PIOS_HMC5x83_Sensitivity_1_3Ga;
|
||||
break;
|
||||
case 0x40:
|
||||
sensitivity = PIOS_HMC5x83_Sensitivity_1_9Ga;
|
||||
break;
|
||||
case 0x60:
|
||||
sensitivity = PIOS_HMC5x83_Sensitivity_2_5Ga;
|
||||
break;
|
||||
case 0x80:
|
||||
sensitivity = PIOS_HMC5x83_Sensitivity_4_0Ga;
|
||||
break;
|
||||
case 0xA0:
|
||||
sensitivity = PIOS_HMC5x83_Sensitivity_4_7Ga;
|
||||
break;
|
||||
case 0xC0:
|
||||
sensitivity = PIOS_HMC5x83_Sensitivity_5_6Ga;
|
||||
break;
|
||||
case 0xE0:
|
||||
sensitivity = PIOS_HMC5x83_Sensitivity_8_1Ga;
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
for (int i = 0; i < 3; i++) {
|
||||
temp = ((int16_t)((uint16_t)buffer[2 * i] << 8)
|
||||
+ buffer[2 * i + 1]) * 1000 / sensitivity;
|
||||
out[i] = temp;
|
||||
}
|
||||
// Data reads out as X,Z,Y
|
||||
temp = out[2];
|
||||
out[2] = out[1];
|
||||
out[1] = temp;
|
||||
|
||||
// This should not be necessary but for some reason it is coming out of continuous conversion mode
|
||||
dev->cfg->Driver->Write(handler, PIOS_HMC5x83_MODE_REG, PIOS_HMC5x83_MODE_CONTINUOUS);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Read the identification bytes from the HMC5x83 sensor
|
||||
* \param[out] uint8_t array of size 4 to store HMC5x83 ID.
|
||||
* \return 0 if successful, -1 if not
|
||||
*/
|
||||
uint8_t PIOS_HMC5x83_ReadID(pios_hmc5x83_dev_t handler, uint8_t out[4])
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
uint8_t retval = dev->cfg->Driver->Read(handler, PIOS_HMC5x83_DATAOUT_IDA_REG, out, 3);
|
||||
|
||||
out[3] = '\0';
|
||||
return retval;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Tells whether new magnetometer readings are available
|
||||
* \return true if new data is available
|
||||
* \return false if new data is not available
|
||||
*/
|
||||
bool PIOS_HMC5x83_NewDataAvailable(pios_hmc5x83_dev_t handler)
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
|
||||
return dev->data_ready;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Run self-test operation. Do not call this during operational use!!
|
||||
* \return 0 if success, -1 if test failed
|
||||
*/
|
||||
int32_t PIOS_HMC5x83_Test(pios_hmc5x83_dev_t handler)
|
||||
{
|
||||
int32_t failed = 0;
|
||||
uint8_t registers[3] = { 0, 0, 0 };
|
||||
uint8_t status;
|
||||
uint8_t ctrl_a_read;
|
||||
uint8_t ctrl_b_read;
|
||||
uint8_t mode_read;
|
||||
int16_t values[3];
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
|
||||
/* Verify that ID matches (HMC5x83 ID is null-terminated ASCII string "H43") */
|
||||
char id[4];
|
||||
|
||||
PIOS_HMC5x83_ReadID(handler, (uint8_t *)id);
|
||||
if ((id[0] != 'H') || (id[1] != '4') || (id[2] != '3')) { // Expect H43
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Backup existing configuration */
|
||||
if (dev->cfg->Driver->Read(handler, PIOS_HMC5x83_CONFIG_REG_A, registers, 3) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Stop the device and read out last value */
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (dev->cfg->Driver->Write(handler, PIOS_HMC5x83_MODE_REG, PIOS_HMC5x83_MODE_IDLE) != 0) {
|
||||
return -1;
|
||||
}
|
||||
if (dev->cfg->Driver->Read(handler, PIOS_HMC5x83_DATAOUT_STATUS_REG, &status, 1) != 0) {
|
||||
return -1;
|
||||
}
|
||||
if (PIOS_HMC5x83_ReadMag(handler, values) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/*
|
||||
* Put HMC5x83 into self test mode
|
||||
* This is done by placing measurement config into positive (0x01) or negative (0x10) bias
|
||||
* and then placing the mode register into single-measurement mode. This causes the HMC5x83
|
||||
* to create an artificial magnetic field of ~1.1 Gauss.
|
||||
*
|
||||
* If gain were PIOS_HMC5x83_GAIN_2_5, for example, X and Y will read around +766 LSB
|
||||
* (1.16 Ga * 660 LSB/Ga) and Z would read around +713 LSB (1.08 Ga * 660 LSB/Ga)
|
||||
*
|
||||
* Changing measurement config back to PIOS_HMC5x83_MEASCONF_NORMAL will leave self-test mode.
|
||||
*/
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (dev->cfg->Driver->Write(handler, PIOS_HMC5x83_CONFIG_REG_A, PIOS_HMC5x83_MEASCONF_BIAS_POS | PIOS_HMC5x83_ODR_15) != 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (dev->cfg->Driver->Write(handler, PIOS_HMC5x83_CONFIG_REG_B, PIOS_HMC5x83_GAIN_8_1) != 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (dev->cfg->Driver->Write(handler, PIOS_HMC5x83_MODE_REG, PIOS_HMC5x83_MODE_SINGLE) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Must wait for value to be updated */
|
||||
PIOS_DELAY_WaitmS(200);
|
||||
|
||||
if (PIOS_HMC5x83_ReadMag(handler, values) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
dev->cfg->Driver->Read(handler, PIOS_HMC5x83_CONFIG_REG_A, &ctrl_a_read, 1);
|
||||
dev->cfg->Driver->Read(handler, PIOS_HMC5x83_CONFIG_REG_B, &ctrl_b_read, 1);
|
||||
dev->cfg->Driver->Read(handler, PIOS_HMC5x83_MODE_REG, &mode_read, 1);
|
||||
dev->cfg->Driver->Read(handler, PIOS_HMC5x83_DATAOUT_STATUS_REG, &status, 1);
|
||||
|
||||
|
||||
/* Restore backup configuration */
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (dev->cfg->Driver->Write(handler, PIOS_HMC5x83_CONFIG_REG_A, registers[0]) != 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (dev->cfg->Driver->Write(handler, PIOS_HMC5x83_CONFIG_REG_B, registers[1]) != 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
if (dev->cfg->Driver->Write(handler, PIOS_HMC5x83_MODE_REG, registers[2]) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
return failed;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief IRQ Handler
|
||||
*/
|
||||
bool PIOS_HMC5x83_IRQHandler(pios_hmc5x83_dev_t handler)
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
|
||||
dev->data_ready = true;
|
||||
return false;
|
||||
}
|
||||
|
||||
#ifdef PIOS_INCLUDE_SPI
|
||||
int32_t PIOS_HMC5x83_SPI_Read(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t *buffer, uint8_t len);
|
||||
int32_t PIOS_HMC5x83_SPI_Write(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t buffer);
|
||||
|
||||
const struct pios_hmc5x83_io_driver PIOS_HMC5x83_SPI_DRIVER = {
|
||||
.Read = PIOS_HMC5x83_SPI_Read,
|
||||
.Write = PIOS_HMC5x83_SPI_Write,
|
||||
};
|
||||
|
||||
static int32_t pios_hmc5x83_spi_claim_bus(pios_hmc5x83_dev_data_t *dev)
|
||||
{
|
||||
if (PIOS_SPI_ClaimBus(dev->port_id) < 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_SPI_RC_PinSet(dev->port_id, dev->slave_num, 0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void pios_hmc5x83_spi_release_bus(pios_hmc5x83_dev_data_t *dev)
|
||||
{
|
||||
PIOS_SPI_RC_PinSet(dev->port_id, dev->slave_num, 1);
|
||||
PIOS_SPI_ReleaseBus(dev->port_id);
|
||||
}
|
||||
/**
|
||||
* @brief Reads one or more bytes into a buffer
|
||||
* \param[in] address HMC5x83 register address (depends on size)
|
||||
* \param[out] buffer destination buffer
|
||||
* \param[in] len number of bytes which should be read
|
||||
* \return 0 if operation was successful
|
||||
* \return -1 if error during I2C transfer
|
||||
* \return -2 if unable to claim i2c device
|
||||
*/
|
||||
int32_t PIOS_HMC5x83_SPI_Read(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t *buffer, uint8_t len)
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
|
||||
if (pios_hmc5x83_spi_claim_bus(dev) < 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
memset(buffer, 0xA5, len);
|
||||
PIOS_SPI_TransferByte(dev->port_id, address | PIOS_HMC5x83_SPI_AUTOINCR_FLAG | PIOS_HMC5x83_SPI_READ_FLAG);
|
||||
|
||||
// buffer[0] = address | PIOS_HMC5x83_SPI_AUTOINCR_FLAG | PIOS_HMC5x83_SPI_READ_FLAG;
|
||||
/* Copy the transfer data to the buffer */
|
||||
if (PIOS_SPI_TransferBlock(dev->port_id, NULL, buffer, len, NULL) < 0) {
|
||||
pios_hmc5x83_spi_release_bus(dev);
|
||||
return -3;
|
||||
}
|
||||
pios_hmc5x83_spi_release_bus(dev);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Writes one or more bytes to the HMC5x83
|
||||
* \param[in] address Register address
|
||||
* \param[in] buffer source buffer
|
||||
* \return 0 if operation was successful
|
||||
* \return -1 if error during I2C transfer
|
||||
* \return -2 if unable to claim spi device
|
||||
*/
|
||||
int32_t PIOS_HMC5x83_SPI_Write(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t buffer)
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
|
||||
if (pios_hmc5x83_spi_claim_bus(dev) < 0) {
|
||||
return -1;
|
||||
}
|
||||
uint8_t data[] = {
|
||||
address | PIOS_HMC5x83_SPI_AUTOINCR_FLAG,
|
||||
buffer,
|
||||
};
|
||||
|
||||
if (PIOS_SPI_TransferBlock(dev->port_id, data, NULL, sizeof(data), NULL) < 0) {
|
||||
pios_hmc5x83_spi_release_bus(dev);
|
||||
return -2;
|
||||
}
|
||||
|
||||
pios_hmc5x83_spi_release_bus(dev);
|
||||
return 0;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
|
||||
int32_t PIOS_HMC5x83_I2C_Read(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t *buffer, uint8_t len);
|
||||
int32_t PIOS_HMC5x83_I2C_Write(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t buffer);
|
||||
|
||||
const struct pios_hmc5x83_io_driver PIOS_HMC5x83_I2C_DRIVER = {
|
||||
.Read = PIOS_HMC5x83_I2C_Read,
|
||||
.Write = PIOS_HMC5x83_I2C_Write,
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Reads one or more bytes into a buffer
|
||||
* \param[in] address HMC5x83 register address (depends on size)
|
||||
* \param[out] buffer destination buffer
|
||||
* \param[in] len number of bytes which should be read
|
||||
* \return 0 if operation was successful
|
||||
* \return -1 if error during I2C transfer
|
||||
* \return -2 if unable to claim i2c device
|
||||
*/
|
||||
int32_t PIOS_HMC5x83_I2C_Read(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t *buffer, uint8_t len)
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
uint8_t addr_buffer[] = {
|
||||
address,
|
||||
};
|
||||
|
||||
const struct pios_i2c_txn txn_list[] = {
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = PIOS_HMC5x83_I2C_ADDR,
|
||||
.rw = PIOS_I2C_TXN_WRITE,
|
||||
.len = sizeof(addr_buffer),
|
||||
.buf = addr_buffer,
|
||||
}
|
||||
,
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = PIOS_HMC5x83_I2C_ADDR,
|
||||
.rw = PIOS_I2C_TXN_READ,
|
||||
.len = len,
|
||||
.buf = buffer,
|
||||
}
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(dev->port_id, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Writes one or more bytes to the HMC5x83
|
||||
* \param[in] address Register address
|
||||
* \param[in] buffer source buffer
|
||||
* \return 0 if operation was successful
|
||||
* \return -1 if error during I2C transfer
|
||||
* \return -2 if unable to claim i2c device
|
||||
*/
|
||||
int32_t PIOS_HMC5x83_I2C_Write(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t buffer)
|
||||
{
|
||||
pios_hmc5x83_dev_data_t *dev = dev_validate(handler);
|
||||
uint8_t data[] = {
|
||||
address,
|
||||
buffer,
|
||||
};
|
||||
|
||||
const struct pios_i2c_txn txn_list[] = {
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = PIOS_HMC5x83_I2C_ADDR,
|
||||
.rw = PIOS_I2C_TXN_WRITE,
|
||||
.len = sizeof(data),
|
||||
.buf = data,
|
||||
}
|
||||
,
|
||||
};
|
||||
|
||||
;
|
||||
return PIOS_I2C_Transfer(dev->port_id, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
|
||||
#endif /* PIOS_INCLUDE_HMC5x83 */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -40,30 +40,65 @@ const struct pios_flash_jedec_cfg pios_flash_jedec_catalog[] =
|
||||
.expect_manufacturer = JEDEC_MANUFACTURER_ST,
|
||||
.expect_memorytype = 0x20,
|
||||
.expect_capacity = 0x15,
|
||||
.sector_erase = 0xD8,
|
||||
.chip_erase = 0xC7,
|
||||
.sector_erase = 0xD8,
|
||||
.chip_erase = 0xC7,
|
||||
.fast_read = 0x0B,
|
||||
.fast_read_dummy_bytes = 1,
|
||||
},
|
||||
{ // m25px16
|
||||
.expect_manufacturer = JEDEC_MANUFACTURER_ST,
|
||||
.expect_memorytype = 0x71,
|
||||
.expect_capacity = 0x15,
|
||||
.sector_erase = 0xD8,
|
||||
.chip_erase = 0xC7,
|
||||
.sector_erase = 0xD8,
|
||||
.chip_erase = 0xC7,
|
||||
.fast_read = 0x0B,
|
||||
.fast_read_dummy_bytes = 1,
|
||||
},
|
||||
{ // w25x
|
||||
.expect_manufacturer = JEDEC_MANUFACTURER_WINBOND,
|
||||
.expect_memorytype = 0x30,
|
||||
.expect_capacity = 0x13,
|
||||
.sector_erase = 0x20,
|
||||
.chip_erase = 0x60
|
||||
.sector_erase = 0x20,
|
||||
.chip_erase = 0x60,
|
||||
.fast_read = 0x0B,
|
||||
.fast_read_dummy_bytes = 1,
|
||||
},
|
||||
{ // 25q16
|
||||
.expect_manufacturer = JEDEC_MANUFACTURER_WINBOND,
|
||||
.expect_memorytype = 0x40,
|
||||
.expect_capacity = 0x15,
|
||||
.sector_erase = 0x20,
|
||||
.chip_erase = 0x60
|
||||
}
|
||||
.sector_erase = 0x20,
|
||||
.chip_erase = 0x60,
|
||||
.fast_read = 0x0B,
|
||||
.fast_read_dummy_bytes = 1,
|
||||
},
|
||||
{ // 25q512
|
||||
.expect_manufacturer = JEDEC_MANUFACTURER_MICRON,
|
||||
.expect_memorytype = 0xBA,
|
||||
.expect_capacity = 0x20,
|
||||
.sector_erase = 0xD8,
|
||||
.chip_erase = 0xC7,
|
||||
.fast_read = 0x0B,
|
||||
.fast_read_dummy_bytes = 1,
|
||||
},
|
||||
{ // 25q256
|
||||
.expect_manufacturer = JEDEC_MANUFACTURER_NUMORIX,
|
||||
.expect_memorytype = 0xBA,
|
||||
.expect_capacity = 0x19,
|
||||
.sector_erase = 0xD8,
|
||||
.chip_erase = 0xC7,
|
||||
.fast_read = 0x0B,
|
||||
.fast_read_dummy_bytes = 1,
|
||||
},
|
||||
{ // 25q128
|
||||
.expect_manufacturer = JEDEC_MANUFACTURER_MICRON,
|
||||
.expect_memorytype = 0xBA,
|
||||
.expect_capacity = 0x18,
|
||||
.sector_erase = 0xD8,
|
||||
.chip_erase = 0xC7,
|
||||
.fast_read = 0x0B,
|
||||
.fast_read_dummy_bytes = 1,
|
||||
},
|
||||
};
|
||||
const uint32_t pios_flash_jedec_catalog_size = NELEMENTS(pios_flash_jedec_catalog);
|
||||
|
||||
|
@ -36,15 +36,19 @@
|
||||
extern const struct pios_flash_driver pios_jedec_flash_driver;
|
||||
|
||||
#define JEDEC_MANUFACTURER_ST 0x20
|
||||
#define JEDEC_MANUFACTURER_MICRON 0x20
|
||||
#define JEDEC_MANUFACTURER_NUMORIX 0x20
|
||||
#define JEDEC_MANUFACTURER_MACRONIX 0xC2
|
||||
#define JEDEC_MANUFACTURER_WINBOND 0xEF
|
||||
|
||||
struct pios_flash_jedec_cfg {
|
||||
uint8_t expect_manufacturer;
|
||||
uint8_t expect_memorytype;
|
||||
uint8_t expect_capacity;
|
||||
uint32_t sector_erase;
|
||||
uint32_t chip_erase;
|
||||
uint8_t expect_manufacturer;
|
||||
uint8_t expect_memorytype;
|
||||
uint8_t expect_capacity;
|
||||
uint8_t sector_erase;
|
||||
uint8_t chip_erase;
|
||||
uint8_t fast_read;
|
||||
uint8_t fast_read_dummy_bytes;
|
||||
};
|
||||
|
||||
int32_t PIOS_Flash_Jedec_Init(uintptr_t *flash_id, uint32_t spi_id, uint32_t slave_num);
|
||||
|
@ -1,116 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_HMC5883 HMC5883 Functions
|
||||
* @brief Deals with the hardware interface to the magnetometers
|
||||
* @{
|
||||
*
|
||||
* @file pios_hmc5883.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief HMC5883 functions header.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_HMC5883_H
|
||||
#define PIOS_HMC5883_H
|
||||
|
||||
/* HMC5883 Addresses */
|
||||
#define PIOS_HMC5883_I2C_ADDR 0x1E
|
||||
#define PIOS_HMC5883_I2C_READ_ADDR 0x3D
|
||||
#define PIOS_HMC5883_I2C_WRITE_ADDR 0x3C
|
||||
#define PIOS_HMC5883_CONFIG_REG_A (uint8_t)0x00
|
||||
#define PIOS_HMC5883_CONFIG_REG_B (uint8_t)0x01
|
||||
#define PIOS_HMC5883_MODE_REG (uint8_t)0x02
|
||||
#define PIOS_HMC5883_DATAOUT_XMSB_REG 0x03
|
||||
#define PIOS_HMC5883_DATAOUT_XLSB_REG 0x04
|
||||
#define PIOS_HMC5883_DATAOUT_ZMSB_REG 0x05
|
||||
#define PIOS_HMC5883_DATAOUT_ZLSB_REG 0x06
|
||||
#define PIOS_HMC5883_DATAOUT_YMSB_REG 0x07
|
||||
#define PIOS_HMC5883_DATAOUT_YLSB_REG 0x08
|
||||
#define PIOS_HMC5883_DATAOUT_STATUS_REG 0x09
|
||||
#define PIOS_HMC5883_DATAOUT_IDA_REG 0x0A
|
||||
#define PIOS_HMC5883_DATAOUT_IDB_REG 0x0B
|
||||
#define PIOS_HMC5883_DATAOUT_IDC_REG 0x0C
|
||||
|
||||
/* Output Data Rate */
|
||||
#define PIOS_HMC5883_ODR_0_75 0x00
|
||||
#define PIOS_HMC5883_ODR_1_5 0x04
|
||||
#define PIOS_HMC5883_ODR_3 0x08
|
||||
#define PIOS_HMC5883_ODR_7_5 0x0C
|
||||
#define PIOS_HMC5883_ODR_15 0x10
|
||||
#define PIOS_HMC5883_ODR_30 0x14
|
||||
#define PIOS_HMC5883_ODR_75 0x18
|
||||
|
||||
/* Measure configuration */
|
||||
#define PIOS_HMC5883_MEASCONF_NORMAL 0x00
|
||||
#define PIOS_HMC5883_MEASCONF_BIAS_POS 0x01
|
||||
#define PIOS_HMC5883_MEASCONF_BIAS_NEG 0x02
|
||||
|
||||
/* Gain settings */
|
||||
#define PIOS_HMC5883_GAIN_0_88 0x00
|
||||
#define PIOS_HMC5883_GAIN_1_3 0x20
|
||||
#define PIOS_HMC5883_GAIN_1_9 0x40
|
||||
#define PIOS_HMC5883_GAIN_2_5 0x60
|
||||
#define PIOS_HMC5883_GAIN_4_0 0x80
|
||||
#define PIOS_HMC5883_GAIN_4_7 0xA0
|
||||
#define PIOS_HMC5883_GAIN_5_6 0xC0
|
||||
#define PIOS_HMC5883_GAIN_8_1 0xE0
|
||||
|
||||
/* Modes */
|
||||
#define PIOS_HMC5883_MODE_CONTINUOUS 0x00
|
||||
#define PIOS_HMC5883_MODE_SINGLE 0x01
|
||||
#define PIOS_HMC5883_MODE_IDLE 0x02
|
||||
#define PIOS_HMC5883_MODE_SLEEP 0x03
|
||||
|
||||
/* Sensitivity Conversion Values */
|
||||
#define PIOS_HMC5883_Sensitivity_0_88Ga 1370 // LSB/Ga
|
||||
#define PIOS_HMC5883_Sensitivity_1_3Ga 1090 // LSB/Ga
|
||||
#define PIOS_HMC5883_Sensitivity_1_9Ga 820 // LSB/Ga
|
||||
#define PIOS_HMC5883_Sensitivity_2_5Ga 660 // LSB/Ga
|
||||
#define PIOS_HMC5883_Sensitivity_4_0Ga 440 // LSB/Ga
|
||||
#define PIOS_HMC5883_Sensitivity_4_7Ga 390 // LSB/Ga
|
||||
#define PIOS_HMC5883_Sensitivity_5_6Ga 330 // LSB/Ga
|
||||
#define PIOS_HMC5883_Sensitivity_8_1Ga 230 // LSB/Ga --> NOT RECOMMENDED
|
||||
|
||||
|
||||
struct pios_hmc5883_cfg {
|
||||
#ifdef PIOS_HMC5883_HAS_GPIOS
|
||||
const struct pios_exti_cfg *exti_cfg; /* Pointer to the EXTI configuration */
|
||||
#endif
|
||||
uint8_t M_ODR; /* OUTPUT DATA RATE --> here below the relative define (See datasheet page 11 for more details) */
|
||||
uint8_t Meas_Conf; /* Measurement Configuration,: Normal, positive bias, or negative bias --> here below the relative define */
|
||||
uint8_t Gain; /* Gain Configuration, select the full scale --> here below the relative define (See datasheet page 11 for more details) */
|
||||
uint8_t Mode;
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
extern void PIOS_HMC5883_Init(const struct pios_hmc5883_cfg *cfg);
|
||||
extern bool PIOS_HMC5883_NewDataAvailable(void);
|
||||
extern int32_t PIOS_HMC5883_ReadMag(int16_t out[3]);
|
||||
extern uint8_t PIOS_HMC5883_ReadID(uint8_t out[4]);
|
||||
extern int32_t PIOS_HMC5883_Test(void);
|
||||
extern bool PIOS_HMC5883_IRQHandler();
|
||||
|
||||
#endif /* PIOS_HMC5883_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
137
flight/pios/inc/pios_hmc5x83.h
Normal file
@ -0,0 +1,137 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_HMC5x83 HMC5x83 Functions
|
||||
* @brief Deals with the hardware interface to the magnetometers
|
||||
* @{
|
||||
*
|
||||
* @file pios_hmc5x83.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief HMC5x83 functions header.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_HMC5x83_H
|
||||
#define PIOS_HMC5x83_H
|
||||
#include <stdint.h>
|
||||
/* HMC5x83 Addresses */
|
||||
#define PIOS_HMC5x83_I2C_ADDR 0x1E
|
||||
#define PIOS_HMC5x83_I2C_READ_ADDR 0x3D
|
||||
#define PIOS_HMC5x83_I2C_WRITE_ADDR 0x3C
|
||||
|
||||
#define PIOS_HMC5x83_SPI_READ_FLAG 0x80
|
||||
#define PIOS_HMC5x83_SPI_AUTOINCR_FLAG 0x40
|
||||
#define PIOS_HMC5x83_CONFIG_REG_A (uint8_t)0x00
|
||||
#define PIOS_HMC5x83_CONFIG_REG_B (uint8_t)0x01
|
||||
#define PIOS_HMC5x83_MODE_REG (uint8_t)0x02
|
||||
#define PIOS_HMC5x83_DATAOUT_XMSB_REG 0x03
|
||||
#define PIOS_HMC5x83_DATAOUT_XLSB_REG 0x04
|
||||
#define PIOS_HMC5x83_DATAOUT_ZMSB_REG 0x05
|
||||
#define PIOS_HMC5x83_DATAOUT_ZLSB_REG 0x06
|
||||
#define PIOS_HMC5x83_DATAOUT_YMSB_REG 0x07
|
||||
#define PIOS_HMC5x83_DATAOUT_YLSB_REG 0x08
|
||||
#define PIOS_HMC5x83_DATAOUT_STATUS_REG 0x09
|
||||
#define PIOS_HMC5x83_DATAOUT_IDA_REG 0x0A
|
||||
#define PIOS_HMC5x83_DATAOUT_IDB_REG 0x0B
|
||||
#define PIOS_HMC5x83_DATAOUT_IDC_REG 0x0C
|
||||
|
||||
/* Output Data Rate */
|
||||
#define PIOS_HMC5x83_ODR_0_75 0x00
|
||||
#define PIOS_HMC5x83_ODR_1_5 0x04
|
||||
#define PIOS_HMC5x83_ODR_3 0x08
|
||||
#define PIOS_HMC5x83_ODR_7_5 0x0C
|
||||
#define PIOS_HMC5x83_ODR_15 0x10
|
||||
#define PIOS_HMC5x83_ODR_30 0x14
|
||||
#define PIOS_HMC5x83_ODR_75 0x18
|
||||
|
||||
/* Measure configuration */
|
||||
#define PIOS_HMC5x83_MEASCONF_NORMAL 0x00
|
||||
#define PIOS_HMC5x83_MEASCONF_BIAS_POS 0x01
|
||||
#define PIOS_HMC5x83_MEASCONF_BIAS_NEG 0x02
|
||||
|
||||
/* Gain settings */
|
||||
#define PIOS_HMC5x83_GAIN_0_88 0x00
|
||||
#define PIOS_HMC5x83_GAIN_1_3 0x20
|
||||
#define PIOS_HMC5x83_GAIN_1_9 0x40
|
||||
#define PIOS_HMC5x83_GAIN_2_5 0x60
|
||||
#define PIOS_HMC5x83_GAIN_4_0 0x80
|
||||
#define PIOS_HMC5x83_GAIN_4_7 0xA0
|
||||
#define PIOS_HMC5x83_GAIN_5_6 0xC0
|
||||
#define PIOS_HMC5x83_GAIN_8_1 0xE0
|
||||
|
||||
#define PIOS_HMC5x83_CTRLA_TEMP 0x40
|
||||
|
||||
/* Modes */
|
||||
#define PIOS_HMC5x83_MODE_CONTINUOUS 0x00
|
||||
#define PIOS_HMC5x83_MODE_SINGLE 0x01
|
||||
#define PIOS_HMC5x83_MODE_IDLE 0x02
|
||||
#define PIOS_HMC5x83_MODE_SLEEP 0x03
|
||||
|
||||
/* Sensitivity Conversion Values */
|
||||
#define PIOS_HMC5x83_Sensitivity_0_88Ga 1370 // LSB/Ga
|
||||
#define PIOS_HMC5x83_Sensitivity_1_3Ga 1090 // LSB/Ga
|
||||
#define PIOS_HMC5x83_Sensitivity_1_9Ga 820 // LSB/Ga
|
||||
#define PIOS_HMC5x83_Sensitivity_2_5Ga 660 // LSB/Ga
|
||||
#define PIOS_HMC5x83_Sensitivity_4_0Ga 440 // LSB/Ga
|
||||
#define PIOS_HMC5x83_Sensitivity_4_7Ga 390 // LSB/Ga
|
||||
#define PIOS_HMC5x83_Sensitivity_5_6Ga 330 // LSB/Ga
|
||||
#define PIOS_HMC5x83_Sensitivity_8_1Ga 230 // LSB/Ga --> NOT RECOMMENDED
|
||||
|
||||
typedef uintptr_t pios_hmc5x83_dev_t;
|
||||
|
||||
struct pios_hmc5x83_io_driver {
|
||||
int32_t (*Write)(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t buffer);
|
||||
int32_t (*Read)(pios_hmc5x83_dev_t handler, uint8_t address, uint8_t *buffer, uint8_t len);
|
||||
};
|
||||
|
||||
#ifdef PIOS_INCLUDE_SPI
|
||||
extern const struct pios_hmc5x83_io_driver PIOS_HMC5x83_SPI_DRIVER;
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
extern const struct pios_hmc5x83_io_driver PIOS_HMC5x83_I2C_DRIVER;
|
||||
#endif
|
||||
|
||||
struct pios_hmc5x83_cfg {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
const struct pios_exti_cfg *exti_cfg; /* Pointer to the EXTI configuration */
|
||||
#endif
|
||||
uint8_t M_ODR; // OUTPUT DATA RATE --> here below the relative define (See datasheet page 11 for more details) */
|
||||
uint8_t Meas_Conf; // Measurement Configuration,: Normal, positive bias, or negative bias --> here below the relative define */
|
||||
uint8_t Gain; // Gain Configuration, select the full scale --> here below the relative define (See datasheet page 11 for more details) */
|
||||
uint8_t Mode;
|
||||
bool TempCompensation; // enable temperature sensor on HMC5983 for temperature gain compensation
|
||||
const struct pios_hmc5x83_io_driver *Driver;
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
extern pios_hmc5x83_dev_t PIOS_HMC5x83_Init(const struct pios_hmc5x83_cfg *cfg, uint32_t port_id, uint8_t device_num);
|
||||
extern bool PIOS_HMC5x83_NewDataAvailable(pios_hmc5x83_dev_t handler);
|
||||
extern int32_t PIOS_HMC5x83_ReadMag(pios_hmc5x83_dev_t handler, int16_t out[3]);
|
||||
extern uint8_t PIOS_HMC5x83_ReadID(pios_hmc5x83_dev_t handler, uint8_t out[4]);
|
||||
extern int32_t PIOS_HMC5x83_Test(pios_hmc5x83_dev_t handler);
|
||||
extern bool PIOS_HMC5x83_IRQHandler(pios_hmc5x83_dev_t handler);
|
||||
|
||||
#endif /* PIOS_HMC5x83_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -40,6 +40,7 @@
|
||||
#define M_2_SQRTPI_F 1.12837916709551257389615890312f /* 2/sqrt(pi) */
|
||||
#define M_1_PI_F 0.31830988618379067153776752675f /* 1/pi */
|
||||
#define M_2_PI_F 0.63661977236758134307553505349f /* 2/pi */
|
||||
#define M_2PI_F 6.28318530717958647692528676656f /* 2pi */
|
||||
#define M_LN10_F 2.30258509299404568401799145468f /* ln(10) */
|
||||
#define M_LN2_F 0.69314718055994530941723212146f /* ln(2) */
|
||||
#define M_LNPI_F 1.14472988584940017414342735135f /* ln(pi) */
|
||||
@ -54,6 +55,7 @@
|
||||
#define M_PI_D 3.14159265358979323846264338328d /* pi */
|
||||
#define M_PI_2_D 1.57079632679489661923132169164d /* pi/2 */
|
||||
#define M_PI_4_D 0.78539816339744830961566084582d /* pi/4 */
|
||||
#define M_2PI_D 6.28318530717958647692528676656d /* 2pi */
|
||||
#define M_SQRTPI_D 1.77245385090551602729816748334d /* sqrt(pi) */
|
||||
#define M_2_SQRTPI_D 1.12837916709551257389615890312d /* 2/sqrt(pi) */
|
||||
#define M_1_PI_D 0.31830988618379067153776752675d /* 1/pi */
|
||||
|
@ -204,10 +204,10 @@
|
||||
#include <pios_hmc5843.h>
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_HMC5883
|
||||
/* HMC5883 3-Axis Digital Compass */
|
||||
/* #define PIOS_HMC5883_HAS_GPIOS */
|
||||
#include <pios_hmc5883.h>
|
||||
#ifdef PIOS_INCLUDE_HMC5X83
|
||||
/* HMC5883/HMC5983 3-Axis Digital Compass */
|
||||
/* #define PIOS_HMC5x83_HAS_GPIOS */
|
||||
#include <pios_hmc5x83.h>
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_BMP085
|
||||
|
@ -585,6 +585,9 @@ static int32_t SPI_DMA_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer
|
||||
|
||||
/* Wait until all bytes have been transmitted/received */
|
||||
while (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)) {
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
vTaskDelay(0);
|
||||
#endif
|
||||
;
|
||||
}
|
||||
|
||||
|
@ -84,7 +84,7 @@
|
||||
#define PIOS_INCLUDE_MPU6000
|
||||
#define PIOS_MPU6000_ACCEL
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
/* #define PIOS_INCLUDE_HMC5883 */
|
||||
/* #define PIOS_INCLUDE_HMC5X83 */
|
||||
/* #define PIOS_HMC5883_HAS_GPIOS */
|
||||
/* #define PIOS_INCLUDE_BMP085 */
|
||||
/* #define PIOS_INCLUDE_MS5611 */
|
||||
|
@ -84,8 +84,8 @@
|
||||
// #define PIOS_INCLUDE_MPU6000
|
||||
// #define PIOS_MPU6000_ACCEL
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
// #define PIOS_INCLUDE_HMC5883
|
||||
// #define PIOS_HMC5883_HAS_GPIOS
|
||||
// #define PIOS_INCLUDE_HMC5X83
|
||||
// #define PIOS_HMC5X83_HAS_GPIOS
|
||||
/* #define PIOS_INCLUDE_BMP085 */
|
||||
// #define PIOS_INCLUDE_MS5611
|
||||
// #define PIOS_INCLUDE_MPXV
|
||||
|
@ -90,10 +90,10 @@ void PIOS_ADC_DMC_irq_handler(void)
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
#include "pios_hmc5883.h"
|
||||
static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = {
|
||||
.vector = PIOS_HMC5883_IRQHandler,
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
#include "pios_hmc5x83.h"
|
||||
static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
.vector = PIOS_HMC5x83_IRQHandler,
|
||||
.line = EXTI_Line7,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
@ -123,14 +123,15 @@ static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = {
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_hmc5883_cfg pios_hmc5883_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5883_cfg,
|
||||
.M_ODR = PIOS_HMC5883_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5883_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5883_MODE_CONTINUOUS,
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5883 */
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
/**
|
||||
* Configuration for the MS5611 chip
|
||||
@ -929,8 +930,8 @@ void PIOS_Board_Init(void)
|
||||
PIOS_ADC_Init(&pios_adc_cfg);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
PIOS_HMC5883_Init(&pios_hmc5883_cfg);
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
PIOS_HMC5x83_Init(&pios_hmc5x83_cfg, pios_i2c_mag_pressure_adapter_id, 0);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
|
@ -81,7 +81,7 @@
|
||||
/* #define PIOS_INCLUDE_MPU6000 */
|
||||
/* #define PIOS_MPU6000_ACCEL */
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
/* #define PIOS_INCLUDE_HMC5883 */
|
||||
/* #define PIOS_INCLUDE_HMC5X83 */
|
||||
/* #define PIOS_HMC5883_HAS_GPIOS */
|
||||
/* #define PIOS_INCLUDE_BMP085 */
|
||||
/* #define PIOS_INCLUDE_MS5611 */
|
||||
|
@ -81,8 +81,8 @@
|
||||
/* #define PIOS_INCLUDE_MPU6000 */
|
||||
/* #define PIOS_MPU6000_ACCEL */
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
#define PIOS_INCLUDE_HMC5883
|
||||
/* #define PIOS_HMC5883_HAS_GPIOS */
|
||||
#define PIOS_INCLUDE_HMC5X83
|
||||
/* #define PIOS_HMC5X83_HAS_GPIOS */
|
||||
#define PIOS_INCLUDE_BMP085
|
||||
/* #define PIOS_INCLUDE_MS5611 */
|
||||
/* #define PIOS_INCLUDE_MPXV */
|
||||
|
@ -84,8 +84,8 @@
|
||||
#define PIOS_INCLUDE_MPU6000
|
||||
#define PIOS_MPU6000_ACCEL
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
#define PIOS_INCLUDE_HMC5883
|
||||
#define PIOS_HMC5883_HAS_GPIOS
|
||||
#define PIOS_INCLUDE_HMC5X83
|
||||
#define PIOS_HMC5X83_HAS_GPIOS
|
||||
/* #define PIOS_INCLUDE_BMP085 */
|
||||
#define PIOS_INCLUDE_MS5611
|
||||
#define PIOS_INCLUDE_MPXV
|
||||
|
@ -57,6 +57,7 @@
|
||||
*/
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
|
||||
#include "pios_adc_priv.h"
|
||||
void PIOS_ADC_DMC_irq_handler(void);
|
||||
void DMA2_Stream4_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMC_irq_handler")));
|
||||
@ -91,10 +92,16 @@ void PIOS_ADC_DMC_irq_handler(void)
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
#include "pios_hmc5883.h"
|
||||
static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = {
|
||||
.vector = PIOS_HMC5883_IRQHandler,
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
#include "pios_hmc5x83.h"
|
||||
pios_hmc5x83_dev_t onboard_mag = 0;
|
||||
|
||||
bool pios_board_internal_mag_handler()
|
||||
{
|
||||
return PIOS_HMC5x83_IRQHandler(onboard_mag);
|
||||
}
|
||||
static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
.vector = pios_board_internal_mag_handler,
|
||||
.line = EXTI_Line7,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
@ -124,14 +131,15 @@ static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = {
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_hmc5883_cfg pios_hmc5883_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5883_cfg,
|
||||
.M_ODR = PIOS_HMC5883_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5883_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5883_MODE_CONTINUOUS,
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5883 */
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
/**
|
||||
* Configuration for the MS5611 chip
|
||||
@ -944,8 +952,8 @@ void PIOS_Board_Init(void)
|
||||
PIOS_ADC_Init(&pios_adc_cfg);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
PIOS_HMC5883_Init(&pios_hmc5883_cfg);
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
onboard_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_cfg, pios_i2c_mag_pressure_adapter_id, 0);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
|
@ -81,8 +81,8 @@
|
||||
#define PIOS_INCLUDE_MPU6000
|
||||
#define PIOS_MPU6000_ACCEL
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
#define PIOS_INCLUDE_HMC5883
|
||||
#define PIOS_HMC5883_HAS_GPIOS
|
||||
#define PIOS_INCLUDE_HMC5X83
|
||||
#define PIOS_HMC5X83_HAS_GPIOS
|
||||
/* #define PIOS_INCLUDE_BMP085 */
|
||||
#define PIOS_INCLUDE_MS5611
|
||||
#define PIOS_INCLUDE_MPXV
|
||||
|
@ -81,10 +81,16 @@ void PIOS_ADC_DMC_irq_handler(void)
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
#include "pios_hmc5883.h"
|
||||
static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = {
|
||||
.vector = PIOS_HMC5883_IRQHandler,
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
pios_hmc5x83_dev_t onboard_mag = 0;
|
||||
|
||||
bool pios_board_internal_mag_handler()
|
||||
{
|
||||
return PIOS_HMC5x83_IRQHandler(onboard_mag);
|
||||
}
|
||||
#include "pios_hmc5x83.h"
|
||||
static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
.vector = pios_board_internal_mag_handler,
|
||||
.line = EXTI_Line5,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
@ -114,14 +120,15 @@ static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = {
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_hmc5883_cfg pios_hmc5883_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5883_cfg,
|
||||
.M_ODR = PIOS_HMC5883_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5883_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5883_MODE_CONTINUOUS,
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5883 */
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
/**
|
||||
* Configuration for the MS5611 chip
|
||||
@ -938,8 +945,8 @@ void PIOS_Board_Init(void)
|
||||
PIOS_ADC_Init(&pios_adc_cfg);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5883)
|
||||
PIOS_HMC5883_Init(&pios_hmc5883_cfg);
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
onboard_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_cfg, pios_i2c_pressure_adapter_id, 0);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
|
@ -100,6 +100,7 @@ SRC += $(FLIGHTLIB)/sanitycheck.c
|
||||
SRC += $(MATHLIB)/sin_lookup.c
|
||||
SRC += $(MATHLIB)/pid.c
|
||||
SRC += $(MATHLIB)/mathmisc.c
|
||||
SRC += $(MATHLIB)/butterworth.c
|
||||
|
||||
SRC += $(PIOSCORECOMMON)/pios_task_monitor.c
|
||||
SRC += $(PIOSCORECOMMON)/pios_dosfs_logfs.c
|
||||
|
@ -63,7 +63,7 @@
|
||||
|
||||
/* Select the sensors to include */
|
||||
// #define PIOS_INCLUDE_BMA180
|
||||
// #define PIOS_INCLUDE_HMC5883
|
||||
// #define PIOS_INCLUDE_HMC5X83
|
||||
// #define PIOS_INCLUDE_MPU6000
|
||||
// #define PIOS_MPU6000_ACCEL
|
||||
// #define PIOS_INCLUDE_L3GD20
|
||||
|
@ -30,9 +30,6 @@ GCS_LIBRARY_PATH
|
||||
libQt5Qml.so.5 \
|
||||
libQt5DBus.so.5 \
|
||||
libQt5QuickParticles.so.5 \
|
||||
libicui18n.so.51 \
|
||||
libicuuc.so.51 \
|
||||
libicudata.so.51 \
|
||||
libqgsttools_p.so.1
|
||||
|
||||
data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_QT_LIBRARY_PATH\") $$addNewline()
|
||||
@ -142,9 +139,9 @@ GCS_LIBRARY_PATH
|
||||
Qt5MultimediaWidgets$${DS}.dll \
|
||||
Qt5Quick$${DS}.dll \
|
||||
Qt5Qml$${DS}.dll \
|
||||
icuin51.dll \
|
||||
icudt51.dll \
|
||||
icuuc51.dll
|
||||
icuin52.dll \
|
||||
icudt52.dll \
|
||||
icuuc52.dll
|
||||
# it is more robust to take the following DLLs from Qt rather than from MinGW
|
||||
QT_DLLS += libgcc_s_dw2-1.dll \
|
||||
libstdc++-6.dll \
|
||||
@ -158,7 +155,8 @@ GCS_LIBRARY_PATH
|
||||
imageformats \
|
||||
platforms \
|
||||
mediaservice \
|
||||
sqldrivers
|
||||
sqldrivers \
|
||||
opengl32_32
|
||||
for(dir, QT_PLUGIN_DIRS) {
|
||||
data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/$$dir\") $$addNewline()
|
||||
}
|
||||
@ -235,6 +233,13 @@ GCS_LIBRARY_PATH
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(OPENSSL_DIR)/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline()
|
||||
}
|
||||
|
||||
# copy OpenGL DLL
|
||||
OPENGL_DLLS = \
|
||||
opengl32_32/opengl32.dll
|
||||
for(dll, OPENGL_DLLS) {
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(MESAWIN_DIR)/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline()
|
||||
}
|
||||
|
||||
data_copy.target = FORCE
|
||||
QMAKE_EXTRA_TARGETS += data_copy
|
||||
}
|
||||
|
@ -3,6 +3,9 @@ import QtQuick 2.0
|
||||
Item {
|
||||
id: info
|
||||
property variant sceneSize
|
||||
|
||||
property var tele_status : (OPLinkStatus.LinkState == 1 ? GCSTelemetryStats.Status :
|
||||
OPLinkStatus.LinkState == 4 ? GCSTelemetryStats.Status : 0 )
|
||||
|
||||
property real home_heading: 180/3.1415 * Math.atan2(TakeOffLocation.East - PositionState.East,
|
||||
TakeOffLocation.North - PositionState.North)
|
||||
@ -112,7 +115,7 @@ Item {
|
||||
elementName: "telemetry-status"
|
||||
|
||||
Text {
|
||||
text: ["Disconnected","HandshakeReq","HandshakeAck","Connected"][GCSTelemetryStats.Status]
|
||||
text: ["Disconnected","HandshakeReq","HandshakeAck","Connected"][tele_status.toString()]
|
||||
|
||||
anchors.centerIn: parent
|
||||
font.pixelSize: Math.floor(parent.height*1.2)
|
||||
@ -130,7 +133,8 @@ Item {
|
||||
property int minTxRateNumber : index+1
|
||||
elementName: "tx" + minTxRateNumber
|
||||
sceneSize: info.sceneSize
|
||||
visible: txNumberBar.txRateNumber >= minTxRateNumber
|
||||
visible: txNumberBar.txRateNumber >= minTxRateNumber && ((GCSTelemetryStats.Status ==3 && OPLinkStatus.LinkState == 4 )
|
||||
|| (GCSTelemetryStats.Status ==3 && OPLinkStatus.LinkState == 1 ))
|
||||
}
|
||||
}
|
||||
|
||||
@ -144,7 +148,8 @@ Item {
|
||||
property int minRxRateNumber : index+1
|
||||
elementName: "rx" + minRxRateNumber
|
||||
sceneSize: info.sceneSize
|
||||
visible: rxNumberBar.rxRateNumber >= minRxRateNumber
|
||||
visible: rxNumberBar.rxRateNumber >= minRxRateNumber && ((GCSTelemetryStats.Status ==3 && OPLinkStatus.LinkState == 4 )
|
||||
|| (GCSTelemetryStats.Status ==3 && OPLinkStatus.LinkState == 1 ))
|
||||
}
|
||||
}
|
||||
|
||||
@ -188,7 +193,7 @@ Item {
|
||||
width: scaledBounds.width * sceneItem.width
|
||||
height: scaledBounds.height * sceneItem.height
|
||||
y: Math.floor(scaledBounds.y * sceneItem.height)
|
||||
visible: true
|
||||
visible: OPLinkStatus.LinkState == 4 //OPLink Connected
|
||||
|
||||
MouseArea { id: total_dist_mouseArea; anchors.fill: parent; onClicked: reset_distance()}
|
||||
|
||||
|
@ -4487,10 +4487,6 @@ p, li { white-space: pre-wrap; }
|
||||
<source> Unknown compatibility level: </source>
|
||||
<translation type="unfinished"> Niveau de compatibilité inconnu : </translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Unknown compatibility level: </source>
|
||||
<translation type="vanished">Niveau de compatibilité inconnu : </translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>LoggingGadgetFactory</name>
|
||||
@ -6456,8 +6452,7 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>Avoid &quot;Manual&quot; for multirotors! Never select &quot;ALtitude&quot;, &quot;VelocityControl&quot; or &quot;CruiseControl&quot; on a fixed wing!</p></body></html></source>
|
||||
<translatorcomment>Typo : "AL"titude + allow translation on dropdown menu Altitude - Velocity control - CruiseControl</translatorcomment>
|
||||
<source><html><head/><body><p>Avoid &quot;Manual&quot; for multirotors! Never select &quot;Altitude&quot;, &quot;VelocityControl&quot; or &quot;CruiseControl&quot; on a fixed wing!</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Éviter &quot;Manuel&quot; pour les multirotors ! Ne jamais sélectionner &quot;Altitude&quot;, &quot;VelocityControl&quot; ou &quot;CruiseControl&quot; sur une aile volante !</p></body></html></translation>
|
||||
</message>
|
||||
</context>
|
||||
@ -6716,10 +6711,6 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
|
||||
<source>Form</source>
|
||||
<translation>Formulaire</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Current value of slider.</source>
|
||||
<translation type="vanished">Valeur actuelle du curseur.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Link</source>
|
||||
@ -6801,7 +6792,7 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Calibration</source>
|
||||
<translation type="unfinished">Étalonnage</translation>
|
||||
<translation>Étalonnage</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -6833,10 +6824,6 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
|
||||
<source>Clear</source>
|
||||
<translation>Effacer tout</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Telemetry link not established.</source>
|
||||
<translation type="vanished">Lien de télémétrie coupé.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Ctrl+S</source>
|
||||
@ -7031,117 +7018,16 @@ Une valeur de 0.00 désactive le filtre.</translation>
|
||||
<source>Calibration instructions</source>
|
||||
<translation>Instructions d'étalonnage</translation>
|
||||
</message>
|
||||
<message>
|
||||
<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:9pt; font-weight:400; font-style:normal;">
|
||||
<table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;">
|
||||
<tr>
|
||||
<td style="border: none;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:16pt; font-weight:600; font-style:italic;">Help</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Following steps #1, #2 and #3 are necessary. Step #4 is optional, it may helps you achieve the best possible results.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; font-style:italic;">#1: Multi-Point calibration</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This calibration will compute the scale for Magnetometer or Accelerometer sensors. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Press &quot;Calibrate Mag&quot; or &quot;Calibrate Accel&quot; to begin calibration, and follow the instructions which will be displayed here. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">For optimal calibration perform the Accel calibration with the board not mounted to the craft. in this way you can accurately level the board on your desk/table during the process. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Magnetometer calibration need to be performed inside your plane/copter to account for metal/magnetic stuffs on board.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt; font-weight:600; font-style:italic;">Note 1:</span><span style=" font-size:11pt;"> Your </span><span style=" font-size:11pt; font-weight:600;">HomeLocation must be set first</span><span style=" font-size:11pt;">, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt; font-weight:600; font-style:italic;">Note 2:</span><span style=" font-size:11pt;"> There is no need to point exactly at South/North/West/East. They are just used to easily tells the user how to point the plane/craft. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">You can simply assume that North is in front of you, right is East etc. and perform the calibration this way.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; font-style:italic;">#2: Board level calibration</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step will ensure that board leveling is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; font-style:italic;">#3: Gyro Bias calculation</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step allows to calibrate the gyro measured value when the board is steady. To perform the calibration leave the board/aircraft completely steady and click start. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; font-style:italic;">#4: Thermal Calibration</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">The calibration will compute sensors bias variations at different temperatures while the board warms up.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This allow a certain amount of correction of those bias variations against temperature changes. It does improve both altitude hold and yaw performances.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">To perform this calibration leave the board to cool down at room temperature in the coldest places available. after 15-20 minutes attach the usb connector to the board and Click the Calibrate button leaving the board steady. Wait until completed</span></p>
|
||||
<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p></td></tr></table></body></html></source>
|
||||
<translation type="obsolete"><!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:9pt; font-weight:400; font-style:normal;">
|
||||
<table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;">
|
||||
<tr>
|
||||
<td style="border: none;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:16pt; font-weight:600; font-style:italic;">Aide</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Les étapes #1, #2 et #3 sont nécessaires. L'étape #4 vous aidera à atteindre les meilleurs résultats possibles.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; font-style:italic;">#1 : Étalonnage multipoints</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Cet étalonnage va calculer les échelles pour les capteurs Accéléromètres ou Magnétomètre. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Cliquer sur &quot;Étalonner Accéléromètre&quot; ou &quot;Étalonner Magnétomètre&quot; pour démarrer l'étalonnage puis suivez les instructions qui seront affichées ici. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Pour un calibrage optimal effectuez l'étalonnage des Accéléromètres sans monter la carte sur l'appareil, de cette façon vous pourrez précisément la mettre de niveau sur votre bureau/table pendant le processus. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Le calibrage du magnétomètre devra être effectué avec la carte montée dans votre appareil pour tenir compte des champs magnétiques/ masses métalliques à bord.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt; font-weight:600; font-style:italic;">Note 1:</span><span style=" font-size:11pt;"> Votre </span><span style=" font-size:11pt; font-weight:600;">PositionHome doit être définie en premier</span><span style=" font-size:11pt;">, ainsi que le vecteur de champ magnétique (Be) et l'accélération due à la gravité (g_e).</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt; font-weight:600; font-style:italic;">Note 2:</span><span style=" font-size:11pt;"> Vous n'avez pas besoin de pointer exactement dans les directions Sud/Nord/Ouest/Est. Ceci est simplement utilisé pour indiquer clairement à l'utilisateur comment orienter son appareil.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Vous pouvez simplement admettre que le Nord est face à vous, l'Est à votre droite, etc. et effectuer l'étalonnage de cette façon.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; font-style:italic;">#2 : Étalonnage du niveau de la carte</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Cette étape fera en sorte que la mise de niveau de la carte soit parfaite. Veuillez placer l'appareil le plus horizontalement possible (utilisez un niveau à bulle si nécessaire), puis appuyez sur Démarrer ci-dessus et ne bougez pas du tout votre appareil jusqu'à la fin de l'étalonnage.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; font-style:italic;">#3 : Étalonnage de l'ajustement des Gyroscopes</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Cette étape permet d'étalonner la valeur mesurée sur les gyros lorsque la carte ne bouge pas. Pour effectuer l'étalonnage laissez la carte/l'appareil sans bouger et cliquez sur Démarrer. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; font-style:italic;">#4 : Étalonnage de la compensation de température</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Cet étalonnage va calculer les variations des capteurs à plusieurs températures lors du réchauffement de la carte.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Ceci permet un certain niveau de correction sur la variation des ajustements en fonction des changements de température. Il améliore à la fois le maintien d'altitude et les performances sur l'axe de lacet.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Pour effectuer cette calibration laissez refroidir la carte à température ambiante dans un endroit le plus froid possible. Après 15-20 minutes branchez le connecteur USB à la carte, cliquez sur le bouton Démarrer et ne bougez plus la carte. Attendez jusqu'à la fin du processus.</span></p>
|
||||
<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p></td></tr></table></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>#1: Accelerometer/Magnetometer calibration</source>
|
||||
<translation type="vanished">#1 : Étalonnage Accéléromètres/Magnétomètre</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Launch accelerometer range and bias calibration.</source>
|
||||
<translation>Démarrer l'étalonnage des plages et ajustements des accéléromètres.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Calibrate Accel</source>
|
||||
<translation type="vanished">Étalonner Accéléromètre</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Launch magnetometer range and bias calibration.</source>
|
||||
<translation>Démarrer l'étalonnage des plages et ajustements du magnétomètre.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Calibrate Mag</source>
|
||||
<translation type="vanished">Étalonner Magnétomètre</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>#2: Board level calibration</source>
|
||||
<translation type="vanished">#2 : Étalonnage du niveau de la carte</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>#3: Gyro bias calibration</source>
|
||||
<translation type="vanished">#3 : Étalonnage de l'ajustement des Gyros</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>#4*: Thermal calibration</source>
|
||||
<translatorcomment>Typo : Why "*" ? Optional ?</translatorcomment>
|
||||
<translation type="obsolete">#4* : Étalonnage de la compensation de température</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Temperature</source>
|
||||
<translation type="vanished">Température</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>°C - Temperature rise</source>
|
||||
<translation type="vanished">°C - Augmentation température</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>this contains the current status of the thermal calibration wizard</source>
|
||||
<translation type="vanished">ceci contient le statut actuel de l'assistant d'étalonnage température</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>End</source>
|
||||
@ -7205,6 +7091,7 @@ p, li { white-space: pre-wrap; }
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:10pt; font-weight:400; font-style:normal;">
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-weight:600;"><br /></p></body></html></source>
|
||||
<translatorcomment>Blank text ?</translatorcomment>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
@ -7218,82 +7105,72 @@ p, li { white-space: pre-wrap; }
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
<table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;">
|
||||
<tr>
|
||||
<td style="border: none;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;">Help</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Steps 1, 2 and 3 are necessary.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Step 4 is optional but may help achieve the best possible results.</span></p>
|
||||
<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 1: Accelerometer and Magnetometer calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">These calibrations will compute the scale for Magnetometer and Accelerometer sensors. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Press </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> to begin calibration and follow the instructions which will be displayed. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">For optimal calibration, perform the acceleration calibration with the board not mounted in the craft.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">In this way you can accurately level the board on your desk/table during the process. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Magnetometer calibration needs to be performed inside your plane/copter to account for metal/magnetic elements on board.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Note 1</span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> </span><span style=" font-family:'Ubuntu'; font-size:11pt; text-decoration: underline;">Your HomeLocation must be set first</span><span style=" font-family:'Ubuntu'; font-size:11pt;">, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Note 2</span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> There is no need to point exactly at South/North/West/East. These are just used to easily tell the user how to point the plane/craft. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">You can simply assume that North is in front of you, right is East, etc., and perform the calibration this way.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 2: Board level calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step will ensure that board leveling is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> and do not move your airframe at all until the end of the calibration.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 3: Gyro bias calculation</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step allows to calibrate the gyro measured value when the board is steady. To perform the calibration leave the board/aircraft completely steady and pres </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start</span><span style=" font-family:'Ubuntu'; font-size:11pt;">. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 4: Thermal calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">The calibration will compute sensors bias variations at different temperatures while the board warms up.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This allows a certain amount of correction of those bias variations against temperature changes. It does improve both altitude hold and yaw performances.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">To perform this calibration leave the board to cool down at room temperature in the coldest places available.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">After 15-20 minutes, attach the usb connector to the board and press </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start,</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> leaving the board steady. Wait until completed.</span></p></td></tr></table></body></html></source>
|
||||
<translation type="unfinished"><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600;">Help</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Steps 1, 2 and 3 are necessary.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Step 4 is optional but may help achieve the best possible results.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 1: Accelerometer and Magnetometer calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step will calibrate the scale for the Magnetometer and the Accelerometer sensors. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;"> to begin, and follow the instructions for each step. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">For best results with the accelerometer calibration, it is advised that it be performed with a free unmounted flight controller as this allows one to accurately position the board for each orientation in the sequence.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">The magnetometer calibration must be performed with the board mounted in the airframe in order for the measurements to incorporate any bias produced by local onboard metal/magnetic elements.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Note 1: Before the magnetometer or the accelerometer calibration is performed your Home Location must be set. This step is needed in order to determine the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Note 2: There is no need to align the airframe exactly south, north, east or west during the individual steps. The directions indicated serve only to tell you in which direction the airframe should be positioned relative to some point. One can simply assume that North is in front of you, East is to the right, West is to the left and South is pointing at you.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 2: Board level calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step will ensure that board leveling is accurate. Place the airframe as horizontally as possible (use a spirit level if necessary), then press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;">. Do not move the airframe at all until the end of the calibration.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 3: Gyro bias calculation</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step will allow you to calibrate the gyro measured value when the board is steady. To perform the calibration leave the board/airframe completely stationary and press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;">. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 4: Thermal calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">The calibration will compute sensors bias variations at different temperatures while the board warms up.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This allows a certain amount of correction of those bias variations against temperature changes. It improves altitude hold accuracy and reduces yaw drift.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">To perform this calibration disconnect any power from the board and leave it to cool down at room temperature for 15-20 minutes. Then attach the usb connector to the board and press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;">, leaving the board completely stationary. Wait until complete.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p></body></html></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 style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;">Aide</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Les étapes 1, 2 et 3 sont nécessaires.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">L'étape 4 est optionnelle et vous aidera à atteindre les meilleurs résultats possibles.</span></p>
|
||||
<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Étape 1: Étalonnage des Accéléromètres et Magnétomètre</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Cet étalonnage va calculer les échelles pour les capteurs Accéléromètres ou Magnétomètre. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Cliquer sur </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Démarrer</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> pour démarrer l'étalonnage puis suivez les instructions qui seront affichées. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Pour un calibrage optimal effectuez l'étalonnage des Accéléromètres sans monter la carte sur l'appareil.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">De cette façon vous pourrez précisément la mettre de niveau sur votre bureau/table pendant le processus. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Le calibrage du magnétomètre devra être effectué avec la carte montée dans votre appareil pour tenir compte des champs magnétiques/ masses métalliques à bord.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Note 1</span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> </span><span style=" font-family:'Ubuntu'; font-size:11pt; text-decoration: underline;">Votre PositionHome doit être définie en premier</span><span style=" font-family:'Ubuntu'; font-size:11pt;">, ainsi que le vecteur de champ magnétique (Be) et l'accélération due à la gravité (g_e).</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Note 2</span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> Vous n'avez pas besoin de pointer exactement dans les directions Sud/Nord/Ouest/Est. Ceci est simplement utilisé pour indiquer clairement à l'utilisateur comment orienter son appareil.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Vous pouvez simplement admettre que le Nord est face à vous, l'Est à votre droite, etc. et effectuer l'étalonnage de cette façon.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Étape 2: Étalonnage du niveau de la carte</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Cette étape fera en sorte que la mise de niveau de la carte soit parfaite. Veuillez placer l'appareil le plus horizontalement possible (utilisez un niveau à bulle si nécessaire), puis appuyez sur </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Démarrer</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> et ne bougez pas du tout votre appareil jusqu'à la fin de l'étalonnage.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Étape 3: Étalonnage de l'ajustement des Gyroscopes</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Cette étape permet d'étalonner la valeur mesurée sur les gyros lorsque la carte ne bouge pas. Pour effectuer l'étalonnage laissez la carte/l'appareil sans bouger et cliquez sur </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Démarrer</span><span style=" font-family:'Ubuntu'; font-size:11pt;">. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Étape 4: Étalonnage de la compensation de température</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Cet étalonnage va calculer les variations des capteurs à plusieurs températures lors du réchauffement de la carte.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Ceci permet un certain niveau de correction sur la variation des ajustements en fonction des changements de température. Il améliore à la fois le maintien d'altitude et les performances sur l'axe de lacet.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Pour effectuer cette calibration laissez refroidir la carte à température ambiante dans un endroit le plus froid possible.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Après 15-20 minutes branchez le connecteur USB à la carte, cliquez sur le bouton </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Démarrer,</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> et ne bougez plus la carte. Attendez jusqu'à la fin du processus.</span></p></td></tr></table></body></html></translation>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600;">Aide</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Les étapes 1, 2 et 3 sont nécessaires</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">L'étape 4 est optionnelle mais vous aidera à atteindre les meilleurs résultats possibles.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Étape 1 : Étalonnage des Accéléromètres et Magnétomètre</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Cet étape va étalonner les échelles des capteurs Accéléromètres ou Magnétomètre. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Appuyez sur </span><span style=" font-size:11pt; font-style:italic;">Démarrer</span><span style=" font-size:11pt;"> pour commencer et suivez les instructions pour chaque étape. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Pour de meilleurs résultats avec l'étalonnage des accéléromètres, il est conseillé de le réaliser avec le contrôleur de vol démonté, ce qui permet de positionner avec précision la carte pour chaque orientation de la séquence.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">L'étalonnage du magnétomètre devra être effectué avec la carte montée sur votre appareil pour tenir compte des déviations produites par les champs magnétiques / masses métalliques à bord.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Note 1 : Avant de débuter l'étalonnage du magnétomètre ou des accéléromètres votre Position Home devra être réglée. Cela est nécessaire pour déterminer le vecteur de champ magnétique (Be) et l'accélération due à la gravité (g_e) de votre position.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Note 2 : Vous n'avez pas besoin d'orienter votre appareil exactement vers le sud, nord, est, ouest à chaque étape. Les orientations demandées servent uniquement à vous indiquer dans quelle direction l'appareil doit être positionné par rapport à un point. Vous pouvez simplement admettre que le Nord est face à vous, l'Est est à droite, l'Ouest à gauche et le Sud pointe vers vous.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Étape 2 : Étalonnage du niveau de la carte</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Cette étape fera en sorte que la mise de niveau de la carte soit parfait. Veuillez placer l'appareil le plus horizontalement possible (utilisez un niveau à bulle si nécessaire), puis appuyez sur </span><span style=" font-size:11pt; font-style:italic;">Démarrer</span><span style=" font-size:11pt;">. Ne bougez pas du tout votre appareil jusqu’à la fin de l'étalonnage.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Étape 3 : Étalonnage de l'ajustement des Gyroscopes</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Cette étape permet d'étalonner la valeur mesurée sur les gyros lorsque la carte ne bouge pas. Pour effectuer l'étalonnage laissez la carte/l'appareil sans bouger et appuyez sur </span><span style=" font-size:11pt; font-style:italic;">Démarrer</span><span style=" font-size:11pt;">. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Étape 4 : Étalonnage de la compensation de température</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Cet étalonnage va calculer les variations des capteurs à plusieurs températures lors du réchauffement de la carte.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Ceci permet un certain niveau de correction sur la variation des ajustements en fonction des changements de température. Il améliore à la fois le maintien d'altitude et les performances sur l'axe de lacet.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Pour effectuer cet étalonnage, déconnectez toutes les alimentations de la carte et laissez-là refroidir à température ambiante pendant 15-20 minutes. Branchez ensuite la prise USB sur la carte, appuyez sur </span><span style=" font-size:11pt; font-style:italic;">Démarrer</span><span style=" font-size:11pt;"> et ne bougez plus la carte. Attendez jusqu'à la fin du processus.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p></body></html></translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
@ -8057,14 +7934,12 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<translation><html><head/><body><p>Ceci ajuste le niveau de stabilité que votre véhicule aura en vol incliné (ex. vol en avançant) en mode Attitude. Ajouter une valeur d'intégrale en mode Attitude lorsque une intégrale est présente en mode Rate n'est pas recommandé.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>This sets the maximum value of the integral (KP) that is used in Rate mode.</p></body></html></source>
|
||||
<translation><html><head/><body><p>Ceci limite la valeur maximale de l'intégrale (KP) qui est utilisée en mode Rate.</p></body></html></translation>
|
||||
<translation type="vanished"><html><head/><body><p>Ceci limite la valeur maximale de l'intégrale (KP) qui est utilisée en mode Rate.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>This sets the maximum value of the integral (KP) that is used in AttitudeMode.</p></body></html></source>
|
||||
<translation><html><head/><body><p>Ceci limite la valeur maximale de l'intégrale (KP) qui est utilisée en mode Attitude.</p></body></html></translation>
|
||||
<translation type="vanished"><html><head/><body><p>Ceci limite la valeur maximale de l'intégrale (KP) qui est utilisée en mode Attitude.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -8164,7 +8039,7 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<message>
|
||||
<location/>
|
||||
<source>PowerTrim</source>
|
||||
<translation type="unfinished">AjustPuissance</translation>
|
||||
<translation>AjustPuissance</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -8175,17 +8050,17 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<message>
|
||||
<location/>
|
||||
<source>MaxPowerFactor</source>
|
||||
<translation type="unfinished">FacteurMaxiPuissance</translation>
|
||||
<translation>FacteurMaxiPuissance</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>MaxAngle</source>
|
||||
<translation type="unfinished">AngleMaxi</translation>
|
||||
<translation>AngleMaxi</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>InvertedPower</source>
|
||||
<translation type="unfinished">PuissanceRenversé</translation>
|
||||
<translation>PuissanceRenversé</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -8212,27 +8087,27 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>How fast the vehicle should climb or descent to compensate a certain altitude difference. higher values could result in more accurate altitude hold but also more violent control actions, lower values are safer and ensure smoother flight. The default value should be fine for the majority of crafts.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Détermine la vitesse à laquelle doit monter ou descendre le véhicule pour compenser une certaine différence d'altitude. Des valeurs plus élevées pourraient entraîner un maintien d'altitude plus précis mais aussi des réactions plus violentes, des valeurs inférieures sont plus sûres et donnent un vol plus doux. La valeur par défaut devrait être bonne pour la plupart des appareils.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Détermine la vitesse à laquelle doit monter ou descendre le véhicule pour compenser une certaine différence d'altitude. Des valeurs plus élevées pourraient entraîner un maintien d'altitude plus précis mais aussi des réactions plus violentes, des valeurs inférieures sont plus sûres et donnent un vol plus doux. La valeur par défaut devrait être bonne pour la plupart des appareils.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>How much the vehicle should throttle up or down to compensate or achieve a certain vertical speed. Higher values lead to more aggressive throttle changes and could lead to oscillations. This is the most likely candidate to change depending on the crafts engine thrust. Heavy craft with weak engines might require higher values.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Détermine de combien le véhicule augmente ou diminue les gaz pour compenser ou atteindre une certaine vitesse verticale. Des valeurs plus élevées entraînent des variations de gaz plus agressives qui peuvent produire des oscillations. C'est le paramètre à changer en fonction de la poussée moteur de l'appareil. Des appareils chargés avec des moteurs faibles peuvent demander des valeurs plus élevées.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Détermine de combien le véhicule augmente ou diminue les gaz pour compenser ou atteindre une certaine vitesse verticale. Des valeurs plus élevées entraînent des variations de gaz plus agressives qui peuvent produire des oscillations. C'est le paramètre à changer en fonction de la poussée moteur de l'appareil. Des appareils chargés avec des moteurs faibles peuvent demander des valeurs plus élevées.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>How fast the vehicle should adjust its neutral throttle estimation. Altitude assumes that when engaged the throttle is in the range required to hover. If the throttle is a lot higher or lower, it needs to adjust this &quot;throttle trim&quot; Higher values make it do this adjustment faster, but this could lead to ugly oscillations. Leave at default unless you know what you are doing.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Détermine la vitesse à laquelle le véhicule doit ajuster son estimation de gaz au neutre. Le Maintien d'Altitude suppose que lorsque il est activé, il est la plage nécessaire pour se maintenir en l'air. Si les gaz est beaucoup plus élevé ou plus bas, il faut ajuster ce "trim". Des valeurs plus élevées peuvent lui permettre de faire cet ajustement plus rapidement mais cela pourrait conduire à des oscillations. A laisser par défaut, à moins de savoir ce que vous faites.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Détermine la vitesse à laquelle le véhicule doit ajuster son estimation de gaz au neutre. Le Maintien d'Altitude suppose que lorsque il est activé, il est la plage nécessaire pour se maintenir en l'air. Si les gaz est beaucoup plus élevé ou plus bas, il faut ajuster ce "trim". Des valeurs plus élevées peuvent lui permettre de faire cet ajustement plus rapidement mais cela pourrait conduire à des oscillations. A laisser par défaut, à moins de savoir ce que vous faites.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Max rate limit (all modes) (deg/s)</source>
|
||||
<translation type="unfinished">Limitation Rate max (tous modes) (deg/s)</translation>
|
||||
<translation>Limitation Rate max (tous modes) (deg/s)</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>Percentage of full stick where the transition from Attitude to Rate occurs. This transition always occurs when the aircraft is exactly inverted (bank angle 180 degrees). Small values are dangerous because they cause flips at small stick angles. Values significantly over 100 act like attitude mode and can never flip.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Pourcentage d'une position de manche à fond où la transition du mode Attitude vers le mode Rate intervient. Cette transition intervient à chaque fois lorsque l'appareil est exactement à l'envers (inclinaison d'un angle de 180 degrés). Des valeurs faibles sont dangereuses car elles provoquent des pirouettes avec de petits mouvements aux manches. Des valeurs significativement au dessus de 100 font que l'appareil ne peut jamais se retourner et reviennent à fonctionner en mode Attitude.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Pourcentage d'une position de manche à fond où la transition du mode Attitude vers le mode Rate intervient. Cette transition intervient à chaque fois lorsque l'appareil est exactement à l'envers (inclinaison d'un angle de 180 degrés). Des valeurs faibles sont dangereuses car elles provoquent des pirouettes avec de petits mouvements aux manches. Des valeurs significativement au dessus de 100 font que l'appareil ne peut jamais se retourner et reviennent à fonctionner en mode Attitude.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -8248,7 +8123,7 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>CP helis can set this to Reversed to automatically reverse the direction of thrust when inverted. Fixed pitch copters, including multicopters, should leave this set at Unreversed. Unreversed direction with Boosted power may be dangerous because it adds power and the thrust direction moves the aircraft towards the ground.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Les hélicos CP peuvent régler ceci à Reversed pour inverser automatiquement la direction de la poussée en vol dos. Les hélicos à pas fixe, multicoptères inclus, doivent laisser ce paramètre à Unreversed. L'association du paramètre Unreversed avec Boosted ci-dessous peut-être dangereuse car elle ajoute de la puissance et la direction de la poussée déplace l'appareil vers le sol.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Les hélicos CP peuvent régler ceci à Reversed pour inverser automatiquement la direction de la poussée en vol dos. Les hélicos à pas fixe, multicoptères inclus, doivent laisser ce paramètre à Unreversed. L'association du paramètre Unreversed avec Boosted ci-dessous peut-être dangereuse car elle ajoute de la puissance et la direction de la poussée déplace l'appareil vers le sol.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -8259,17 +8134,17 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<message>
|
||||
<location/>
|
||||
<source>InvrtdThrustRev</source>
|
||||
<translation type="unfinished">InversPousséeRenversé</translation>
|
||||
<translation>InversPousséeRenversé</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>The bank angle where CruiseControl goes into inverted power mode. InvertedThrustReverse and InvertedPower control the direction and amount of power when in inverted mode.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Ceci correspond à l'angle d'inclinaison où CruiseControl passe en mode puissance renversé. InversPousséeRenversé et PuissanceRenversée contrôlent la direction et la quantité de puissance lorque vous êtes en mode inversé</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Ceci correspond à l'angle d'inclinaison où CruiseControl passe en mode puissance renversé. InversPousséeRenversé et PuissanceRenversée contrôlent la direction et la quantité de puissance lorsque vous êtes en mode inversé</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>Really just a safety limit. 3.0 means it will not use more than 3 times the power the throttle/collective stick is requesting.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Juste une limitation de sécurité. 3.0 signifie qu'il n'utilisera pas plus de 3 fois la puissance demandée par le manche de gaz/collectif.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Juste une limitation de sécurité. 3.0 signifie qu'il n'utilisera pas plus de 3 fois la puissance demandée par le manche de gaz/collectif.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -8279,12 +8154,12 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<message>
|
||||
<location/>
|
||||
<source>MinThrust</source>
|
||||
<translation type="unfinished">PousséeMini</translation>
|
||||
<translation>PousséeMini</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>Throttle/Collective stick below this amount disables Cruise Control. Also, by default Cruise Control forces the use of this value for thrust when InvertedPower setting is Zero and the copter is inverted. CP helis probably want this set to -100%. For safety with fixed pitch copters (including multicopters), never set this so low that the trimmed throttle stick cannot get below it or your motor(s) will still run with the throttle stick all the way down. Fixed pitch throttle sticks go from -100 to 0 in the first tiny bit of throttle stick (and then up to 100 using the rest of the throttle range), so for example, a lot of &quot;high throttle trim&quot; will keep the stick from ever commanding less than 5% so it won't be possible to stop the motors with the throttle stick. Banking the copter in your hand in this state will make the motors speed up.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Lorsque le manche de gaz/collectif est en dessous de cette valeur, cela désactive Cruise Control. En outre, Cruize Control impose l'utilisation de cette valeur de manche de gaz lorsque le paramètre PuissanceInversé est à zéro et l'hélicoptère est à l'envers.</p><p>Les hélicos CP auront besoin probablement d'une valeur fixée à -100. Par mesure de sécurité avec les pas fixes (multicoptères inclus), ne jamais définir une valeur trop basse pour qu'un manche de gaz baissé puisse descendre en dessous de cette valeur ou le(s) moteur(s) continuent de tourner avec le manche de gaz au mini. Le manche de gaz pour pas fixe va de -100 à 0 dans la première petite plage de la course du manche (puis jusqu'à 100 dans la plage de gaz restante) donc par exemple un &quot;trim élevé sur le manche de gaz&quot; va maintenir les gaz au dessus de 5% si bien qu'il ne sera pas possible d'arrêter les moteurs avec la manche des gaz. Le fait d'incliner l'appareil à la main dans cet état fera accélérer les moteurs.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Lorsque le manche de gaz/collectif est en dessous de cette valeur, cela désactive Cruise Control. En outre, Cruize Control impose l'utilisation de cette valeur de manche de gaz lorsque le paramètre PuissanceInversé est à zéro et l'hélicoptère est à l'envers.</p><p>Les hélicos CP auront besoin probablement d'une valeur fixée à -100. Par mesure de sécurité avec les pas fixes (multicoptères inclus), ne jamais définir une valeur trop basse pour qu'un manche de gaz baissé puisse descendre en dessous de cette valeur ou le(s) moteur(s) continuent de tourner avec le manche de gaz au mini. Le manche de gaz pour pas fixe va de -100 à 0 dans la première petite plage de la course du manche (puis jusqu'à 100 dans la plage de gaz restante) donc par exemple un &quot;trim élevé sur le manche de gaz&quot; va maintenir les gaz au dessus de 5% si bien qu'il ne sera pas possible d'arrêter les moteurs avec la manche des gaz. Le fait d'incliner l'appareil à la main dans cet état fera accélérer les moteurs.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -8295,7 +8170,7 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>Multi-copters should probably use 80% to 90% to leave some headroom for stabilization. CP helis can set this to 100%.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Les multicoptères devraient probablement utiliser une valeur de 80% à 90% afin de laisser une certaine marge pour la stabilisation. Les hélicos CP peuvent définir cette valeur à 100%.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Les multicoptères devraient probablement utiliser une valeur de 80% à 90% afin de laisser une certaine marge pour la stabilisation. Les hélicos CP peuvent définir cette valeur à 100%.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -8306,7 +8181,7 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<message>
|
||||
<location/>
|
||||
<source>MaxThrust</source>
|
||||
<translation type="unfinished">PousséeMaxi</translation>
|
||||
<translation>PousséeMaxi</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -8317,12 +8192,12 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>If you find that quickly moving the stick around a lot makes the copter climb a bit, adjust this number down a little. It will be a compromise between climbing a little with lots of stick motion and descending a little with minimal stick motion.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Si vous trouvez qu'un petit mouvement rapide de manche fait légèrement monter l'hélicoptère, baissez un petit peu cette valeur. Ce sera un compromis entre une montée légère avec beaucoup de mouvements de manche et descente légère avec un mouvement de manche minime.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Si vous trouvez qu'un petit mouvement rapide de manche fait légèrement monter l'hélicoptère, baissez un petit peu cette valeur. Ce sera un compromis entre une montée légère avec beaucoup de mouvements de manche et descente légère avec un mouvement de manche minime.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>The amount of power used when in inverted mode. Zero (min throttle stick for fixed pitch copters includding multicopters, neutral collective for CP), Normal (uses stick value), or Boosted (boosted according to bank angle). Beginning multicopter pilots should leave this set to Zero to automatically reduce throttle during flips. Boosted power with Unreversed direction may be dangerous because it adds power and the thrust direction moves the aircraft towards the ground.</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>La quantité de puissance utilisée en vol dos. Zero (PousséeMini pour les hélicos à pas fixe, multicoptères inclus, collectif au neutre pour hélicos CP), Normal (utilise la valeur du manche), ou Boosted (boosté en fonction de l'angle d'inclinaison). Les pilotes débutants en multicoptère devraient laisser ce paramètre à Zero pour automatiquement reduire les gaz durant les flips. L'association du paramètre Boosted avec Unreversed ci-dessus peut-être dangereuse car elle ajoute de la puissance et la direction de la poussée déplace l'appareil vers le sol.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>La quantité de puissance utilisée en vol dos. Zero (PousséeMini pour les hélicos à pas fixe, multicoptères inclus, collectif au neutre pour hélicos CP), Normal (utilise la valeur du manche), ou Boosted (boosté en fonction de l'angle d'inclinaison). Les pilotes débutants en multicoptère devraient laisser ce paramètre à Zero pour automatiquement reduire les gaz durant les flips. L'association du paramètre Boosted avec Unreversed ci-dessus peut-être dangereuse car elle ajoute de la puissance et la direction de la poussée déplace l'appareil vers le sol.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -8355,7 +8230,17 @@ Useful if you have accidentally changed some settings.</source>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>Motor response time to go from min thrust to max thrust. It allows thrust anticipation on entering/exiting inverted mode</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Temps de réponse du moteur pour passer de la poussée minimum à la poussée maximum. Cela permet une anticipation lors de l'entrée/sortie du mode inversé.</p></body></html></translation>
|
||||
<translation><html><head/><body><p>Temps de réponse du moteur pour passer de la poussée minimum à la poussée maximum. Cela permet une anticipation lors de l'entrée/sortie du mode inversé.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>This sets the maximum value of the integral (KI) that is used in Rate mode.</p></body></html></source>
|
||||
<translation><html><head/><body><p>Ceci limite la valeur maximale de l'intégrale (KI) qui est utilisée en mode Rate.</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>This sets the maximum value of the integral (KI) that is used in AttitudeMode.</p></body></html></source>
|
||||
<translation><html><head/><body><p>Ceci limite la valeur maximale de l'intégrale (KI) qui est utilisée en mode Attitude.</p></body></html></translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
@ -9069,7 +8954,7 @@ les données en cache</translation>
|
||||
<translation>Diagramme de Connexion</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+153"/>
|
||||
<location line="+156"/>
|
||||
<source>Save File</source>
|
||||
<translation>Enregistrer Fichier</translation>
|
||||
</message>
|
||||
@ -9420,17 +9305,19 @@ p, li { white-space: pre-wrap; }
|
||||
<translation>Hexacoptère</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+2"/>
|
||||
<location line="+8"/>
|
||||
<location line="+1"/>
|
||||
<source>Hexacopter Coax (Y6)</source>
|
||||
<translation>Hexacoptère Coax (Y6)</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+2"/>
|
||||
<location line="-7"/>
|
||||
<location line="+1"/>
|
||||
<source>Hexacopter X</source>
|
||||
<translation>Hexacoptère X</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+2"/>
|
||||
<location line="+1"/>
|
||||
<source>Hexacopter H</source>
|
||||
<translation>Hexacoptère H</translation>
|
||||
@ -9515,7 +9402,7 @@ p, li { white-space: pre-wrap; }
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<location filename="../../../src/plugins/setupwizard/pages/outputcalibrationpage.cpp" line="+261"/>
|
||||
<location filename="../../../src/plugins/setupwizard/pages/outputcalibrationpage.cpp" line="+267"/>
|
||||
<location line="+76"/>
|
||||
<location line="+28"/>
|
||||
<location line="+19"/>
|
||||
@ -10346,7 +10233,7 @@ p, li { white-space: pre-wrap; }
|
||||
<message>
|
||||
<location/>
|
||||
<source><html><head/><body><p>Reboot the board and clear its settings memory.</p><p> Useful if the board cannot boot properly.</p><p> Blue led starts blinking quick for 20-30 seconds than the board will start normally</p><p><br/></p><p>If telemetry is not running, select the link using the dropdown</p><p>menu on the right.</p><p>PLEASE NOTE: Supported with bootloader versions 4.0 and later</p></body></html></source>
|
||||
<translation type="unfinished"><html><head/><body><p>Redémarre la carte et efface ses paramètres en mémoire.</p><p> Utile si la carte n'arrive pas à démarrer correctement.</p><p> La Led Bleue commence à clignoter rapidement pendant 20-30 secondes puis la carte démarre normalement</p><p><br/></p><p>Si la télémétrie ne fonctionne pas, sélectionnez le lien utilisé avec la liste déroulante</p><p>située à droite.</p><p>VEUILLEZ NOTER : Supporté avec les versions de bootloaders 4.0 et supérieures</p></body></html></translation>
|
||||
<translation type="unfinished"><html><head/><body><p>Redémarre la carte et efface ses paramètres en mémoire.</p><p> Utile si la carte n'arrive pas à démarrer correctement.</p><p> La Led Bleue commence à clignoter rapidement pendant 20-30 secondes puis la carte démarre normalement</p><p><br/></p><p>Si la télémétrie ne fonctionne pas, sélectionnez le lien utilisé avec la liste déroulante située à droite.</p><p>VEUILLEZ NOTER : Supporté avec les versions de bootloaders 4.0 et supérieures</p></body></html></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -10379,11 +10266,29 @@ p, li { white-space: pre-wrap; }
|
||||
<context>
|
||||
<name>ConfigMultiRotorWidget</name>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp" line="+713"/>
|
||||
<location line="+179"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp" line="+696"/>
|
||||
<location line="+24"/>
|
||||
<location line="+31"/>
|
||||
<location line="+31"/>
|
||||
<location line="+25"/>
|
||||
<location line="+24"/>
|
||||
<location line="+24"/>
|
||||
<location line="+41"/>
|
||||
<location line="+200"/>
|
||||
<location line="+70"/>
|
||||
<source>Configuration OK</source>
|
||||
<translation>Configuration OK</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="-302"/>
|
||||
<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="+367"/>
|
||||
<source><font color='red'>ERROR: Assign all %1 motor channels</font></source>
|
||||
<translation><font color='red'>ERREUR : Veuillez affecter tous les %1 canaux moteurs</font></translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>ConfigCCHWWidget</name>
|
||||
@ -10980,7 +10885,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
|
||||
</message>
|
||||
<message>
|
||||
<location line="+3"/>
|
||||
<location line="+44"/>
|
||||
<location line="+47"/>
|
||||
<location line="+15"/>
|
||||
<location line="+25"/>
|
||||
<location line="+13"/>
|
||||
@ -10988,7 +10893,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
|
||||
<translation>Inconnu</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="-92"/>
|
||||
<location line="-95"/>
|
||||
<source>Vehicle type: </source>
|
||||
<translation>Type de véhicule : </translation>
|
||||
</message>
|
||||
@ -11027,6 +10932,11 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
|
||||
<source>Hexacopter Coax (Y6)</source>
|
||||
<translation>Hexacoptère Coax (Y6)</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+3"/>
|
||||
<source>Hexacopter H</source>
|
||||
<translation type="unfinished">Hexacoptère H</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+3"/>
|
||||
<source>Hexacopter X</source>
|
||||
@ -11146,7 +11056,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
|
||||
<translation>Écriture paramètres matériels</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+109"/>
|
||||
<location line="+113"/>
|
||||
<source>Writing actuator settings</source>
|
||||
<translation>Écriture paramètres actionneurs</translation>
|
||||
</message>
|
||||
@ -11192,7 +11102,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
|
||||
<translation>Écriture contrôles manuels par défaut</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+153"/>
|
||||
<location line="+154"/>
|
||||
<source>Preparing mixer settings</source>
|
||||
<translation>Préparation des paramètres de mixage</translation>
|
||||
</message>
|
||||
@ -12459,11 +12369,6 @@ Méfiez-vous de ne pas vous verrouiller l'accès !</translation>
|
||||
<translatorcomment>Pas toucher !</translatorcomment>
|
||||
<translation></translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>url:http://wiki.openpilot.org/x/dACrAQ</source>
|
||||
<translatorcomment>Lien wiki FR http://wiki.openpilot.org/x/B4BYAQ</translatorcomment>
|
||||
<translation type="vanished">url:http://wiki.openpilot.org/x/AwCEAQ</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
<source>Send settings to the board but do not save to the non-volatile memory</source>
|
||||
@ -13689,9 +13594,8 @@ p, li { white-space: pre-wrap; }
|
||||
<translation>OK</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/flightlog/flightlogdialog.cpp" line="+47"/>
|
||||
<source>Manage flight side logs</source>
|
||||
<translation>Gérer les logs de vol</translation>
|
||||
<translation type="vanished">Gérer les logs de vol</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
@ -13811,10 +13715,15 @@ Veuillez vérifier le fichier.
|
||||
<context>
|
||||
<name>FlightLogPlugin</name>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/flightlog/flightlogplugin.cpp" line="+60"/>
|
||||
<location filename="../../../src/plugins/flightlog/flightlogplugin.cpp" line="+61"/>
|
||||
<source>Manage flight side logs...</source>
|
||||
<translation>Gérer les logs de vol...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+20"/>
|
||||
<source>Manage flight side logs</source>
|
||||
<translation type="unfinished">Gérer les logs de vol</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>MonitorGadgetFactory</name>
|
||||
@ -14062,7 +13971,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
<context>
|
||||
<name>ConfigVehicleTypeWidget</name>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/config/configvehicletypewidget.cpp" line="+129"/>
|
||||
<location filename="../../../src/plugins/config/configvehicletypewidget.cpp" line="+130"/>
|
||||
<source>Multirotor</source>
|
||||
<translation>Multirotor</translation>
|
||||
</message>
|
||||
@ -14087,7 +13996,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
<translation type="unfinished">Personnalisé</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+270"/>
|
||||
<location line="+273"/>
|
||||
<source>http://wiki.openpilot.org/x/44Cf</source>
|
||||
<translatorcomment>Lien Wiki FR</translatorcomment>
|
||||
<translation>http://wiki.openpilot.org/x/IIBqAQ</translation>
|
||||
@ -14096,30 +14005,18 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
<context>
|
||||
<name>OpenPilot::GyroBiasCalibrationModel</name>
|
||||
<message>
|
||||
<source>Calibrating the gyroscopes. Keep the copter/plane steady...</source>
|
||||
<translation type="vanished">Étalonnage en cours des gyroscopes. Maintenez l'appareil sans le bouger...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Gyroscope calibration computed succesfully.</source>
|
||||
<translation type="vanished">Étalonnage des gyroscopes calculés avec succès.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/config/calibration/gyrobiascalibrationmodel.cpp" line="+98"/>
|
||||
<location filename="../../../src/plugins/config/calibration/gyrobiascalibrationmodel.cpp" line="+100"/>
|
||||
<source>Calibrating the gyroscopes. Keep the vehicle steady...</source>
|
||||
<translation>Étalonnage en cours des gyroscopes. Maintenez l'appareil sans le bouger...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+58"/>
|
||||
<location line="+55"/>
|
||||
<source>Gyroscope calibration completed successfully.</source>
|
||||
<translation>Étalonnage des gyroscopes calculé avec succès.</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>OpenPilot::LevelCalibrationModel</name>
|
||||
<message>
|
||||
<source>Place horizontally and click Save Position button...</source>
|
||||
<translation type="vanished">Positionner horizontalement et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/config/calibration/levelcalibrationmodel.cpp" line="+72"/>
|
||||
<source>Place horizontally and press Save Position...</source>
|
||||
@ -14140,69 +14037,9 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
<source>Board level calibration completed successfully.</source>
|
||||
<translation>Mise à niveau de la carte calculé avec succès.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Leave horizontally, rotate 180° along yaw axis and click Save Position button...</source>
|
||||
<translation type="vanished">Garder horizontal, tourner de 180° sur l'axe de Yaw et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Board leveling computed successfully.</source>
|
||||
<translation type="vanished">Mise à niveau de la carte calculé avec succès.</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>OpenPilot::SixPointCalibrationModel</name>
|
||||
<message>
|
||||
<source>Place horizontally, nose pointing north and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner horizontalement, le nez en direction du nord et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place with nose down, right side west and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner avec le nez vers le bas, le coté droit vers l'ouest et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place right side down, nose west and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner le flanc droit vers le bas, le nez en direction de l'ouest et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place upside down, nose east and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner à l'envers, le nez vers l'est et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place with nose up, left side north and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner le nez vers le haut, le flanc droit vers le nord et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place with left side down, nose south and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner avec le flanc gauche vers le bas, le nez vers le sud et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place horizontally and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner horizontalement et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place with nose down and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner avec le nez vers le bas et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place right side down and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner le flanc droit vers le bas et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place upside down and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner à l'envers et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place with nose up and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner avec le nez vers le haut et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Place with left side down and click Save Position button...</source>
|
||||
<translation type="obsolete">Positionner le flanc gauche vers le bas et cliquer sur le bouton Enregistrer Position...</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source><p>HomeLocation not SET.</p><p>Please set your HomeLocation and try again. Aborting calibration!</p></source>
|
||||
<translation type="obsolete"><p>Position Home non définie.</p><p>Veuillez définir votre position Home et essayez à nouveau. Étalonnage abandonné !</p></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/config/calibration/sixpointcalibrationmodel.cpp" line="+59"/>
|
||||
<source>Place horizontally, nose pointing north and press Save Position...</source>
|
||||
@ -14293,26 +14130,9 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
<source>Calibration failed! Please review the help and retry.</source>
|
||||
<translation>Échec étalonnage ! Veuillez lire les instructions et essayer à nouveau.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Sensor scale and bias computed succesfully.</source>
|
||||
<translatorcomment>Typo : succeSSfully.</translatorcomment>
|
||||
<translation type="obsolete">Échelle et ajustement du capteur calculés avec succès.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Bad calibration. Please review the instructions and repeat.</source>
|
||||
<translation type="obsolete">Mauvais étalonnage. Relisez les instructions et essayez à nouveau.</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>OpenPilot::CompensationCalculationTransition</name>
|
||||
<message>
|
||||
<source>Calibration completed succesfully</source>
|
||||
<translation type="vanished">Étalonnage terminé avec succès</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Calibration failed! Please read the instructions and retry.</source>
|
||||
<translation type="vanished">Échec étalonnage ! Veuillez lire les instructions et essayer à nouveau.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/config/calibration/thermal/compensationcalculationtransition.h" line="+59"/>
|
||||
<source>Thermal calibration completed successfully.</source>
|
||||
@ -14324,38 +14144,6 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
<translation>Échec étalonnage ! Veuillez relire les instructions et essayer à nouveau.</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>OpenPilot::ThermalCalibrationModel</name>
|
||||
<message>
|
||||
<source>Start</source>
|
||||
<translation type="vanished">Démarrer</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Saving initial settings</source>
|
||||
<translation type="vanished">Enregistrement des paramètres initiaux</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Setup board for calibration</source>
|
||||
<translation type="vanished">Préparation de la carte pour l'étalonnage</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>*** Please Wait *** Samples acquisition, this can take several minutes</source>
|
||||
<translatorcomment>Only one line allowed for text</translatorcomment>
|
||||
<translation type="vanished">*** Veuillez Patienter *** Acquisition des échantillons, cela demande du temps</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Restore board settings</source>
|
||||
<translation type="vanished">Restaurer les paramètres de la carte</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Calculate calibration data</source>
|
||||
<translation type="vanished">Calcul des données d'étalonnage</translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Canceled</source>
|
||||
<translation type="vanished">Annulé</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>TelemetryPlugin</name>
|
||||
<message>
|
||||
@ -14471,8 +14259,8 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+63"/>
|
||||
<source>Target temperature span has been acquired. You may now end acquisition or continue.</source>
|
||||
<translation>La différence de température a été atteinte. Vous pouvez arrêter maintenant ou continuer.</translation>
|
||||
<source>Target temperature span has been acquired. Acquisition may be ended or, preferably, continued.</source>
|
||||
<translation>La différence de température a été atteinte. Vous pouvez arrêter maintenant, mais il est préférable de continuer.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+32"/>
|
||||
@ -14488,13 +14276,13 @@ et même conduire au crash. A utiliser avec prudence.</translation>
|
||||
<context>
|
||||
<name>ConfigRevoWidget</name>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/config/configrevowidget.cpp" line="+318"/>
|
||||
<location filename="../../../src/plugins/config/configrevowidget.cpp" line="+328"/>
|
||||
<source>Temperature: %1°C</source>
|
||||
<translation>Température : %1°C</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+5"/>
|
||||
<source>Variance: %1°C/min</source>
|
||||
<source>Gradient: %1°C/min</source>
|
||||
<translation>Variation : %1°C/min</translation>
|
||||
</message>
|
||||
<message>
|
||||
|
@ -18,5 +18,9 @@
|
||||
<string>1.3.1</string>
|
||||
<key>CFBundleShortVersionString</key>
|
||||
<string>1.3.1</string>
|
||||
<key>NSPrincipalClass</key>
|
||||
<string>NSApplication</string>
|
||||
<key>NSHighResolutionCapable</key>
|
||||
<string>True</string>
|
||||
</dict>
|
||||
</plist>
|
||||
|
@ -55,18 +55,23 @@ GyroBiasCalibrationModel::GyroBiasCalibrationModel(QObject *parent) :
|
||||
|
||||
void GyroBiasCalibrationModel::start()
|
||||
{
|
||||
// Store and reset board rotation before calibration starts
|
||||
storeAndClearBoardRotation();
|
||||
// reset dirty state to forget previous unsaved runs
|
||||
m_dirty = false;
|
||||
|
||||
// configure board for calibration
|
||||
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
|
||||
memento.revoCalibrationData = revoCalibrationData;
|
||||
revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_FALSE;
|
||||
revoCalibration->setData(revoCalibrationData);
|
||||
|
||||
// Disable gyro bias correction while calibrating
|
||||
AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData();
|
||||
memento.attitudeSettingsData = attitudeSettingsData;
|
||||
// Disable gyro bias correction while calibrating
|
||||
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE;
|
||||
// Zero board rotation
|
||||
attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = 0;
|
||||
attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = 0;
|
||||
attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = 0;
|
||||
attitudeSettings->setData(attitudeSettingsData);
|
||||
|
||||
UAVObject::Metadata gyroStateMetadata = gyroState->getMetadata();
|
||||
@ -89,9 +94,6 @@ void GyroBiasCalibrationModel::start()
|
||||
gyro_state_accum_y.clear();
|
||||
gyro_state_accum_z.clear();
|
||||
|
||||
// reset dirty state to forget previous unsaved runs
|
||||
m_dirty = false;
|
||||
|
||||
started();
|
||||
progressChanged(0);
|
||||
displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_NED);
|
||||
@ -149,9 +151,6 @@ void GyroBiasCalibrationModel::getSample(UAVObject *obj)
|
||||
revoCalibration->setData(memento.revoCalibrationData);
|
||||
attitudeSettings->setData(memento.attitudeSettingsData);
|
||||
|
||||
// Recall saved board rotation
|
||||
recallBoardRotation();
|
||||
|
||||
stopped();
|
||||
displayInstructions(tr("Gyroscope calibration completed successfully."), WizardModel::Success);
|
||||
displayVisualHelp(CALIBRATION_HELPER_IMAGE_EMPTY);
|
||||
|
@ -57,8 +57,7 @@ public:
|
||||
signals:
|
||||
void started();
|
||||
void stopped();
|
||||
void storeAndClearBoardRotation();
|
||||
void recallBoardRotation();
|
||||
|
||||
void progressChanged(int value);
|
||||
void displayVisualHelp(QString elementID);
|
||||
void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info);
|
||||
|
@ -159,8 +159,8 @@ void LevelCalibrationModel::save()
|
||||
|
||||
// Update the biases based on collected data
|
||||
// "rotate" the board in the opposite direction as the calculated offset
|
||||
attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] -= rot_data_pitch;
|
||||
attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] -= rot_data_roll;
|
||||
attitudeSettingsData.BoardLevelTrim[AttitudeSettings::BOARDLEVELTRIM_PITCH] -= rot_data_pitch;
|
||||
attitudeSettingsData.BoardLevelTrim[AttitudeSettings::BOARDLEVELTRIM_ROLL] -= rot_data_roll;
|
||||
|
||||
attitudeSettings->setData(attitudeSettingsData);
|
||||
|
||||
|
@ -481,7 +481,7 @@ void SixPointCalibrationModel::save()
|
||||
if (calibratingMag) {
|
||||
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
|
||||
|
||||
for (int i = 0; i < RevoCalibration::MAG_TRANSFORM_R2C2; i++) {
|
||||
for (int i = 0; i < RevoCalibration::MAG_TRANSFORM_NUMELEM; i++) {
|
||||
revoCalibrationData.mag_transform[i] = result.revoCalibrationData.mag_transform[i];
|
||||
}
|
||||
for (int i = 0; i < 3; i++) {
|
||||
|
@ -407,7 +407,7 @@ void ThermalCalibrationHelper::updateTemperature(float temp)
|
||||
}
|
||||
if (!m_rangeReached && (range() >= TargetTempDelta)) {
|
||||
m_rangeReached = true;
|
||||
addInstructions(tr("Target temperature span has been acquired. You may now end acquisition or continue."));
|
||||
addInstructions(tr("Target temperature span has been acquired. Acquisition may be ended or, preferably, continued."));
|
||||
}
|
||||
emit temperatureRangeChanged(range());
|
||||
|
||||
|
@ -56,6 +56,33 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions()
|
||||
GUIConfigDataUnion configData = getConfigData();
|
||||
multiGUISettingsStruct multi = configData.multi;
|
||||
|
||||
// Octocopter X motor definition
|
||||
if (multi.VTOLMotorNNE > 0 && multi.VTOLMotorNNE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorNNE - 1] = QString("VTOLMotorNNE");
|
||||
}
|
||||
if (multi.VTOLMotorENE > 0 && multi.VTOLMotorENE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorENE - 1] = QString("VTOLMotorENE");
|
||||
}
|
||||
if (multi.VTOLMotorESE > 0 && multi.VTOLMotorESE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorESE - 1] = QString("VTOLMotorESE");
|
||||
}
|
||||
if (multi.VTOLMotorSSE > 0 && multi.VTOLMotorSSE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorSSE - 1] = QString("VTOLMotorSSE");
|
||||
}
|
||||
if (multi.VTOLMotorSSW > 0 && multi.VTOLMotorSSW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorSSW - 1] = QString("VTOLMotorSSW");
|
||||
}
|
||||
if (multi.VTOLMotorWSW > 0 && multi.VTOLMotorWSW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorWSW - 1] = QString("VTOLMotorWSW");
|
||||
}
|
||||
if (multi.VTOLMotorWNW > 0 && multi.VTOLMotorWNW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorWNW - 1] = QString("VTOLMotorWNW");
|
||||
}
|
||||
if (multi.VTOLMotorNNW > 0 && multi.VTOLMotorNNW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorNNW - 1] = QString("VTOLMotorNNW");
|
||||
}
|
||||
// End OctocopterX
|
||||
|
||||
if (multi.VTOLMotorN > 0 && multi.VTOLMotorN <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorN - 1] = QString("VTOLMotorN");
|
||||
}
|
||||
@ -110,8 +137,8 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) :
|
||||
m_aircraft->quadShape->setScene(scene);
|
||||
|
||||
QStringList multiRotorTypes;
|
||||
multiRotorTypes << "Tricopter Y" << "Quad +" << "Quad X" << "Hexacopter" << "Hexacopter X" << "Hexacopter Y6"
|
||||
<< "Octocopter" << "Octocopter V" << "Octo Coax +" << "Octo Coax X";
|
||||
multiRotorTypes << "Tricopter Y" << "Quad +" << "Quad X" << "Hexacopter" << "Hexacopter X" << "Hexacopter H" << "Hexacopter Y6"
|
||||
<< "Octocopter" << "Octocopter X" << "Octocopter V" << "Octo Coax +" << "Octo Coax X";
|
||||
m_aircraft->multirotorFrameType->addItems(multiRotorTypes);
|
||||
|
||||
// Set default model to "Quad X"
|
||||
@ -158,16 +185,23 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
|
||||
} else if (frameType == "Hexa" || frameType == "Hexacopter") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter"));
|
||||
|
||||
m_aircraft->mrRollMixLevel->setValue(50);
|
||||
m_aircraft->mrPitchMixLevel->setValue(33);
|
||||
setYawMixLevel(33);
|
||||
m_aircraft->mrRollMixLevel->setValue(100); // Old Roll 50 - Pitch 33 - Yaw 33
|
||||
m_aircraft->mrPitchMixLevel->setValue(100); // Do not alter mixer matrix
|
||||
setYawMixLevel(100);
|
||||
} else if (frameType == "HexaX" || frameType == "Hexacopter X") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType,
|
||||
m_aircraft->multirotorFrameType->findText("Hexacopter X"));
|
||||
|
||||
m_aircraft->mrRollMixLevel->setValue(33);
|
||||
m_aircraft->mrPitchMixLevel->setValue(50);
|
||||
setYawMixLevel(33);
|
||||
m_aircraft->mrRollMixLevel->setValue(100); // Old: Roll 33 - Pitch 50 - Yaw 33
|
||||
m_aircraft->mrPitchMixLevel->setValue(100); // Do not alter mixer matrix
|
||||
setYawMixLevel(100);
|
||||
} else if (frameType == "HexaH" || frameType == "Hexacopter H") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType,
|
||||
m_aircraft->multirotorFrameType->findText("Hexacopter H"));
|
||||
|
||||
m_aircraft->mrRollMixLevel->setValue(100); // Do not alter mixer matrix
|
||||
m_aircraft->mrPitchMixLevel->setValue(100); // All mixers RPY levels = 100%
|
||||
setYawMixLevel(100);
|
||||
} else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType,
|
||||
m_aircraft->multirotorFrameType->findText("Hexacopter Y6"));
|
||||
@ -178,9 +212,15 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
|
||||
} else if (frameType == "Octo" || frameType == "Octocopter") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter"));
|
||||
|
||||
m_aircraft->mrRollMixLevel->setValue(33);
|
||||
m_aircraft->mrPitchMixLevel->setValue(33);
|
||||
setYawMixLevel(25);
|
||||
m_aircraft->mrRollMixLevel->setValue(100); // Do not alter mixer matrix
|
||||
m_aircraft->mrPitchMixLevel->setValue(100); // All mixers RPY levels = 100%
|
||||
setYawMixLevel(100);
|
||||
} else if (frameType == "OctoX" || frameType == "Octocopter X") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter X"));
|
||||
|
||||
m_aircraft->mrRollMixLevel->setValue(100); // Do not alter mixer matrix
|
||||
m_aircraft->mrPitchMixLevel->setValue(100); // All mixers RPY levels = 100%
|
||||
setYawMixLevel(100);
|
||||
} else if (frameType == "OctoV" || frameType == "Octocopter V") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType,
|
||||
m_aircraft->multirotorFrameType->findText("Octocopter V"));
|
||||
@ -235,10 +275,14 @@ void ConfigMultiRotorWidget::setupEnabledControls(QString frameType)
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 6, true);
|
||||
} else if (frameType == "HexaX" || frameType == "Hexacopter X") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 6, true);
|
||||
} else if (frameType == "HexaH" || frameType == "Hexacopter H") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 6, true);
|
||||
} else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 6, true);
|
||||
} else if (frameType == "Octo" || frameType == "Octocopter") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 8, true);
|
||||
} else if (frameType == "OctoX" || frameType == "Octocopter X") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 8, true);
|
||||
} else if (frameType == "OctoV" || frameType == "Octocopter V") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 8, true);
|
||||
} else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") {
|
||||
@ -270,15 +314,23 @@ void ConfigMultiRotorWidget::registerWidgets(ConfigTaskWidget &parent)
|
||||
|
||||
void ConfigMultiRotorWidget::resetActuators(GUIConfigDataUnion *configData)
|
||||
{
|
||||
configData->multi.VTOLMotorN = 0;
|
||||
configData->multi.VTOLMotorNE = 0;
|
||||
configData->multi.VTOLMotorE = 0;
|
||||
configData->multi.VTOLMotorSE = 0;
|
||||
configData->multi.VTOLMotorS = 0;
|
||||
configData->multi.VTOLMotorSW = 0;
|
||||
configData->multi.VTOLMotorW = 0;
|
||||
configData->multi.VTOLMotorNW = 0;
|
||||
configData->multi.VTOLMotorN = 0;
|
||||
configData->multi.VTOLMotorNE = 0;
|
||||
configData->multi.VTOLMotorE = 0;
|
||||
configData->multi.VTOLMotorSE = 0;
|
||||
configData->multi.VTOLMotorS = 0;
|
||||
configData->multi.VTOLMotorSW = 0;
|
||||
configData->multi.VTOLMotorW = 0;
|
||||
configData->multi.VTOLMotorNW = 0;
|
||||
configData->multi.TRIYaw = 0;
|
||||
configData->multi.VTOLMotorNNE = 0;
|
||||
configData->multi.VTOLMotorENE = 0;
|
||||
configData->multi.VTOLMotorESE = 0;
|
||||
configData->multi.VTOLMotorSSE = 0;
|
||||
configData->multi.VTOLMotorSSW = 0;
|
||||
configData->multi.VTOLMotorWSW = 0;
|
||||
configData->multi.VTOLMotorWNW = 0;
|
||||
configData->multi.VTOLMotorNNW = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -366,10 +418,13 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
|
||||
int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
|
||||
if (channel > -1) {
|
||||
// get motor 1 value for Pitch
|
||||
double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
|
||||
m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27));
|
||||
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
// get motor 2 value for Yaw and Roll
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
setYawMixLevel(-qRound(value / 1.27));
|
||||
|
||||
// change channels
|
||||
@ -392,9 +447,12 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
|
||||
int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
|
||||
if (channel > -1) {
|
||||
// get motor 1 value for Pitch
|
||||
double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
|
||||
m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27));
|
||||
|
||||
// get motor 2 value for Yaw and Roll
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
setYawMixLevel(-qRound(value / 1.27));
|
||||
|
||||
@ -402,6 +460,34 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
|
||||
m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27));
|
||||
}
|
||||
} else if (frameType == "HexaH") {
|
||||
// Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2, multi.VTOLMotorE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3, multi.VTOLMotorSE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorSW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox5, multi.VTOLMotorW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox6, multi.VTOLMotorNW);
|
||||
|
||||
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
|
||||
// This assumes that all vectors are identical - if not, the user should use the
|
||||
// "custom" setting.
|
||||
|
||||
int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
|
||||
if (channel > -1) {
|
||||
// get motor 1 value for Pitch
|
||||
double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
|
||||
m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27));
|
||||
|
||||
// get motor 2 value for Yaw and Roll
|
||||
channel += 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
setYawMixLevel(-qRound(value / 1.27));
|
||||
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
|
||||
m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27));
|
||||
}
|
||||
} else if (frameType == "HexaCoax") {
|
||||
// Motors 1/2/3 4/5/6 are: NW/W NE/E S/SE
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNW);
|
||||
@ -449,8 +535,8 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
setYawMixLevel(-qRound(value / 1.27));
|
||||
|
||||
// change channels
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
// Get M3 Roll value
|
||||
channel = m_aircraft->multiMotorChannelBox3->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
|
||||
m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27));
|
||||
} else if (frameType == "OctoV") {
|
||||
@ -477,6 +563,34 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27));
|
||||
}
|
||||
}
|
||||
} else if (frameType == "OctoX") {
|
||||
// Motors 1 to 8 are NNE / ENE / ESE / etc
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNNE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2, multi.VTOLMotorENE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3, multi.VTOLMotorESE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorSSE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox5, multi.VTOLMotorSSW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox6, multi.VTOLMotorWSW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox7, multi.VTOLMotorWNW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox8, multi.VTOLMotorNNW);
|
||||
|
||||
|
||||
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
|
||||
// This assumes that all vectors are identical - if not, the user should use the
|
||||
// "custom" setting.
|
||||
int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
|
||||
if (channel > -1) {
|
||||
double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
|
||||
m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27));
|
||||
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
setYawMixLevel(-qRound(value / 1.27));
|
||||
|
||||
// Get M2 Roll value
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
|
||||
m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27));
|
||||
}
|
||||
} else if (frameType == "OctoCoaxX") {
|
||||
// Motors 1 to 8 are N / NE / E / etc
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNW);
|
||||
@ -549,6 +663,37 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter X") {
|
||||
airframeType = "HexaX";
|
||||
setupHexa(false);
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter H") {
|
||||
airframeType = "HexaH";
|
||||
|
||||
// Show any config errors in GUI
|
||||
if (throwConfigError(6)) {
|
||||
return airframeType;
|
||||
}
|
||||
motorList << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW";
|
||||
setupMotors(motorList);
|
||||
|
||||
// Motor 1 to 6, H layout
|
||||
// ---------------------------------------------
|
||||
// Motor: 1 2 3 4 5 6
|
||||
// ROLL {-0.50, -1.00, -0.50, 0.50, 1.00, 0.50}
|
||||
// PITCH {1.00, 0.00, -1.00, -1.00, -0.00, 1.00}
|
||||
// YAW {-0.50, 1.00, -0.50, 0.50, -1.00, 0.50}
|
||||
// ---------------------------------------------
|
||||
// http://wiki.paparazziuav.org/wiki/RotorcraftMixing
|
||||
// pitch roll yaw
|
||||
double hMixer[8][3] = {
|
||||
{ 1, -0.5, -0.5 },
|
||||
{ 0, -1, 1 },
|
||||
{ -1, -0.5, -0.5 },
|
||||
{ -1, 0.5, 0.5 },
|
||||
{ 0, 1, -1 },
|
||||
{ 1, 0.5, 0.5 },
|
||||
{ 0, 0, 0 },
|
||||
{ 0, 0, 0 }
|
||||
};
|
||||
setupMultiRotorMixer(hMixer);
|
||||
m_aircraft->mrStatusLabel->setText(tr("Configuration OK"));
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter Y6") {
|
||||
airframeType = "HexaCoax";
|
||||
|
||||
@ -572,7 +717,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
{ 0, 0, 0 }
|
||||
};
|
||||
setupMultiRotorMixer(mixerMatrix);
|
||||
m_aircraft->mrStatusLabel->setText("Configuration OK");
|
||||
m_aircraft->mrStatusLabel->setText(tr("Configuration OK"));
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter") {
|
||||
airframeType = "Octo";
|
||||
|
||||
@ -583,20 +728,58 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE" << "VTOLMotorS" << "VTOLMotorSW"
|
||||
<< "VTOLMotorW" << "VTOLMotorNW";
|
||||
setupMotors(motorList);
|
||||
// Motor 1 to 8:
|
||||
// Motor 1 to 8, OctoP
|
||||
// -------------------------------------------------------
|
||||
// Motor: 1 2 3 4 5 6 7 8
|
||||
// ROLL {0.00, -0.71, -1.00, -0.71, 0.00, 0.71, 1.00, 0.71}
|
||||
// PITCH {1.00, 0.71, -0.00, -0.71,-1.00,-0.71,-0.00, 0.71}
|
||||
// YAW {-1.00, 1.00, -1.00, 1.00, -1.00, 1.00,-1.00, 1.00}
|
||||
// -------------------------------------------------------
|
||||
// http://wiki.paparazziuav.org/wiki/RotorcraftMixing
|
||||
// pitch roll yaw
|
||||
double mixerMatrix[8][3] = {
|
||||
{ 1, 0, -1 },
|
||||
{ 1, -1, 1 },
|
||||
{ 0, -1, -1 },
|
||||
{ -1, -1, 1 },
|
||||
{ -1, 0, -1 },
|
||||
{ -1, 1, 1 },
|
||||
{ 0, 1, -1 },
|
||||
{ 1, 1, 1 }
|
||||
{ 1, 0, -1 },
|
||||
{ 0.71, -0.71, 1 },
|
||||
{ 0, -1, -1 },
|
||||
{ -0.71, -0.71, 1 },
|
||||
{ -1, 0, -1 },
|
||||
{ -0.71, 0.71, 1 },
|
||||
{ 0, 1, -1 },
|
||||
{ 0.71, 0.71, 1 }
|
||||
};
|
||||
setupMultiRotorMixer(mixerMatrix);
|
||||
m_aircraft->mrStatusLabel->setText("Configuration OK");
|
||||
m_aircraft->mrStatusLabel->setText(tr("Configuration OK"));
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter X") {
|
||||
airframeType = "OctoX";
|
||||
|
||||
// Show any config errors in GUI
|
||||
if (throwConfigError(8)) {
|
||||
return airframeType;
|
||||
}
|
||||
motorList << "VTOLMotorNNE" << "VTOLMotorENE" << "VTOLMotorESE" << "VTOLMotorSSE" << "VTOLMotorSSW" << "VTOLMotorWSW"
|
||||
<< "VTOLMotorWNW" << "VTOLMotorNNW";
|
||||
setupMotors(motorList);
|
||||
// Motor 1 to 8, OctoX
|
||||
// --------------------------------------------------------
|
||||
// Motor: 1 2 3 4 5 6 7 8
|
||||
// ROLL {-0.41, -1.00, -1.00, -0.41, 0.41, 1.00, 1.00, 0.41}
|
||||
// PITCH {1.00, 0.41, -0.41, -1.00, -1.00, -0.41, 0.41, 1.00}
|
||||
// YAW {-1.00, 1.00, -1.00, 1.00, -1.00, 1.00, -1.00, 1.00}
|
||||
// --------------------------------------------------------
|
||||
// http://wiki.paparazziuav.org/wiki/RotorcraftMixing
|
||||
// pitch roll yaw
|
||||
double mixerMatrix[8][3] = {
|
||||
{ 1, -0.41, -1 },
|
||||
{ 0.41, -1, 1 },
|
||||
{ -0.41, -1, -1 },
|
||||
{ -1, -0.41, 1 },
|
||||
{ -1, 0.41, -1 },
|
||||
{ -0.41, 1, 1 },
|
||||
{ 0.41, 1, -1 },
|
||||
{ 1, 0.41, 1 }
|
||||
};
|
||||
setupMultiRotorMixer(mixerMatrix);
|
||||
m_aircraft->mrStatusLabel->setText(tr("Configuration OK"));
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter V") {
|
||||
airframeType = "OctoV";
|
||||
|
||||
@ -621,7 +804,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
{ 0.33, 1, 1 }
|
||||
};
|
||||
setupMultiRotorMixer(mixerMatrix);
|
||||
m_aircraft->mrStatusLabel->setText("Configuration OK");
|
||||
m_aircraft->mrStatusLabel->setText(tr("Configuration OK"));
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax +") {
|
||||
airframeType = "OctoCoaxP";
|
||||
|
||||
@ -645,7 +828,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
{ 0, 1, 1 }
|
||||
};
|
||||
setupMultiRotorMixer(mixerMatrix);
|
||||
m_aircraft->mrStatusLabel->setText("Configuration OK");
|
||||
m_aircraft->mrStatusLabel->setText(tr("Configuration OK"));
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax X") {
|
||||
airframeType = "OctoCoaxX";
|
||||
|
||||
@ -669,7 +852,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
{ -1, 1, 1 }
|
||||
};
|
||||
setupMultiRotorMixer(mixerMatrix);
|
||||
m_aircraft->mrStatusLabel->setText("Configuration OK");
|
||||
m_aircraft->mrStatusLabel->setText(tr("Configuration OK"));
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Tricopter Y") {
|
||||
airframeType = "Tri";
|
||||
|
||||
@ -678,7 +861,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
return airframeType;
|
||||
}
|
||||
if (m_aircraft->triYawChannelBox->currentText() == "None") {
|
||||
m_aircraft->mrStatusLabel->setText("<font color='red'>Error: Assign a Yaw channel</font>");
|
||||
m_aircraft->mrStatusLabel->setText(tr("<font color='red'>ERROR: Assign a Yaw channel</font>"));
|
||||
return airframeType;
|
||||
}
|
||||
motorList << "VTOLMotorNW" << "VTOLMotorNE" << "VTOLMotorS";
|
||||
@ -688,7 +871,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
config.multi.TRIYaw = m_aircraft->triYawChannelBox->currentIndex();
|
||||
setConfigData(config);
|
||||
|
||||
// Motor 1 to 6, Y6 Layout:
|
||||
// Motor 1 to 3, Tricopter Y Layout:
|
||||
// pitch roll yaw
|
||||
double mixerMatrix[8][3] = {
|
||||
{ 0.5, 1, 0 },
|
||||
@ -748,11 +931,15 @@ void ConfigMultiRotorWidget::updateAirframe(QString frameType)
|
||||
} else if (frameType == "Hexa" || frameType == "Hexacopter") {
|
||||
elementId = "quad-hexa";
|
||||
} else if (frameType == "HexaX" || frameType == "Hexacopter X") {
|
||||
elementId = "quad-hexa-X";
|
||||
} else if (frameType == "HexaH" || frameType == "Hexacopter H") {
|
||||
elementId = "quad-hexa-H";
|
||||
} else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") {
|
||||
elementId = "hexa-coax";
|
||||
} else if (frameType == "Octo" || frameType == "Octocopter") {
|
||||
elementId = "quad-octo";
|
||||
} else if (frameType == "OctoX" || frameType == "Octocopter X") {
|
||||
elementId = "quad-octo-X";
|
||||
} else if (frameType == "OctoV" || frameType == "Octocopter V") {
|
||||
elementId = "quad-octo-v";
|
||||
} else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") {
|
||||
@ -824,6 +1011,23 @@ void ConfigMultiRotorWidget::setupMotors(QList<QString> motorList)
|
||||
configData.multi.VTOLMotorW = index;
|
||||
} else if (motor == QString("VTOLMotorNW")) {
|
||||
configData.multi.VTOLMotorNW = index;
|
||||
// OctoX
|
||||
} else if (motor == QString("VTOLMotorNNE")) {
|
||||
configData.multi.VTOLMotorNNE = index;
|
||||
} else if (motor == QString("VTOLMotorENE")) {
|
||||
configData.multi.VTOLMotorENE = index;
|
||||
} else if (motor == QString("VTOLMotorESE")) {
|
||||
configData.multi.VTOLMotorESE = index;
|
||||
} else if (motor == QString("VTOLMotorSSE")) {
|
||||
configData.multi.VTOLMotorSSE = index;
|
||||
} else if (motor == QString("VTOLMotorSSW")) {
|
||||
configData.multi.VTOLMotorSSW = index;
|
||||
} else if (motor == QString("VTOLMotorWSW")) {
|
||||
configData.multi.VTOLMotorWSW = index;
|
||||
} else if (motor == QString("VTOLMotorWNW")) {
|
||||
configData.multi.VTOLMotorWNW = index;
|
||||
} else if (motor == QString("VTOLMotorNNW")) {
|
||||
configData.multi.VTOLMotorNNW = index;
|
||||
}
|
||||
}
|
||||
setConfigData(configData);
|
||||
@ -914,41 +1118,44 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout)
|
||||
|
||||
// and set only the relevant channels:
|
||||
|
||||
// Motor 1 to 6, P Layout:
|
||||
// Motor 1 to 6, HexaP Layout
|
||||
// ---------------------------------------------
|
||||
// Motor: 1 2 3 4 5 6
|
||||
// ROLL {0.00, -1.00, -1.00, 0.00, 1.00, 1.00}
|
||||
// PITCH {1.00, 0.50, -0.50, -1.00, -0.50, 0.50}
|
||||
// YAW {-1.00, 1.00, -1.00, 1.00, -1.00, 1.00}
|
||||
// ---------------------------------------------
|
||||
// http://wiki.paparazziuav.org/wiki/RotorcraftMixing
|
||||
// pitch roll yaw
|
||||
// 1 { 0.3 , 0 ,-0.3 // N CW
|
||||
// 2 { 0.3 ,-0.5 , 0.3 // NE CCW
|
||||
// 3 {-0.3 ,-0.5 ,-0.3 // SE CW
|
||||
// 4 {-0.3 , 0 , 0.3 // S CCW
|
||||
// 5 {-0.3 , 0.5 ,-0.3 // SW CW
|
||||
// 6 { 0.3 , 0.5 , 0.3 // NW CCW
|
||||
double pMixer[8][3] = {
|
||||
{ 1, 0, -1 },
|
||||
{ 1, -1, 1 },
|
||||
{ -1, -1, -1 },
|
||||
{ -1, 0, 1 },
|
||||
{ -1, 1, -1 },
|
||||
{ 1, 1, 1 },
|
||||
{ 0, 0, 0 },
|
||||
{ 0, 0, 0 }
|
||||
{ 1, 0, -1 },
|
||||
{ 0.5, -1, 1 },
|
||||
{ -0.5, -1, -1 },
|
||||
{ -1, 0, 1 },
|
||||
{ -0.5, 1, -1 },
|
||||
{ 0.5, 1, 1 },
|
||||
{ 0, 0, 0 },
|
||||
{ 0, 0, 0 }
|
||||
};
|
||||
|
||||
// Motor 1 to 6, X Layout:
|
||||
// 1 [ 0.5, -0.3, -0.3 ] NE
|
||||
// 2 [ 0 , -0.3, 0.3 ] E
|
||||
// 3 [ -0.5, -0.3, -0.3 ] SE
|
||||
// 4 [ -0.5, 0.3, 0.3 ] SW
|
||||
// 5 [ 0 , 0.3, -0.3 ] W
|
||||
// 6 [ 0.5, 0.3, 0.3 ] NW
|
||||
// Motor 1 to 6, HexaX Layout
|
||||
// ---------------------------------------------
|
||||
// Motor: 1 2 3 4 5 6
|
||||
// ROLL {-0.50, -1.00, -0.50, 0.50, 1.00, 0.50}
|
||||
// PITCH {1.00, 0.00, -1.00, -1.00, -0.00, 1.00}
|
||||
// YAW {-1.00, 1.00, -1.00, 1.00, -1.00, 1.00}
|
||||
// ---------------------------------------------
|
||||
// http://wiki.paparazziuav.org/wiki/RotorcraftMixing
|
||||
// pitch roll yaw
|
||||
double xMixer[8][3] = {
|
||||
{ 1, -1, -1 },
|
||||
{ 0, -1, 1 },
|
||||
{ -1, -1, -1 },
|
||||
{ -1, 1, 1 },
|
||||
{ 0, 1, -1 },
|
||||
{ 1, 1, 1 },
|
||||
{ 0, 0, 0 },
|
||||
{ 0, 0, 0 }
|
||||
{ 1, -0.5, -1 },
|
||||
{ 0, -1, 1 },
|
||||
{ -1, -0.5, -1 },
|
||||
{ -1, 0.5, 1 },
|
||||
{ 0, 1, -1 },
|
||||
{ 1, 0.5, 1 },
|
||||
{ 0, 0, 0 },
|
||||
{ 0, 0, 0 }
|
||||
};
|
||||
|
||||
if (pLayout) {
|
||||
@ -956,7 +1163,7 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout)
|
||||
} else {
|
||||
setupMultiRotorMixer(xMixer);
|
||||
}
|
||||
m_aircraft->mrStatusLabel->setText("Configuration OK");
|
||||
m_aircraft->mrStatusLabel->setText(tr("Configuration OK"));
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -1021,7 +1228,7 @@ bool ConfigMultiRotorWidget::throwConfigError(int numMotors)
|
||||
|
||||
if (error) {
|
||||
m_aircraft->mrStatusLabel->setText(
|
||||
QString("<font color='red'>ERROR: Assign all %1 motor channels</font>").arg(numMotors));
|
||||
QString(tr("<font color='red'>ERROR: Assign all %1 motor channels</font>")).arg(numMotors));
|
||||
}
|
||||
return error;
|
||||
}
|
||||
|
@ -42,6 +42,15 @@ typedef struct {
|
||||
uint VTOLMotorNE : 4;
|
||||
uint VTOLMotorSW : 4;
|
||||
uint VTOLMotorSE : 4; // 32 bits
|
||||
// OctoX
|
||||
uint VTOLMotorNNE : 4;
|
||||
uint VTOLMotorENE : 4;
|
||||
uint VTOLMotorESE : 4;
|
||||
uint VTOLMotorSSE : 4;
|
||||
uint VTOLMotorSSW : 4;
|
||||
uint VTOLMotorWSW : 4;
|
||||
uint VTOLMotorWNW : 4;
|
||||
uint VTOLMotorNNW : 4; // 32 bits
|
||||
uint TRIYaw : 4;
|
||||
quint32 padding : 28; // 64 bits
|
||||
quint32 padding1;
|
||||
|
@ -157,8 +157,6 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
|
||||
|
||||
connect(m_gyroBiasCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations()));
|
||||
connect(m_gyroBiasCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations()));
|
||||
connect(m_gyroBiasCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation()));
|
||||
connect(m_gyroBiasCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation()));
|
||||
connect(m_gyroBiasCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)),
|
||||
this, SLOT(addInstructions(QString, WizardModel::MessageType)));
|
||||
connect(m_gyroBiasCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
|
||||
@ -332,7 +330,7 @@ void ConfigRevoWidget::displayTemperature(float temperature)
|
||||
|
||||
void ConfigRevoWidget::displayTemperatureGradient(float temperatureGradient)
|
||||
{
|
||||
m_ui->temperatureGradientLabel->setText(tr("Variance: %1°C/min").arg(format(temperatureGradient)));
|
||||
m_ui->temperatureGradientLabel->setText(tr("Gradient: %1°C/min").arg(format(temperatureGradient)));
|
||||
}
|
||||
|
||||
void ConfigRevoWidget::displayTemperatureRange(float temperatureRange)
|
||||
|
@ -28,6 +28,10 @@
|
||||
#include "configtxpidwidget.h"
|
||||
#include "txpidsettings.h"
|
||||
#include "hwsettings.h"
|
||||
#include "stabilizationsettings.h"
|
||||
#include "stabilizationsettingsbank1.h"
|
||||
#include "stabilizationsettingsbank2.h"
|
||||
#include "stabilizationsettingsbank3.h"
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
|
||||
@ -51,16 +55,21 @@ ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
connect(m_txpid->Apply, SIGNAL(clicked()), this, SLOT(applySettings()));
|
||||
connect(m_txpid->Save, SIGNAL(clicked()), this, SLOT(saveSettings()));
|
||||
|
||||
addWidgetBinding("TxPIDSettings", "BankNumber", m_txpid->pidBank, 0, 1, true);
|
||||
connect(m_txpid->PID1, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSpinBoxProperties(int)));
|
||||
connect(m_txpid->PID2, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSpinBoxProperties(int)));
|
||||
connect(m_txpid->PID3, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSpinBoxProperties(int)));
|
||||
|
||||
addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID1, TxPIDSettings::PIDS_INSTANCE1);
|
||||
addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID2, TxPIDSettings::PIDS_INSTANCE2);
|
||||
addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID3, TxPIDSettings::PIDS_INSTANCE3);
|
||||
addWidgetBinding("TxPIDSettings", "BankNumber", m_txpid->pidBank, 0, 1, true);
|
||||
|
||||
addWidgetBinding("TxPIDSettings", "Inputs", m_txpid->Input1, TxPIDSettings::INPUTS_INSTANCE1);
|
||||
addWidgetBinding("TxPIDSettings", "Inputs", m_txpid->Input2, TxPIDSettings::INPUTS_INSTANCE2);
|
||||
addWidgetBinding("TxPIDSettings", "Inputs", m_txpid->Input3, TxPIDSettings::INPUTS_INSTANCE3);
|
||||
|
||||
// It's important that the PIDx values are populated before the MinPIDx and MaxPIDx,
|
||||
// otherwise the MinPIDx and MaxPIDx will be capped by the old spin box limits. The correct limits
|
||||
// are set when updateSpinBoxProperties is called when the PIDx->currentTextChanged signal is sent.
|
||||
// The binding order is reversed because the values are populated in reverse.
|
||||
|
||||
addWidgetBinding("TxPIDSettings", "MinPID", m_txpid->MinPID1, TxPIDSettings::MINPID_INSTANCE1);
|
||||
addWidgetBinding("TxPIDSettings", "MinPID", m_txpid->MinPID2, TxPIDSettings::MINPID_INSTANCE2);
|
||||
addWidgetBinding("TxPIDSettings", "MinPID", m_txpid->MinPID3, TxPIDSettings::MINPID_INSTANCE3);
|
||||
@ -69,6 +78,10 @@ ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
addWidgetBinding("TxPIDSettings", "MaxPID", m_txpid->MaxPID2, TxPIDSettings::MAXPID_INSTANCE2);
|
||||
addWidgetBinding("TxPIDSettings", "MaxPID", m_txpid->MaxPID3, TxPIDSettings::MAXPID_INSTANCE3);
|
||||
|
||||
addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID1, TxPIDSettings::PIDS_INSTANCE1);
|
||||
addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID2, TxPIDSettings::PIDS_INSTANCE2);
|
||||
addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID3, TxPIDSettings::PIDS_INSTANCE3);
|
||||
|
||||
addWidgetBinding("TxPIDSettings", "ThrottleRange", m_txpid->ThrottleMin, TxPIDSettings::THROTTLERANGE_MIN);
|
||||
addWidgetBinding("TxPIDSettings", "ThrottleRange", m_txpid->ThrottleMax, TxPIDSettings::THROTTLERANGE_MAX);
|
||||
|
||||
@ -88,6 +101,257 @@ ConfigTxPIDWidget::~ConfigTxPIDWidget()
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
static bool isResponsivenessOption(int pidOption)
|
||||
{
|
||||
switch (pidOption) {
|
||||
case TxPIDSettings::PIDS_ROLLRATERESP:
|
||||
case TxPIDSettings::PIDS_PITCHRATERESP:
|
||||
case TxPIDSettings::PIDS_ROLLPITCHRATERESP:
|
||||
case TxPIDSettings::PIDS_YAWRATERESP:
|
||||
case TxPIDSettings::PIDS_ROLLATTITUDERESP:
|
||||
case TxPIDSettings::PIDS_PITCHATTITUDERESP:
|
||||
case TxPIDSettings::PIDS_ROLLPITCHATTITUDERESP:
|
||||
case TxPIDSettings::PIDS_YAWATTITUDERESP:
|
||||
return true;
|
||||
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
static bool isAttitudeOption(int pidOption)
|
||||
{
|
||||
switch (pidOption) {
|
||||
case TxPIDSettings::PIDS_ROLLATTITUDEKP:
|
||||
case TxPIDSettings::PIDS_PITCHATTITUDEKP:
|
||||
case TxPIDSettings::PIDS_ROLLPITCHATTITUDEKP:
|
||||
case TxPIDSettings::PIDS_YAWATTITUDEKP:
|
||||
case TxPIDSettings::PIDS_ROLLATTITUDEKI:
|
||||
case TxPIDSettings::PIDS_PITCHATTITUDEKI:
|
||||
case TxPIDSettings::PIDS_ROLLPITCHATTITUDEKI:
|
||||
case TxPIDSettings::PIDS_YAWATTITUDEKI:
|
||||
case TxPIDSettings::PIDS_ROLLATTITUDEILIMIT:
|
||||
case TxPIDSettings::PIDS_PITCHATTITUDEILIMIT:
|
||||
case TxPIDSettings::PIDS_ROLLPITCHATTITUDEILIMIT:
|
||||
case TxPIDSettings::PIDS_YAWATTITUDEILIMIT:
|
||||
case TxPIDSettings::PIDS_ROLLATTITUDERESP:
|
||||
case TxPIDSettings::PIDS_PITCHATTITUDERESP:
|
||||
case TxPIDSettings::PIDS_ROLLPITCHATTITUDERESP:
|
||||
case TxPIDSettings::PIDS_YAWATTITUDERESP:
|
||||
return true;
|
||||
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
template <class StabilizationSettingsBankX>
|
||||
static float defaultValueForPidOption(const StabilizationSettingsBankX *bank, int pidOption)
|
||||
{
|
||||
switch (pidOption) {
|
||||
case TxPIDSettings::PIDS_DISABLED:
|
||||
return 0.0f;
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLRATEKP:
|
||||
return bank->getRollRatePID_Kp();
|
||||
|
||||
case TxPIDSettings::PIDS_PITCHRATEKP:
|
||||
return bank->getPitchRatePID_Kp();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLPITCHRATEKP:
|
||||
return bank->getRollRatePID_Kp();
|
||||
|
||||
case TxPIDSettings::PIDS_YAWRATEKP:
|
||||
return bank->getYawRatePID_Kp();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLRATEKI:
|
||||
return bank->getRollRatePID_Ki();
|
||||
|
||||
case TxPIDSettings::PIDS_PITCHRATEKI:
|
||||
return bank->getPitchRatePID_Ki();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLPITCHRATEKI:
|
||||
return bank->getRollRatePID_Ki();
|
||||
|
||||
case TxPIDSettings::PIDS_YAWRATEKI:
|
||||
return bank->getYawRatePID_Ki();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLRATEKD:
|
||||
return bank->getRollRatePID_Kd();
|
||||
|
||||
case TxPIDSettings::PIDS_PITCHRATEKD:
|
||||
return bank->getPitchRatePID_Kd();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLPITCHRATEKD:
|
||||
return bank->getRollRatePID_Kd();
|
||||
|
||||
case TxPIDSettings::PIDS_YAWRATEKD:
|
||||
return bank->getYawRatePID_Kd();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLRATEILIMIT:
|
||||
return bank->getRollRatePID_ILimit();
|
||||
|
||||
case TxPIDSettings::PIDS_PITCHRATEILIMIT:
|
||||
return bank->getPitchRatePID_ILimit();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLPITCHRATEILIMIT:
|
||||
return bank->getRollRatePID_ILimit();
|
||||
|
||||
case TxPIDSettings::PIDS_YAWRATEILIMIT:
|
||||
return bank->getYawRatePID_ILimit();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLRATERESP:
|
||||
return bank->getManualRate_Roll();
|
||||
|
||||
case TxPIDSettings::PIDS_PITCHRATERESP:
|
||||
return bank->getManualRate_Pitch();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLPITCHRATERESP:
|
||||
return bank->getManualRate_Roll();
|
||||
|
||||
case TxPIDSettings::PIDS_YAWRATERESP:
|
||||
return bank->getManualRate_Yaw();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLATTITUDEKP:
|
||||
return bank->getRollPI_Kp();
|
||||
|
||||
case TxPIDSettings::PIDS_PITCHATTITUDEKP:
|
||||
return bank->getPitchPI_Kp();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLPITCHATTITUDEKP:
|
||||
return bank->getRollPI_Kp();
|
||||
|
||||
case TxPIDSettings::PIDS_YAWATTITUDEKP:
|
||||
return bank->getYawPI_Kp();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLATTITUDEKI:
|
||||
return bank->getRollPI_Ki();
|
||||
|
||||
case TxPIDSettings::PIDS_PITCHATTITUDEKI:
|
||||
return bank->getPitchPI_Ki();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLPITCHATTITUDEKI:
|
||||
return bank->getRollPI_Ki();
|
||||
|
||||
case TxPIDSettings::PIDS_YAWATTITUDEKI:
|
||||
return bank->getYawPI_Ki();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLATTITUDEILIMIT:
|
||||
return bank->getRollPI_ILimit();
|
||||
|
||||
case TxPIDSettings::PIDS_PITCHATTITUDEILIMIT:
|
||||
return bank->getPitchPI_ILimit();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLPITCHATTITUDEILIMIT:
|
||||
return bank->getRollPI_ILimit();
|
||||
|
||||
case TxPIDSettings::PIDS_YAWATTITUDEILIMIT:
|
||||
return bank->getYawPI_ILimit();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLATTITUDERESP:
|
||||
return (float)bank->getRollMax();
|
||||
|
||||
case TxPIDSettings::PIDS_PITCHATTITUDERESP:
|
||||
return (float)bank->getPitchMax();
|
||||
|
||||
case TxPIDSettings::PIDS_ROLLPITCHATTITUDERESP:
|
||||
return (float)bank->getRollMax();
|
||||
|
||||
case TxPIDSettings::PIDS_YAWATTITUDERESP:
|
||||
return bank->getYawMax();
|
||||
|
||||
case -1: // The PID Option field was uninitialized.
|
||||
return 0.0f;
|
||||
|
||||
default:
|
||||
Q_ASSERT_X(false, "getDefaultValueForOption", "Incorrect PID option");
|
||||
return 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
float ConfigTxPIDWidget::getDefaultValueForPidOption(int pidOption)
|
||||
{
|
||||
if (pidOption == TxPIDSettings::PIDS_GYROTAU) {
|
||||
StabilizationSettings *stab = qobject_cast<StabilizationSettings *>(getObject(QString("StabilizationSettings")));
|
||||
return stab->getGyroTau();
|
||||
}
|
||||
|
||||
int pidBankIndex = m_txpid->pidBank->currentIndex();
|
||||
|
||||
if (pidBankIndex == -1) {
|
||||
// The pidBank field was uninitilized.
|
||||
return 0.0f;
|
||||
}
|
||||
|
||||
int bankNumber = pidBankIndex + 1;
|
||||
|
||||
if (bankNumber == 1) {
|
||||
StabilizationSettingsBank1 *bank = qobject_cast<StabilizationSettingsBank1 *>(getObject(QString("StabilizationSettingsBank1")));
|
||||
return defaultValueForPidOption(bank, pidOption);
|
||||
} else if (bankNumber == 2) {
|
||||
StabilizationSettingsBank2 *bank = qobject_cast<StabilizationSettingsBank2 *>(getObject(QString("StabilizationSettingsBank2")));
|
||||
return defaultValueForPidOption(bank, pidOption);
|
||||
} else if (bankNumber == 3) {
|
||||
StabilizationSettingsBank3 *bank = qobject_cast<StabilizationSettingsBank3 *>(getObject(QString("StabilizationSettingsBank3")));
|
||||
return defaultValueForPidOption(bank, pidOption);
|
||||
} else {
|
||||
Q_ASSERT_X(false, "getDefaultValueForPidOption", "Incorrect bank number");
|
||||
return 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigTxPIDWidget::updateSpinBoxProperties(int selectedPidOption)
|
||||
{
|
||||
QObject *PIDx = sender();
|
||||
|
||||
QDoubleSpinBox *minPID;
|
||||
QDoubleSpinBox *maxPID;
|
||||
|
||||
if (PIDx == m_txpid->PID1) {
|
||||
minPID = m_txpid->MinPID1;
|
||||
maxPID = m_txpid->MaxPID1;
|
||||
} else if (PIDx == m_txpid->PID2) {
|
||||
minPID = m_txpid->MinPID2;
|
||||
maxPID = m_txpid->MaxPID2;
|
||||
} else if (PIDx == m_txpid->PID3) {
|
||||
minPID = m_txpid->MinPID3;
|
||||
maxPID = m_txpid->MaxPID3;
|
||||
} else {
|
||||
Q_ASSERT_X(false, "updateSpinBoxProperties", "Incorrect sender object");
|
||||
return;
|
||||
}
|
||||
|
||||
// The ranges need to be setup before the values can be set,
|
||||
// otherwise the value might be incorrectly capped.
|
||||
|
||||
if (isResponsivenessOption(selectedPidOption)) {
|
||||
if (isAttitudeOption(selectedPidOption)) {
|
||||
// Limit to 180 degrees.
|
||||
minPID->setRange(0, 180);
|
||||
maxPID->setRange(0, 180);
|
||||
} else {
|
||||
minPID->setRange(0, 999);
|
||||
maxPID->setRange(0, 999);
|
||||
}
|
||||
minPID->setSingleStep(1);
|
||||
maxPID->setSingleStep(1);
|
||||
minPID->setDecimals(0);
|
||||
maxPID->setDecimals(0);
|
||||
} else {
|
||||
minPID->setRange(0, 99.99);
|
||||
maxPID->setRange(0, 99.99);
|
||||
minPID->setSingleStep(0.000100);
|
||||
maxPID->setSingleStep(0.000100);
|
||||
minPID->setDecimals(6);
|
||||
maxPID->setDecimals(6);
|
||||
}
|
||||
|
||||
float value = getDefaultValueForPidOption(selectedPidOption);
|
||||
|
||||
minPID->setValue(value);
|
||||
maxPID->setValue(value);
|
||||
}
|
||||
|
||||
void ConfigTxPIDWidget::refreshValues()
|
||||
{
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
|
@ -40,6 +40,8 @@ private:
|
||||
Ui_TxPIDWidget *m_txpid;
|
||||
|
||||
private slots:
|
||||
void updateSpinBoxProperties(int selectedPidOption);
|
||||
float getDefaultValueForPidOption(int pidOption);
|
||||
void refreshValues();
|
||||
void applySettings();
|
||||
void saveSettings();
|
||||
|
@ -85,6 +85,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
|
||||
case SystemSettings::AIRFRAMETYPE_OCTOCOAXX:
|
||||
case SystemSettings::AIRFRAMETYPE_OCTOCOAXP:
|
||||
case SystemSettings::AIRFRAMETYPE_OCTO:
|
||||
case SystemSettings::AIRFRAMETYPE_OCTOX:
|
||||
case SystemSettings::AIRFRAMETYPE_HEXAX:
|
||||
case SystemSettings::AIRFRAMETYPE_HEXACOAX:
|
||||
case SystemSettings::AIRFRAMETYPE_HEXA:
|
||||
@ -263,8 +264,11 @@ int ConfigVehicleTypeWidget::frameCategory(QString frameType)
|
||||
} else if (frameType == "Tri" || frameType == "Tricopter Y" || frameType == "QuadX" || frameType == "Quad X"
|
||||
|| frameType == "QuadP" || frameType == "Quad +" || frameType == "Hexa" || frameType == "Hexacopter"
|
||||
|| frameType == "HexaX" || frameType == "Hexacopter X" || frameType == "HexaCoax"
|
||||
|| frameType == "Hexacopter Y6" || frameType == "Octo" || frameType == "Octocopter" || frameType == "OctoV"
|
||||
|| frameType == "Octocopter V" || frameType == "OctoCoaxP" || frameType == "Octo Coax +"
|
||||
|| frameType == "HexaH" || frameType == "Hexacopter H" || frameType == "Hexacopter Y6"
|
||||
|| frameType == "Octo" || frameType == "Octocopter"
|
||||
|| frameType == "OctoX" || frameType == "Octocopter X"
|
||||
|| frameType == "OctoV" || frameType == "Octocopter V"
|
||||
|| frameType == "OctoCoaxP" || frameType == "Octo Coax +"
|
||||
|| frameType == "OctoCoaxX" || frameType == "Octo Coax X") {
|
||||
return ConfigVehicleTypeWidget::MULTIROTOR;
|
||||
} else if (frameType == "HeliCP") {
|
||||
|
Before Width: | Height: | Size: 758 KiB After Width: | Height: | Size: 898 KiB |
@ -1303,7 +1303,7 @@ channel value for each flight mode.</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p>Avoid &quot;Manual&quot; for multirotors! Never select &quot;ALtitude&quot;, &quot;VelocityControl&quot; or &quot;CruiseControl&quot; on a fixed wing!</p></body></html></string>
|
||||
<string><html><head/><body><p>Avoid &quot;Manual&quot; for multirotors! Never select &quot;Altitude&quot;, &quot;VelocityControl&quot; or &quot;CruiseControl&quot; on a fixed wing!</p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
|
@ -968,42 +968,37 @@ A setting of 0.00 disables the filter.</string>
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
<table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;">
|
||||
<tr>
|
||||
<td style="border: none;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;">Help</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Steps 1, 2 and 3 are necessary.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Step 4 is optional but may help achieve the best possible results.</span></p>
|
||||
<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 1: Accelerometer and Magnetometer calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">These calibrations will compute the scale for Magnetometer and Accelerometer sensors. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Press </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> to begin calibration and follow the instructions which will be displayed. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">For optimal calibration, perform the acceleration calibration with the board not mounted in the craft.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">In this way you can accurately level the board on your desk/table during the process. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Magnetometer calibration needs to be performed inside your plane/copter to account for metal/magnetic elements on board.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Note 1</span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> </span><span style=" font-family:'Ubuntu'; font-size:11pt; text-decoration: underline;">Your HomeLocation must be set first</span><span style=" font-family:'Ubuntu'; font-size:11pt;">, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Note 2</span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> There is no need to point exactly at South/North/West/East. These are just used to easily tell the user how to point the plane/craft. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">You can simply assume that North is in front of you, right is East, etc., and perform the calibration this way.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 2: Board level calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step will ensure that board leveling is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> and do not move your airframe at all until the end of the calibration.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 3: Gyro bias calculation</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step allows to calibrate the gyro measured value when the board is steady. To perform the calibration leave the board/aircraft completely steady and pres </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start</span><span style=" font-family:'Ubuntu'; font-size:11pt;">. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 4: Thermal calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">The calibration will compute sensors bias variations at different temperatures while the board warms up.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This allows a certain amount of correction of those bias variations against temperature changes. It does improve both altitude hold and yaw performances.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">To perform this calibration leave the board to cool down at room temperature in the coldest places available.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">After 15-20 minutes, attach the usb connector to the board and press </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-style:italic;">Start,</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> leaving the board steady. Wait until completed.</span></p></td></tr></table></body></html></string>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600;">Help</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Steps 1, 2 and 3 are necessary.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Step 4 is optional but may help achieve the best possible results.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 1: Accelerometer and Magnetometer calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step will calibrate the scale for the Magnetometer and the Accelerometer sensors. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;"> to begin, and follow the instructions for each step. </span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">For best results with the accelerometer calibration, it is advised that it be performed with a free unmounted flight controller as this allows one to accurately position the board for each orientation in the sequence.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">The magnetometer calibration must be performed with the board mounted in the airframe in order for the measurements to incorporate any bias produced by local onboard metal/magnetic elements.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Note 1: Before the magnetometer or the accelerometer calibration is performed your Home Location must be set. This step is needed in order to determine the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">Note 2: There is no need to align the airframe exactly south, north, east or west during the individual steps. The directions indicated serve only to tell you in which direction the airframe should be positioned relative to some point. One can simply assume that North is in front of you, East is to the right, West is to the left and South is pointing at you.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 2: Board level calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step will ensure that board leveling is accurate. Place the airframe as horizontally as possible (use a spirit level if necessary), then press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;">. Do not move the airframe at all until the end of the calibration.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 3: Gyro bias calculation</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This step will allow you to calibrate the gyro measured value when the board is steady. To perform the calibration leave the board/airframe completely stationary and press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;">. </span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; font-style:italic;">Step 4: Thermal calibration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">The calibration will compute sensors bias variations at different temperatures while the board warms up.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">This allows a certain amount of correction of those bias variations against temperature changes. It improves altitude hold accuracy and reduces yaw drift.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;">To perform this calibration disconnect any power from the board and leave it to cool down at room temperature for 15-20 minutes. Then attach the usb connector to the board and press </span><span style=" font-size:11pt; font-style:italic;">Start</span><span style=" font-size:11pt;">, leaving the board completely stationary. Wait until complete.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p></body></html></string>
|
||||
</property>
|
||||
<property name="textInteractionFlags">
|
||||
<set>Qt::LinksAccessibleByKeyboard|Qt::LinksAccessibleByMouse|Qt::TextBrowserInteraction|Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse</set>
|
||||
|
@ -16641,7 +16641,7 @@ border-radius: 5;</string>
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KP) that is used in Rate mode.</p></body></html></string>
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KI) that is used in Rate mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
@ -16694,7 +16694,7 @@ border-radius: 5;</string>
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KP) that is used in Rate mode.</p></body></html></string>
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KI) that is used in Rate mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
@ -17851,7 +17851,7 @@ font:bold;</string>
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KP) that is used in AttitudeMode.</p></body></html></string>
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KI) that is used in AttitudeMode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
@ -17932,7 +17932,7 @@ font:bold;</string>
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KP) that is used in AttitudeMode.</p></body></html></string>
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KI) that is used in AttitudeMode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
@ -18042,7 +18042,7 @@ font:bold;</string>
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KP) that is used in AttitudeMode.</p></body></html></string>
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KI) that is used in AttitudeMode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
@ -18657,7 +18657,7 @@ font:bold;</string>
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KP) that is used in Rate mode.</p></body></html></string>
|
||||
<string><html><head/><body><p>This sets the maximum value of the integral (KI) that is used in Rate mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
|
@ -83,10 +83,6 @@ public:
|
||||
|
||||
void init();
|
||||
|
||||
QIODevice *getCurrentConnection()
|
||||
{
|
||||
return m_ioDev;
|
||||
}
|
||||
DevListItem getCurrentDevice()
|
||||
{
|
||||
return m_connectionDevice;
|
||||
|
@ -143,7 +143,6 @@ RESOURCES += core.qrc \
|
||||
|
||||
unix:!macx {
|
||||
images.files = images/openpilot_logo_*.png
|
||||
images.files = images/qtcreator_logo_*.png
|
||||
images.path = /share/pixmaps
|
||||
INSTALLS += images
|
||||
}
|
||||
|
Before Width: | Height: | Size: 1.4 KiB |
@ -7,9 +7,9 @@ import org.openpilot 1.0
|
||||
import "functions.js" as Functions
|
||||
|
||||
Rectangle {
|
||||
width: 600
|
||||
width: 700
|
||||
height: 400
|
||||
|
||||
id: root
|
||||
ColumnLayout {
|
||||
anchors.fill: parent
|
||||
anchors.margins: 10
|
||||
@ -59,11 +59,11 @@ Rectangle {
|
||||
delegate:
|
||||
Text {
|
||||
verticalAlignment: Text.AlignVCenter
|
||||
text: Functions.millisToTime(styleData.value)
|
||||
text: Functions.microsToTime(styleData.value)
|
||||
}
|
||||
}
|
||||
TableViewColumn {
|
||||
role: "Type"; title: "Type"; width: 60;
|
||||
role: "Type"; title: "Type"; width: 50;
|
||||
delegate:
|
||||
Text {
|
||||
verticalAlignment: Text.AlignVCenter
|
||||
@ -72,6 +72,7 @@ Rectangle {
|
||||
case 0 : text: qsTr("Empty"); break;
|
||||
case 1 : text: qsTr("Text"); break;
|
||||
case 2 : text: qsTr("UAVO"); break;
|
||||
case 3 : text: qsTr("UAVO(P)"); break;
|
||||
default: text: qsTr("Unknown"); break;
|
||||
}
|
||||
}
|
||||
@ -93,12 +94,16 @@ Rectangle {
|
||||
spacing: 10
|
||||
Text {
|
||||
id: totalFlights
|
||||
text: "<b>" + qsTr("Flights recorded: ") + "</b>" + (logStatus.Flight + 1)
|
||||
text: "<b>" + qsTr("Flights recorded:") + "</b> " + (logStatus.Flight + 1)
|
||||
}
|
||||
Text {
|
||||
id: totalSlots
|
||||
text: "<b>" + qsTr("Slots used/free:") + "</b> " +
|
||||
logStatus.UsedSlots + "/" + logStatus.FreeSlots
|
||||
}
|
||||
Text {
|
||||
id: totalEntries
|
||||
text: "<b>" + qsTr("Entries logged (free): ") + "</b>" +
|
||||
logStatus.UsedSlots + " (" + logStatus.FreeSlots + ")"
|
||||
text: "<b>" + qsTr("Entries downloaded:") + "</b> " + logManager.logEntriesCount
|
||||
}
|
||||
Rectangle {
|
||||
Layout.fillHeight: true
|
||||
@ -393,7 +398,7 @@ Rectangle {
|
||||
text: qsTr("OK")
|
||||
isDefault: true
|
||||
activeFocusOnPress: true
|
||||
onClicked: dialog.close()
|
||||
onClicked: logDialog.close()
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -10,11 +10,9 @@ include(../../plugins/uavobjectutil/uavobjectutil.pri)
|
||||
include(../../plugins/uavtalk/uavtalk.pri)
|
||||
|
||||
HEADERS += flightlogplugin.h \
|
||||
flightlogmanager.h \
|
||||
flightlogdialog.h
|
||||
flightlogmanager.h
|
||||
SOURCES += flightlogplugin.cpp \
|
||||
flightlogmanager.cpp \
|
||||
flightlogdialog.cpp
|
||||
flightlogmanager.cpp
|
||||
|
||||
OTHER_FILES += Flightlog.pluginspec \
|
||||
FlightLogDialog.qml \
|
||||
|
@ -1,70 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file flightlogdialog.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup [Group]
|
||||
* @{
|
||||
* @addtogroup FlightLogDialog
|
||||
* @{
|
||||
* @brief [Brief]
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "flightlogdialog.h"
|
||||
|
||||
#include <QVBoxLayout>
|
||||
|
||||
#include <QtQuick>
|
||||
#include <QQuickView>
|
||||
#include <QQmlEngine>
|
||||
#include <QQmlContext>
|
||||
|
||||
#include "flightlogmanager.h"
|
||||
#include "uavobject.h"
|
||||
|
||||
FlightLogDialog::FlightLogDialog(QWidget *parent, FlightLogManager *flightLogManager) :
|
||||
QDialog(parent)
|
||||
{
|
||||
qmlRegisterType<ExtendedDebugLogEntry>("org.openpilot", 1, 0, "DebugLogEntry");
|
||||
qmlRegisterType<UAVOLogSettingsWrapper>("org.openpilot", 1, 0, "UAVOLogSettingsWrapper");
|
||||
|
||||
setWindowIcon(QIcon(":/core/images/openpilot_logo_32.png"));
|
||||
setWindowTitle(tr("Manage flight side logs"));
|
||||
setWindowFlags(windowFlags() & ~Qt::WindowContextHelpButtonHint);
|
||||
setMinimumSize(600, 400);
|
||||
|
||||
QQuickView *view = new QQuickView();
|
||||
view->rootContext()->setContextProperty("dialog", this);
|
||||
view->rootContext()->setContextProperty("logStatus", flightLogManager->flightLogStatus());
|
||||
view->rootContext()->setContextProperty("logControl", flightLogManager->flightLogControl());
|
||||
view->rootContext()->setContextProperty("logSettings", flightLogManager->flightLogSettings());
|
||||
view->rootContext()->setContextProperty("logManager", flightLogManager);
|
||||
view->setResizeMode(QQuickView::SizeRootObjectToView);
|
||||
view->setSource(QUrl("qrc:/flightlog/FlightLogDialog.qml"));
|
||||
|
||||
QWidget *container = QWidget::createWindowContainer(view);
|
||||
container->setMinimumSize(600, 400);
|
||||
container->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
|
||||
QVBoxLayout *lay = new QVBoxLayout();
|
||||
lay->setContentsMargins(0, 0, 0, 0);
|
||||
setLayout(lay);
|
||||
layout()->addWidget(container);
|
||||
}
|
||||
|
||||
FlightLogDialog::~FlightLogDialog()
|
||||
{}
|
@ -1,15 +0,0 @@
|
||||
#ifndef FLIGHTLOGDIALOG_H
|
||||
#define FLIGHTLOGDIALOG_H
|
||||
|
||||
#include <QDialog>
|
||||
#include "flightlogmanager.h"
|
||||
|
||||
class FlightLogDialog : public QDialog {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit FlightLogDialog(QWidget *parent, FlightLogManager *flightLogManager);
|
||||
~FlightLogDialog();
|
||||
};
|
||||
|
||||
#endif // FLIGHTLOGDIALOG_H
|
@ -205,21 +205,47 @@ void FlightLogManager::retrieveLogs(int flightToRetrieve)
|
||||
for (int flight = startFlight; flight <= endFlight; flight++) {
|
||||
m_flightLogControl->setFlight(flight);
|
||||
bool gotLast = false;
|
||||
int entry = 0;
|
||||
int slot = 0;
|
||||
while (!gotLast) {
|
||||
// Send request for loading flight entry on flight side and wait for ack/nack
|
||||
m_flightLogControl->setEntry(entry);
|
||||
m_flightLogControl->setEntry(slot);
|
||||
|
||||
if (updateHelper.doObjectAndWait(m_flightLogControl, UAVTALK_TIMEOUT) == UAVObjectUpdaterHelper::SUCCESS &&
|
||||
requestHelper.doObjectAndWait(m_flightLogEntry, UAVTALK_TIMEOUT) == UAVObjectUpdaterHelper::SUCCESS) {
|
||||
if (m_flightLogEntry->getType() != DebugLogEntry::TYPE_EMPTY) {
|
||||
// Ok, we retrieved the entry, and it was the correct one. clone it and add it to the list
|
||||
ExtendedDebugLogEntry *logEntry = new ExtendedDebugLogEntry();
|
||||
|
||||
logEntry->setData(m_flightLogEntry->getData(), m_objectManager);
|
||||
m_logEntries << logEntry;
|
||||
if (logEntry->getData().Type == DebugLogEntry::TYPE_MULTIPLEUAVOBJECTS) {
|
||||
const quint32 total_len = sizeof(DebugLogEntry::DataFields);
|
||||
const quint32 data_len = sizeof(((DebugLogEntry::DataFields *)0)->Data);
|
||||
const quint32 header_len = total_len - data_len;
|
||||
|
||||
DebugLogEntry::DataFields fields;
|
||||
quint32 start = logEntry->getData().Size;
|
||||
|
||||
// cycle until there is space for another object
|
||||
while (start + header_len + 1 < data_len) {
|
||||
memset(&fields, 0xFF, total_len);
|
||||
memcpy(&fields, &logEntry->getData().Data[start], header_len);
|
||||
// check wether a packed object is found
|
||||
// note that empty data blocks are set as 0xFF in flight side to minimize flash wearing
|
||||
// thus as soon as this read outside of used area, the test will fail as lenght would be 0xFFFF
|
||||
quint32 toread = header_len + fields.Size;
|
||||
if (!(toread + start > data_len)) {
|
||||
memcpy(&fields, &logEntry->getData().Data[start], toread);
|
||||
ExtendedDebugLogEntry *subEntry = new ExtendedDebugLogEntry();
|
||||
subEntry->setData(fields, m_objectManager);
|
||||
m_logEntries << subEntry;
|
||||
}
|
||||
start += toread;
|
||||
}
|
||||
}
|
||||
|
||||
// Increment to get next entry from flight side
|
||||
entry++;
|
||||
slot++;
|
||||
} else {
|
||||
// We are done, not more entries on this flight
|
||||
gotLast = true;
|
||||
@ -280,7 +306,7 @@ void FlightLogManager::exportToOPL(QString fileName)
|
||||
ExtendedDebugLogEntry *entry = m_logEntries[currentEntry];
|
||||
|
||||
// Only log uavobjects
|
||||
if (entry->getType() == ExtendedDebugLogEntry::TYPE_UAVOBJECT) {
|
||||
if (entry->getType() == ExtendedDebugLogEntry::TYPE_UAVOBJECT || entry->getType() == ExtendedDebugLogEntry::TYPE_MULTIPLEUAVOBJECTS) {
|
||||
// Set timestamp that should be logged for this entry
|
||||
logFile.setNextTimeStamp(entry->getFlightTime() - adjustedBaseTime);
|
||||
|
||||
@ -615,7 +641,7 @@ QString ExtendedDebugLogEntry::getLogString()
|
||||
{
|
||||
if (getType() == DebugLogEntry::TYPE_TEXT) {
|
||||
return QString((const char *)getData().Data);
|
||||
} else if (getType() == DebugLogEntry::TYPE_UAVOBJECT) {
|
||||
} else if (getType() == DebugLogEntry::TYPE_UAVOBJECT || getType() == DebugLogEntry::TYPE_MULTIPLEUAVOBJECTS) {
|
||||
return m_object->toString().replace("\n", " ").replace("\t", " ");
|
||||
} else {
|
||||
return "";
|
||||
@ -631,7 +657,7 @@ void ExtendedDebugLogEntry::toXML(QXmlStreamWriter *xmlWriter, quint32 baseTime)
|
||||
if (getType() == DebugLogEntry::TYPE_TEXT) {
|
||||
xmlWriter->writeAttribute("type", "text");
|
||||
xmlWriter->writeTextElement("message", QString((const char *)getData().Data));
|
||||
} else if (getType() == DebugLogEntry::TYPE_UAVOBJECT) {
|
||||
} else if (getType() == DebugLogEntry::TYPE_UAVOBJECT || getType() == DebugLogEntry::TYPE_MULTIPLEUAVOBJECTS) {
|
||||
xmlWriter->writeAttribute("type", "uavobject");
|
||||
m_object->toXML(xmlWriter);
|
||||
}
|
||||
@ -644,7 +670,7 @@ void ExtendedDebugLogEntry::toCSV(QTextStream *csvStream, quint32 baseTime)
|
||||
|
||||
if (getType() == DebugLogEntry::TYPE_TEXT) {
|
||||
data = QString((const char *)getData().Data);
|
||||
} else if (getType() == DebugLogEntry::TYPE_UAVOBJECT) {
|
||||
} else if (getType() == DebugLogEntry::TYPE_UAVOBJECT || getType() == DebugLogEntry::TYPE_MULTIPLEUAVOBJECTS) {
|
||||
data = m_object->toString().replace("\n", "").replace("\t", "");
|
||||
}
|
||||
*csvStream << QString::number(getFlight() + 1) << '\t' << QString::number(getFlightTime() - baseTime) << '\t' << QString::number(getEntry()) << '\t' << data << '\n';
|
||||
@ -654,7 +680,7 @@ void ExtendedDebugLogEntry::setData(const DebugLogEntry::DataFields &data, UAVOb
|
||||
{
|
||||
DebugLogEntry::setData(data);
|
||||
|
||||
if (getType() == DebugLogEntry::TYPE_UAVOBJECT) {
|
||||
if (getType() == DebugLogEntry::TYPE_UAVOBJECT || getType() == DebugLogEntry::TYPE_MULTIPLEUAVOBJECTS) {
|
||||
UAVDataObject *object = (UAVDataObject *)objectManager->getObject(getObjectID(), getInstanceID());
|
||||
Q_ASSERT(object);
|
||||
m_object = object->clone(getInstanceID());
|
||||
|
@ -94,6 +94,10 @@ public slots:
|
||||
setDirty(true);
|
||||
if (m_setting != 1 && m_setting != 3) {
|
||||
setPeriod(0);
|
||||
} else {
|
||||
if (!period()) {
|
||||
setPeriod(500);
|
||||
}
|
||||
}
|
||||
emit settingChanged(setting);
|
||||
}
|
||||
@ -178,7 +182,7 @@ class FlightLogManager : public QObject {
|
||||
Q_PROPERTY(QStringList logSettings READ logSettings NOTIFY logSettingsChanged)
|
||||
Q_PROPERTY(QStringList logStatuses READ logStatuses NOTIFY logStatusesChanged)
|
||||
Q_PROPERTY(int loggingEnabled READ loggingEnabled WRITE setLoggingEnabled NOTIFY loggingEnabledChanged)
|
||||
|
||||
Q_PROPERTY(int logEntriesCount READ logEntriesCount NOTIFY logEntriesChanged)
|
||||
|
||||
public:
|
||||
explicit FlightLogManager(QObject *parent = 0);
|
||||
@ -240,7 +244,10 @@ public:
|
||||
{
|
||||
return m_loggingEnabled;
|
||||
}
|
||||
|
||||
int logEntriesCount()
|
||||
{
|
||||
return m_logEntries.count();
|
||||
}
|
||||
signals:
|
||||
void logEntriesChanged();
|
||||
void flightEntriesChanged();
|
||||
|
@ -26,14 +26,15 @@
|
||||
#include <QtPlugin>
|
||||
#include <QStringList>
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <QtQuick>
|
||||
|
||||
#include <coreplugin/coreconstants.h>
|
||||
#include <coreplugin/actionmanager/actionmanager.h>
|
||||
#include <coreplugin/icore.h>
|
||||
#include <QKeySequence>
|
||||
#include <coreplugin/modemanager.h>
|
||||
|
||||
#include "flightlogdialog.h"
|
||||
#include "flightlogmanager.h"
|
||||
#include "uavobject.h"
|
||||
|
||||
FlightLogPlugin::FlightLogPlugin() : m_logDialog(0)
|
||||
{}
|
||||
@ -72,12 +73,23 @@ bool FlightLogPlugin::initialize(const QStringList & args, QString *errMsg)
|
||||
void FlightLogPlugin::ShowLogManagementDialog()
|
||||
{
|
||||
if (!m_logDialog) {
|
||||
m_logDialog = new FlightLogDialog(0, new FlightLogManager());
|
||||
connect(m_logDialog, SIGNAL(finished(int)), this, SLOT(LogManagementDialogClosed()));
|
||||
m_logDialog->show();
|
||||
} else {
|
||||
m_logDialog->raise();
|
||||
qmlRegisterType<ExtendedDebugLogEntry>("org.openpilot", 1, 0, "DebugLogEntry");
|
||||
qmlRegisterType<UAVOLogSettingsWrapper>("org.openpilot", 1, 0, "UAVOLogSettingsWrapper");
|
||||
FlightLogManager *flightLogManager = new FlightLogManager();
|
||||
m_logDialog = new QQuickView();
|
||||
m_logDialog->setIcon(QIcon(":/core/images/openpilot_logo_32.png"));
|
||||
m_logDialog->setTitle(tr("Manage flight side logs"));
|
||||
m_logDialog->rootContext()->setContextProperty("logStatus", flightLogManager->flightLogStatus());
|
||||
m_logDialog->rootContext()->setContextProperty("logControl", flightLogManager->flightLogControl());
|
||||
m_logDialog->rootContext()->setContextProperty("logSettings", flightLogManager->flightLogSettings());
|
||||
m_logDialog->rootContext()->setContextProperty("logManager", flightLogManager);
|
||||
m_logDialog->rootContext()->setContextProperty("logDialog", m_logDialog);
|
||||
m_logDialog->setResizeMode(QQuickView::SizeRootObjectToView);
|
||||
m_logDialog->setSource(QUrl("qrc:/flightlog/FlightLogDialog.qml"));
|
||||
m_logDialog->setModality(Qt::ApplicationModal);
|
||||
connect(m_logDialog, SIGNAL(destroyed()), this, SLOT(LogManagementDialogClosed()));
|
||||
}
|
||||
m_logDialog->show();
|
||||
}
|
||||
|
||||
void FlightLogPlugin::LogManagementDialogClosed()
|
||||
|
@ -28,7 +28,7 @@
|
||||
|
||||
#include <extensionsystem/iplugin.h>
|
||||
#include "flightlogmanager.h"
|
||||
#include "flightlogdialog.h"
|
||||
#include <QQuickView>
|
||||
|
||||
class FlightLogPlugin : public ExtensionSystem::IPlugin {
|
||||
Q_OBJECT
|
||||
@ -47,7 +47,7 @@ private slots:
|
||||
void LogManagementDialogClosed();
|
||||
|
||||
private:
|
||||
FlightLogDialog *m_logDialog;
|
||||
QQuickView *m_logDialog;
|
||||
};
|
||||
|
||||
#endif /* FLIGHTLOGPLUGIN_H_ */
|
||||
|
@ -11,6 +11,12 @@ function millisToTime(ms) {
|
||||
return pad(hours, 2) + ":" + pad(minutes, 2) + ":" + pad(seconds, 2) + ":" + pad(msleft, 3);
|
||||
}
|
||||
|
||||
|
||||
function microsToTime(us) {
|
||||
var ms = Math.floor(us / 1000);
|
||||
return millisToTime(ms);
|
||||
}
|
||||
|
||||
function pad(number, length) {
|
||||
var str = '' + number;
|
||||
while (str.length < length) {
|
||||
|
@ -67,11 +67,7 @@ HIDAPI BOOL WINAPI HidD_FreePreparsedData(PHIDP_PREPARSED_DATA);
|
||||
HIDAPI BOOL WINAPI HidD_FlushQueue(HANDLE);
|
||||
HIDAPI BOOL WINAPI HidD_GetConfiguration(HANDLE, PHIDD_CONFIGURATION, ULONG);
|
||||
HIDAPI BOOL WINAPI HidD_SetConfiguration(HANDLE, PHIDD_CONFIGURATION, ULONG);
|
||||
HIDAPI BOOL WINAPI HidD_GetNumInputBuffers(HANDLE, PULONG);
|
||||
HIDAPI BOOL WINAPI HidD_SetNumInputBuffers(HANDLE HidDeviceObject, ULONG);
|
||||
HIDAPI BOOL WINAPI HidD_GetPhysicalDescriptor(HANDLE, PVOID, ULONG);
|
||||
HIDAPI BOOL WINAPI HidD_GetManufacturerString(HANDLE, PVOID, ULONG);
|
||||
HIDAPI BOOL WINAPI HidD_GetProductString(HANDLE, PVOID, ULONG);
|
||||
HIDAPI BOOL WINAPI HidD_GetIndexedString(HANDLE, ULONG, PVOID, ULONG);
|
||||
HIDAPI BOOL WINAPI HidD_GetSerialNumberString(HANDLE, PVOID, ULONG);
|
||||
|
||||
|
@ -66,7 +66,8 @@ PfdQmlGadgetWidget::PfdQmlGadgetWidget(QWindow *parent) :
|
||||
"ActuatorDesired" <<
|
||||
"TakeOffLocation" <<
|
||||
"PathPlan" <<
|
||||
"WaypointActive";
|
||||
"WaypointActive" <<
|
||||
"OPLinkStatus";
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
|
@ -264,7 +264,7 @@ void ScopeGadgetWidget::preparePlot(PlotType plotType)
|
||||
|
||||
// Only start the timer if we are already connected
|
||||
Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager();
|
||||
if (cm->getCurrentConnection() && replotTimer) {
|
||||
if (cm->isConnected() && replotTimer) {
|
||||
if (!replotTimer->isActive()) {
|
||||
replotTimer->start(m_refreshInterval);
|
||||
} else {
|
||||
|
@ -37,23 +37,13 @@
|
||||
|
||||
|
||||
SerialEnumerationThread::SerialEnumerationThread(SerialConnection *serial)
|
||||
: m_serial(serial),
|
||||
m_running(true)
|
||||
: m_serial(serial), m_running(false)
|
||||
{}
|
||||
|
||||
SerialEnumerationThread::~SerialEnumerationThread()
|
||||
{
|
||||
m_running = false;
|
||||
// wait for the thread to terminate
|
||||
if (wait(2100) == false) {
|
||||
qDebug() << "Cannot terminate SerialEnumerationThread";
|
||||
}
|
||||
}
|
||||
|
||||
void SerialEnumerationThread::run()
|
||||
{
|
||||
m_running = true;
|
||||
QList <Core::IConnection::device> devices = m_serial->availableDevices();
|
||||
|
||||
while (m_running) {
|
||||
if (!m_serial->deviceOpened()) {
|
||||
QList <Core::IConnection::device> newDev = m_serial->availableDevices();
|
||||
@ -62,11 +52,22 @@ void SerialEnumerationThread::run()
|
||||
emit enumerationChanged();
|
||||
}
|
||||
}
|
||||
|
||||
msleep(2000); // update available devices every two seconds (doesn't need more)
|
||||
// update available devices every two seconds (doesn't need more)
|
||||
msleep(2000);
|
||||
}
|
||||
}
|
||||
|
||||
void SerialEnumerationThread::stop()
|
||||
{
|
||||
if (!m_running) {
|
||||
return;
|
||||
}
|
||||
m_running = false;
|
||||
// wait for the thread to terminate
|
||||
if (wait(2100) == false) {
|
||||
qDebug() << "Cannot terminate SerialEnumerationThread";
|
||||
}
|
||||
}
|
||||
|
||||
SerialConnection::SerialConnection() :
|
||||
serialHandle(NULL),
|
||||
@ -100,7 +101,9 @@ SerialConnection::SerialConnection() :
|
||||
}
|
||||
|
||||
SerialConnection::~SerialConnection()
|
||||
{}
|
||||
{
|
||||
m_enumerateThread.stop();
|
||||
}
|
||||
|
||||
void SerialConnection::onEnumerationChanged()
|
||||
{
|
||||
@ -114,12 +117,29 @@ bool sortPorts(const QSerialPortInfo &s1, const QSerialPortInfo &s2)
|
||||
return s1.portName() < s2.portName();
|
||||
}
|
||||
|
||||
QList<QSerialPortInfo> SerialConnection::availablePorts()
|
||||
{
|
||||
QList<QSerialPortInfo> ports = QSerialPortInfo::availablePorts();
|
||||
#if QT_VERSION == 0x050301 && defined(Q_OS_WIN)
|
||||
// workaround to QTBUG-39748 (https://bugreports.qt-project.org/browse/QTBUG-39748)
|
||||
// Qt 5.3.1 reports spurious ports with an empty description...
|
||||
QMutableListIterator<QSerialPortInfo> i(ports);
|
||||
while (i.hasNext()) {
|
||||
if (i.next().description().isEmpty()) {
|
||||
i.remove();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
return ports;
|
||||
}
|
||||
|
||||
|
||||
QList <Core::IConnection::device> SerialConnection::availableDevices()
|
||||
{
|
||||
QList <Core::IConnection::device> list;
|
||||
|
||||
if (enablePolling) {
|
||||
QList<QSerialPortInfo> ports = QSerialPortInfo::availablePorts();
|
||||
QList<QSerialPortInfo> ports = availablePorts();
|
||||
|
||||
// sort the list by port number (nice idea from PT_Dreamer :))
|
||||
qSort(ports.begin(), ports.end(), sortPorts);
|
||||
@ -140,18 +160,20 @@ QIODevice *SerialConnection::openDevice(const QString &deviceName)
|
||||
if (serialHandle) {
|
||||
closeDevice(deviceName);
|
||||
}
|
||||
QList<QSerialPortInfo> ports = QSerialPortInfo::availablePorts();
|
||||
QList<QSerialPortInfo> ports = availablePorts();
|
||||
foreach(QSerialPortInfo port, ports) {
|
||||
if (port.portName() == deviceName) {
|
||||
// don't specify a parent when constructing the QSerialPort as this object will be moved
|
||||
// to a different thread later on (see telemetrymanager.cpp)
|
||||
serialHandle = new QSerialPort(port);
|
||||
// we need to handle port settings here...
|
||||
qDebug() << "Serial telemetry running at " << m_config->speed();
|
||||
serialHandle = new QSerialPort(port, this);
|
||||
if (serialHandle->open(QIODevice::ReadWrite)) {
|
||||
if (serialHandle->setBaudRate(m_config->speed().toInt())
|
||||
&& serialHandle->setDataBits(QSerialPort::Data8)
|
||||
&& serialHandle->setParity(QSerialPort::NoParity)
|
||||
&& serialHandle->setStopBits(QSerialPort::OneStop)
|
||||
&& serialHandle->setFlowControl(QSerialPort::NoFlowControl)) {
|
||||
qDebug() << "Serial telemetry running at " << m_config->speed();
|
||||
m_deviceOpened = true;
|
||||
}
|
||||
}
|
||||
@ -167,12 +189,11 @@ void SerialConnection::closeDevice(const QString &deviceName)
|
||||
// we have to delete the serial connection we created
|
||||
if (serialHandle) {
|
||||
serialHandle->deleteLater();
|
||||
serialHandle = NULL;
|
||||
m_deviceOpened = false;
|
||||
serialHandle = NULL;
|
||||
}
|
||||
m_deviceOpened = false;
|
||||
}
|
||||
|
||||
|
||||
QString SerialConnection::connectionName()
|
||||
{
|
||||
return QString("Serial port");
|
||||
@ -199,7 +220,7 @@ void SerialConnection::resumePolling()
|
||||
enablePolling = true;
|
||||
}
|
||||
|
||||
SerialPlugin::SerialPlugin()
|
||||
SerialPlugin::SerialPlugin() : m_connection(0)
|
||||
{}
|
||||
|
||||
SerialPlugin::~SerialPlugin()
|
||||
|
@ -51,10 +51,11 @@ class SerialEnumerationThread : public QThread {
|
||||
Q_OBJECT
|
||||
public:
|
||||
SerialEnumerationThread(SerialConnection *serial);
|
||||
virtual ~SerialEnumerationThread();
|
||||
|
||||
virtual void run();
|
||||
|
||||
void stop();
|
||||
|
||||
signals:
|
||||
void enumerationChanged();
|
||||
|
||||
@ -106,6 +107,8 @@ private:
|
||||
SerialPluginConfiguration *m_config;
|
||||
SerialPluginOptionsPage *m_optionspage;
|
||||
|
||||
QList<QSerialPortInfo> availablePorts();
|
||||
|
||||
protected slots:
|
||||
void onEnumerationChanged();
|
||||
|
||||
|
@ -107,6 +107,9 @@ void ConnectionDiagram::setupGraphicsScene()
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA:
|
||||
elementsToShow << "hexa";
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_X:
|
||||
elementsToShow << "hexa-x";
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y:
|
||||
elementsToShow << "hexa-y";
|
||||
break;
|
||||
|
@ -101,11 +101,15 @@ void MultiPage::setupMultiTypesCombo()
|
||||
ui->typeCombo->addItem(tr("Hexacopter"), SetupWizard::MULTI_ROTOR_HEXA);
|
||||
m_descriptions << tr("Hexacopter");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter X"), SetupWizard::MULTI_ROTOR_HEXA_X);
|
||||
m_descriptions << tr("Hexacopter X");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter H"), SetupWizard::MULTI_ROTOR_HEXA_H);
|
||||
m_descriptions << tr("Hexacopter H");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter Coax (Y6)"), SetupWizard::MULTI_ROTOR_HEXA_COAX_Y);
|
||||
m_descriptions << tr("Hexacopter Coax (Y6)");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter X"), SetupWizard::MULTI_ROTOR_HEXA_H);
|
||||
m_descriptions << tr("Hexacopter H");
|
||||
|
||||
// Fredrik Arvidsson(m_thread) 2012-08-26 Disable Octos until further notice
|
||||
/*
|
||||
@ -159,6 +163,9 @@ void MultiPage::updateImageAndDescription()
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_H:
|
||||
elementId = "quad-hexa-H";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_X:
|
||||
elementId = "quad-hexa-X";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_OCTO:
|
||||
elementId = "quad-octo";
|
||||
break;
|
||||
|
@ -104,6 +104,12 @@ void OutputCalibrationPage::setupVehicle()
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_X:
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "hexa-x" << "hexa-x-frame" << "hexa-x-m1" << "hexa-x-m2" << "hexa-x-m3" << "hexa-x-m4" << "hexa-x-m5" << "hexa-x-m6";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
Before Width: | Height: | Size: 483 KiB After Width: | Height: | Size: 524 KiB |
Before Width: | Height: | Size: 431 KiB After Width: | Height: | Size: 432 KiB |
@ -204,6 +204,9 @@ QString SetupWizard::getSummaryText()
|
||||
summary.append(tr("Hexacopter Coax (Y6)"));
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_H:
|
||||
summary.append(tr("Hexacopter H"));
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_X:
|
||||
summary.append(tr("Hexacopter X"));
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_OCTO:
|
||||
|
@ -202,9 +202,11 @@ void VehicleConfigurationHelper::applyVehicleConfiguration()
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_X:
|
||||
setupHexaCopter();
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_X:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_V:
|
||||
@ -279,7 +281,9 @@ void VehicleConfigurationHelper::applyActuatorConfiguration()
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_X:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_X:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_V:
|
||||
@ -633,8 +637,9 @@ void VehicleConfigurationHelper::resetVehicleConfig()
|
||||
for (int i = 1; i <= 2; i++) {
|
||||
UAVObjectField *field = mSettings->getField(throttlePattern.arg(i));
|
||||
Q_ASSERT(field);
|
||||
// Wizard support only Multirotors - Set default curve with 90% max
|
||||
for (quint32 i = 0; i < field->getNumElements(); i++) {
|
||||
field->setValue(i * (1.0f / (field->getNumElements() - 1)), i);
|
||||
field->setValue(i * (0.9f / (field->getNumElements() - 1)), i);
|
||||
}
|
||||
}
|
||||
|
||||
@ -831,48 +836,55 @@ void VehicleConfigurationHelper::setupHexaCopter()
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA:
|
||||
{
|
||||
frame = SystemSettings::AIRFRAMETYPE_HEXA;
|
||||
|
||||
// HexaPlus according to new mixer table and pitch-roll-yaw mixing at 100%
|
||||
// Pitch Roll Yaw
|
||||
// M1 { 1 , 0 , -1 },
|
||||
// M2 { 0.5, -1, 1 },
|
||||
// M3 { -0.5, -1, -1 },
|
||||
// M4 { -1 , 0 , 1 },
|
||||
// M5 { -0.5, 1 , -1 },
|
||||
// M6 { 0.5, 1 , 1 },
|
||||
channels[0].type = MIXER_TYPE_MOTOR;
|
||||
channels[0].throttle1 = 100;
|
||||
channels[0].throttle2 = 0;
|
||||
channels[0].roll = 0;
|
||||
channels[0].pitch = 33;
|
||||
channels[0].yaw = -33;
|
||||
channels[0].pitch = 100;
|
||||
channels[0].yaw = -100;
|
||||
|
||||
channels[1].type = MIXER_TYPE_MOTOR;
|
||||
channels[1].throttle1 = 100;
|
||||
channels[1].throttle2 = 0;
|
||||
channels[1].roll = -50;
|
||||
channels[1].pitch = 33;
|
||||
channels[1].yaw = 33;
|
||||
channels[1].roll = -100;
|
||||
channels[1].pitch = 50;
|
||||
channels[1].yaw = 100;
|
||||
|
||||
channels[2].type = MIXER_TYPE_MOTOR;
|
||||
channels[2].throttle1 = 100;
|
||||
channels[2].throttle2 = 0;
|
||||
channels[2].roll = -50;
|
||||
channels[2].pitch = -33;
|
||||
channels[2].yaw = -33;
|
||||
channels[2].roll = -100;
|
||||
channels[2].pitch = -50;
|
||||
channels[2].yaw = -100;
|
||||
|
||||
channels[3].type = MIXER_TYPE_MOTOR;
|
||||
channels[3].throttle1 = 100;
|
||||
channels[3].throttle2 = 0;
|
||||
channels[3].roll = 0;
|
||||
channels[3].pitch = -33;
|
||||
channels[3].yaw = 33;
|
||||
channels[3].pitch = -100;
|
||||
channels[3].yaw = 100;
|
||||
|
||||
channels[4].type = MIXER_TYPE_MOTOR;
|
||||
channels[4].throttle1 = 100;
|
||||
channels[4].throttle2 = 0;
|
||||
channels[4].roll = 50;
|
||||
channels[4].pitch = -33;
|
||||
channels[4].yaw = -33;
|
||||
channels[4].roll = 100;
|
||||
channels[4].pitch = -50;
|
||||
channels[4].yaw = -100;
|
||||
|
||||
channels[5].type = MIXER_TYPE_MOTOR;
|
||||
channels[5].throttle1 = 100;
|
||||
channels[5].throttle2 = 0;
|
||||
channels[5].roll = 50;
|
||||
channels[5].pitch = 33;
|
||||
channels[5].yaw = 33;
|
||||
channels[5].roll = 100;
|
||||
channels[5].pitch = 50;
|
||||
channels[5].yaw = 100;
|
||||
|
||||
guiSettings.multi.VTOLMotorN = 1;
|
||||
guiSettings.multi.VTOLMotorNE = 2;
|
||||
@ -940,49 +952,118 @@ void VehicleConfigurationHelper::setupHexaCopter()
|
||||
}
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H:
|
||||
{
|
||||
frame = SystemSettings::AIRFRAMETYPE_HEXAX;
|
||||
|
||||
frame = SystemSettings::AIRFRAMETYPE_HEXAH;
|
||||
// HexaH according to new mixer table and pitch-roll-yaw mixing at 100%
|
||||
// Pitch Roll Yaw
|
||||
// M1 { 1 , -0.5, -0.5 },
|
||||
// M2 { 0 , -1 , 1 },
|
||||
// M3 { -1 , -0.5, -0.5 },
|
||||
// M4 { -1 , 0.5, 0.5 },
|
||||
// M5 { 0 , 1 , -1 },
|
||||
// M6 { 1 , 0.5, 0.5 },
|
||||
channels[0].type = MIXER_TYPE_MOTOR;
|
||||
channels[0].throttle1 = 100;
|
||||
channels[0].throttle2 = 0;
|
||||
channels[0].roll = -33;
|
||||
channels[0].pitch = 50;
|
||||
channels[0].yaw = -33;
|
||||
channels[0].roll = -50;
|
||||
channels[0].pitch = 100;
|
||||
channels[0].yaw = -50;
|
||||
|
||||
channels[1].type = MIXER_TYPE_MOTOR;
|
||||
channels[1].throttle1 = 100;
|
||||
channels[1].throttle2 = 0;
|
||||
channels[1].roll = -33;
|
||||
channels[1].roll = -100;
|
||||
channels[1].pitch = 0;
|
||||
channels[1].yaw = 33;
|
||||
channels[1].yaw = 100;
|
||||
|
||||
channels[2].type = MIXER_TYPE_MOTOR;
|
||||
channels[2].throttle1 = 100;
|
||||
channels[2].throttle2 = 0;
|
||||
channels[2].roll = -33;
|
||||
channels[2].pitch = -50;
|
||||
channels[2].yaw = -33;
|
||||
channels[2].roll = -50;
|
||||
channels[2].pitch = -100;
|
||||
channels[2].yaw = -50;
|
||||
|
||||
channels[3].type = MIXER_TYPE_MOTOR;
|
||||
channels[3].throttle1 = 100;
|
||||
channels[3].throttle2 = 0;
|
||||
channels[3].roll = -33;
|
||||
channels[3].pitch = -50;
|
||||
channels[3].yaw = 33;
|
||||
channels[3].roll = 50;
|
||||
channels[3].pitch = -100;
|
||||
channels[3].yaw = 50;
|
||||
|
||||
channels[4].type = MIXER_TYPE_MOTOR;
|
||||
channels[4].throttle1 = 100;
|
||||
channels[4].throttle2 = 0;
|
||||
channels[4].roll = 33;
|
||||
channels[4].roll = 100;
|
||||
channels[4].pitch = 0;
|
||||
channels[4].yaw = -33;
|
||||
channels[4].yaw = -100;
|
||||
|
||||
channels[5].type = MIXER_TYPE_MOTOR;
|
||||
channels[5].throttle1 = 100;
|
||||
channels[5].throttle2 = 0;
|
||||
channels[5].roll = 33;
|
||||
channels[5].pitch = 50;
|
||||
channels[5].yaw = -33;
|
||||
channels[5].roll = 50;
|
||||
channels[5].pitch = 100;
|
||||
channels[5].yaw = 50;
|
||||
|
||||
guiSettings.multi.VTOLMotorNE = 1;
|
||||
guiSettings.multi.VTOLMotorE = 2;
|
||||
guiSettings.multi.VTOLMotorSE = 3;
|
||||
guiSettings.multi.VTOLMotorSW = 4;
|
||||
guiSettings.multi.VTOLMotorW = 5;
|
||||
guiSettings.multi.VTOLMotorNW = 6;
|
||||
|
||||
break;
|
||||
}
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_X:
|
||||
{
|
||||
frame = SystemSettings::AIRFRAMETYPE_HEXAH;
|
||||
// HexaX according to new mixer table and pitch-roll-yaw mixing at 100%
|
||||
// Pitch Roll Yaw
|
||||
// M1 { 1, -0.5, -1 },
|
||||
// M2 { 0, -1 , 1 },
|
||||
// M3 { -1, -0.5, -1 },
|
||||
// M4 { -1, 0.5, 1 },
|
||||
// M5 { 0, 1 , -1 },
|
||||
// M6 { 1, 0.5, 1 },
|
||||
channels[0].type = MIXER_TYPE_MOTOR;
|
||||
channels[0].throttle1 = 100;
|
||||
channels[0].throttle2 = 0;
|
||||
channels[0].roll = -50;
|
||||
channels[0].pitch = 100;
|
||||
channels[0].yaw = -100;
|
||||
|
||||
channels[1].type = MIXER_TYPE_MOTOR;
|
||||
channels[1].throttle1 = 100;
|
||||
channels[1].throttle2 = 0;
|
||||
channels[1].roll = -100;
|
||||
channels[1].pitch = 0;
|
||||
channels[1].yaw = 100;
|
||||
|
||||
channels[2].type = MIXER_TYPE_MOTOR;
|
||||
channels[2].throttle1 = 100;
|
||||
channels[2].throttle2 = 0;
|
||||
channels[2].roll = -50;
|
||||
channels[2].pitch = -100;
|
||||
channels[2].yaw = -100;
|
||||
|
||||
channels[3].type = MIXER_TYPE_MOTOR;
|
||||
channels[3].throttle1 = 100;
|
||||
channels[3].throttle2 = 0;
|
||||
channels[3].roll = 50;
|
||||
channels[3].pitch = -100;
|
||||
channels[3].yaw = 100;
|
||||
|
||||
channels[4].type = MIXER_TYPE_MOTOR;
|
||||
channels[4].throttle1 = 100;
|
||||
channels[4].throttle2 = 0;
|
||||
channels[4].roll = 100;
|
||||
channels[4].pitch = 0;
|
||||
channels[4].yaw = -100;
|
||||
|
||||
channels[5].type = MIXER_TYPE_MOTOR;
|
||||
channels[5].throttle1 = 100;
|
||||
channels[5].throttle2 = 0;
|
||||
channels[5].roll = 50;
|
||||
channels[5].pitch = 100;
|
||||
channels[5].yaw = 100;
|
||||
|
||||
guiSettings.multi.VTOLMotorNE = 1;
|
||||
guiSettings.multi.VTOLMotorE = 2;
|
||||
@ -1010,62 +1091,71 @@ void VehicleConfigurationHelper::setupOctoCopter()
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO:
|
||||
{
|
||||
frame = SystemSettings::AIRFRAMETYPE_OCTO;
|
||||
|
||||
// OctoP according to new mixer table and pitch-roll-yaw mixing at 100%
|
||||
// Pitch Roll Yaw
|
||||
// M1{ 1 , 0 , -1 },
|
||||
// M2{ 0.71,-0.71, 1 },
|
||||
// M3{ 0 ,-1 , -1 },
|
||||
// M4{ -0.71,-0.71, 1 },
|
||||
// M5{ -1 , 0 , -1 },
|
||||
// M6{ -0.71, 0.71, 1 },
|
||||
// M7{ 0 , 1 , -1 },
|
||||
// M8{ 0.71, 0.71, 1 }
|
||||
channels[0].type = MIXER_TYPE_MOTOR;
|
||||
channels[0].throttle1 = 100;
|
||||
channels[0].throttle2 = 0;
|
||||
channels[0].roll = 0;
|
||||
channels[0].pitch = 33;
|
||||
channels[0].yaw = -25;
|
||||
channels[0].pitch = 100;
|
||||
channels[0].yaw = -100;
|
||||
|
||||
channels[1].type = MIXER_TYPE_MOTOR;
|
||||
channels[1].throttle1 = 100;
|
||||
channels[1].throttle2 = 0;
|
||||
channels[1].roll = -33;
|
||||
channels[1].pitch = 33;
|
||||
channels[1].yaw = 25;
|
||||
channels[1].roll = -71;
|
||||
channels[1].pitch = 71;
|
||||
channels[1].yaw = 100;
|
||||
|
||||
channels[2].type = MIXER_TYPE_MOTOR;
|
||||
channels[2].throttle1 = 100;
|
||||
channels[2].throttle2 = 0;
|
||||
channels[2].roll = -33;
|
||||
channels[2].roll = -71;
|
||||
channels[2].pitch = 0;
|
||||
channels[2].yaw = -25;
|
||||
channels[2].yaw = -100;
|
||||
|
||||
channels[3].type = MIXER_TYPE_MOTOR;
|
||||
channels[3].throttle1 = 100;
|
||||
channels[3].throttle2 = 0;
|
||||
channels[3].roll = -33;
|
||||
channels[3].pitch = -33;
|
||||
channels[3].yaw = 25;
|
||||
channels[3].roll = -71;
|
||||
channels[3].pitch = -71;
|
||||
channels[3].yaw = 100;
|
||||
|
||||
channels[4].type = MIXER_TYPE_MOTOR;
|
||||
channels[4].throttle1 = 100;
|
||||
channels[4].throttle2 = 0;
|
||||
channels[4].roll = 0;
|
||||
channels[4].pitch = -33;
|
||||
channels[4].yaw = -25;
|
||||
channels[4].pitch = -100;
|
||||
channels[4].yaw = -100;
|
||||
|
||||
channels[5].type = MIXER_TYPE_MOTOR;
|
||||
channels[5].throttle1 = 100;
|
||||
channels[5].throttle2 = 0;
|
||||
channels[5].roll = 33;
|
||||
channels[5].pitch = -33;
|
||||
channels[5].yaw = 25;
|
||||
channels[5].roll = 71;
|
||||
channels[5].pitch = -71;
|
||||
channels[5].yaw = 100;
|
||||
|
||||
channels[6].type = MIXER_TYPE_MOTOR;
|
||||
channels[6].throttle1 = 100;
|
||||
channels[6].throttle2 = 0;
|
||||
channels[6].roll = 33;
|
||||
channels[6].roll = 100;
|
||||
channels[6].pitch = 0;
|
||||
channels[6].yaw = -25;
|
||||
channels[6].yaw = -100;
|
||||
|
||||
channels[7].type = MIXER_TYPE_MOTOR;
|
||||
channels[7].throttle1 = 100;
|
||||
channels[7].throttle2 = 0;
|
||||
channels[7].roll = 33;
|
||||
channels[7].pitch = 33;
|
||||
channels[7].yaw = 25;
|
||||
channels[7].roll = 71;
|
||||
channels[7].pitch = 71;
|
||||
channels[7].yaw = 100;
|
||||
|
||||
guiSettings.multi.VTOLMotorN = 1;
|
||||
guiSettings.multi.VTOLMotorNE = 2;
|
||||
@ -1078,6 +1168,86 @@ void VehicleConfigurationHelper::setupOctoCopter()
|
||||
|
||||
break;
|
||||
}
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_X:
|
||||
{
|
||||
frame = SystemSettings::AIRFRAMETYPE_OCTOX;
|
||||
// OctoX according to new mixer table and pitch-roll-yaw mixing at 100%
|
||||
// Pitch Roll Yaw
|
||||
// M1{ 1 ,-0.41, -1 },
|
||||
// M2{ 0.41, -1 , 1 },
|
||||
// M3{ -0.41, -1 , -1 },
|
||||
// M4{ -1 ,-0.41, 1 },
|
||||
// M5{ -1 , 0.41, -1 },
|
||||
// M6{ -0.41, 1 , 1 },
|
||||
// M7{ 0.41, 1 , -1 },
|
||||
// M8{ 1 , 0.41, 1 }
|
||||
channels[0].type = MIXER_TYPE_MOTOR;
|
||||
channels[0].throttle1 = 100;
|
||||
channels[0].throttle2 = 0;
|
||||
channels[0].roll = -41;
|
||||
channels[0].pitch = 100;
|
||||
channels[0].yaw = -100;
|
||||
|
||||
channels[1].type = MIXER_TYPE_MOTOR;
|
||||
channels[1].throttle1 = 100;
|
||||
channels[1].throttle2 = 0;
|
||||
channels[1].roll = -100;
|
||||
channels[1].pitch = 41;
|
||||
channels[1].yaw = 100;
|
||||
|
||||
channels[2].type = MIXER_TYPE_MOTOR;
|
||||
channels[2].throttle1 = 100;
|
||||
channels[2].throttle2 = 0;
|
||||
channels[2].roll = -100;
|
||||
channels[2].pitch = -41;
|
||||
channels[2].yaw = -100;
|
||||
|
||||
channels[3].type = MIXER_TYPE_MOTOR;
|
||||
channels[3].throttle1 = 100;
|
||||
channels[3].throttle2 = 0;
|
||||
channels[3].roll = -41;
|
||||
channels[3].pitch = -100;
|
||||
channels[3].yaw = 100;
|
||||
|
||||
channels[4].type = MIXER_TYPE_MOTOR;
|
||||
channels[4].throttle1 = 100;
|
||||
channels[4].throttle2 = 0;
|
||||
channels[4].roll = 41;
|
||||
channels[4].pitch = -100;
|
||||
channels[4].yaw = -100;
|
||||
|
||||
channels[5].type = MIXER_TYPE_MOTOR;
|
||||
channels[5].throttle1 = 100;
|
||||
channels[5].throttle2 = 0;
|
||||
channels[5].roll = 100;
|
||||
channels[5].pitch = -41;
|
||||
channels[5].yaw = 100;
|
||||
|
||||
channels[6].type = MIXER_TYPE_MOTOR;
|
||||
channels[6].throttle1 = 100;
|
||||
channels[6].throttle2 = 0;
|
||||
channels[6].roll = 100;
|
||||
channels[6].pitch = 41;
|
||||
channels[6].yaw = -100;
|
||||
|
||||
channels[7].type = MIXER_TYPE_MOTOR;
|
||||
channels[7].throttle1 = 100;
|
||||
channels[7].throttle2 = 0;
|
||||
channels[7].roll = 41;
|
||||
channels[7].pitch = 100;
|
||||
channels[7].yaw = 100;
|
||||
|
||||
guiSettings.multi.VTOLMotorNNE = 1;
|
||||
guiSettings.multi.VTOLMotorENE = 2;
|
||||
guiSettings.multi.VTOLMotorESE = 3;
|
||||
guiSettings.multi.VTOLMotorSSE = 4;
|
||||
guiSettings.multi.VTOLMotorSSW = 5;
|
||||
guiSettings.multi.VTOLMotorWSW = 6;
|
||||
guiSettings.multi.VTOLMotorWNW = 7;
|
||||
guiSettings.multi.VTOLMotorNNW = 8;
|
||||
|
||||
break;
|
||||
}
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X:
|
||||
{
|
||||
frame = SystemSettings::AIRFRAMETYPE_OCTOCOAXX;
|
||||
|
@ -58,9 +58,9 @@ public:
|
||||
enum CONTROLLER_TYPE { CONTROLLER_UNKNOWN, CONTROLLER_CC, CONTROLLER_CC3D, CONTROLLER_REVO, CONTROLLER_OPLINK };
|
||||
enum VEHICLE_TYPE { VEHICLE_UNKNOWN, VEHICLE_MULTI, VEHICLE_FIXEDWING, VEHICLE_HELI, VEHICLE_SURFACE };
|
||||
enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS,
|
||||
MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO,
|
||||
MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_AILERON,
|
||||
FIXED_WING_VTAIL, HELI_CCPM };
|
||||
MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO,
|
||||
MULTI_ROTOR_OCTO_X, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS,
|
||||
FIXED_WING_AILERON, FIXED_WING_VTAIL, HELI_CCPM };
|
||||
enum ESC_TYPE { ESC_RAPID, ESC_LEGACY, ESC_UNKNOWN };
|
||||
enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN };
|
||||
|
||||
|
@ -32,7 +32,7 @@
|
||||
#include <QWidget>
|
||||
#include <QLineEdit>
|
||||
|
||||
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), m_isConnected(false), m_isWidgetUpdatesAllowed(true),
|
||||
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), m_currentBoardId(-1), m_isConnected(false), m_isWidgetUpdatesAllowed(true),
|
||||
m_saveButton(NULL), m_isDirty(false), m_outOfLimitsStyle("background-color: rgb(255, 0, 0);"), m_realtimeUpdateTimer(NULL)
|
||||
{
|
||||
m_pluginManager = ExtensionSystem::PluginManager::instance();
|
||||
@ -231,6 +231,20 @@ UAVObjectManager *ConfigTaskWidget::getObjectManager()
|
||||
void ConfigTaskWidget::onAutopilotDisconnect()
|
||||
{
|
||||
m_isConnected = false;
|
||||
|
||||
// Reset board ID and clear bound combo box lists to force repopulation
|
||||
// when we get another connected signal. This means that we get the
|
||||
// correct values in combo boxes bound to fields with limits applied.
|
||||
m_currentBoardId = -1;
|
||||
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
||||
QComboBox *cb;
|
||||
|
||||
if (binding->widget() && (cb = qobject_cast<QComboBox *>(binding->widget()))) {
|
||||
cb->clear();
|
||||
}
|
||||
}
|
||||
|
||||
enableControls(false);
|
||||
invalidateObjects();
|
||||
}
|
||||
@ -275,7 +289,8 @@ void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj)
|
||||
|
||||
bool dirtyBack = isDirty();
|
||||
emit refreshWidgetsValuesRequested();
|
||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject.values(obj)) {
|
||||
QList<WidgetBinding *> bindings = obj == NULL ? m_widgetBindingsPerObject.values() : m_widgetBindingsPerObject.values(obj);
|
||||
foreach(WidgetBinding * binding, bindings) {
|
||||
if (binding->isEnabled() && binding->field() != NULL && binding->widget() != NULL) {
|
||||
setWidgetFromField(binding->widget(), binding->field(), binding);
|
||||
}
|
||||
@ -978,9 +993,16 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field,
|
||||
cb->clear();
|
||||
QStringList option = field->getOptions();
|
||||
if (hasLimits) {
|
||||
foreach(QString str, option) {
|
||||
if (field->isWithinLimits(str, index, m_currentBoardId)) {
|
||||
cb->addItem(str);
|
||||
// Only add options to combo box if we have a board id to check limits for.
|
||||
// We could enter this method while there is no board connected and without
|
||||
// this check, we would add all the board dependent options whether they were
|
||||
// valid or not. Ultimately this method will be called again when the connected
|
||||
// signal is handled.
|
||||
if (m_currentBoardId > -1) {
|
||||
foreach(QString str, option) {
|
||||
if (field->isWithinLimits(str, index, m_currentBoardId)) {
|
||||
cb->addItem(str);
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
|
@ -53,6 +53,12 @@ bool TelemetryManager::isConnected()
|
||||
void TelemetryManager::start(QIODevice *dev)
|
||||
{
|
||||
device = dev;
|
||||
// OP-1383
|
||||
// take ownership of the device by moving it to the TelemetryManager thread (see TelemetryManager constructor)
|
||||
// this removes the following runtime Qt warning and incidentally fixes GCS crashes:
|
||||
// QObject: Cannot create children for a parent that is in a different thread.
|
||||
// (Parent is QSerialPort(0x56af73f8), parent's thread is QThread(0x23f69ae8), current thread is QThread(0x2649cfd8)
|
||||
device->moveToThread(thread());
|
||||
emit myStart();
|
||||
}
|
||||
|
||||
|
@ -64,7 +64,7 @@ SRC += $(PIOSCOMMON)/pios_etasv3.c
|
||||
SRC += $(PIOSCOMMON)/pios_gcsrcvr.c
|
||||
SRC += $(PIOSCOMMON)/pios_hcsr04.c
|
||||
SRC += $(PIOSCOMMON)/pios_hmc5843.c
|
||||
SRC += $(PIOSCOMMON)/pios_hmc5883.c
|
||||
SRC += $(PIOSCOMMON)/pios_hmc5x83.c
|
||||
SRC += $(PIOSCOMMON)/pios_i2c_esc.c
|
||||
SRC += $(PIOSCOMMON)/pios_l3gd20.c
|
||||
SRC += $(PIOSCOMMON)/pios_mpu6000.c
|
||||
@ -109,6 +109,7 @@ SRC += $(FLIGHTLIB)/CoordinateConversions.c
|
||||
SRC += $(MATHLIB)/sin_lookup.c
|
||||
SRC += $(MATHLIB)/pid.c
|
||||
SRC += $(MATHLIB)/mathmisc.c
|
||||
SRC += $(MATHLIB)/butterworth.c
|
||||
SRC += $(FLIGHTLIB)/printf-stdarg.c
|
||||
|
||||
## Modules
|
||||
|
186
make/tools.mk
@ -9,11 +9,12 @@
|
||||
# Ready to use:
|
||||
# arm_sdk_install
|
||||
# qt_sdk_install
|
||||
# mingw_install (Windows only - NOT USED for Qt-5.1.x)
|
||||
# python_install (Windows only - NOT USED for Qt-5.1.x)
|
||||
# mingw_install (Windows only - NOT USED for Qt-5.3.x)
|
||||
# python_install (Windows only - NOT USED for Qt-5.3.x)
|
||||
# nsis_install (Windows only)
|
||||
# sdl_install (Windows only)
|
||||
# openssl_install (Windows only)
|
||||
# mesawin_install (Windows only)
|
||||
# uncrustify_install
|
||||
# doxygen_install
|
||||
# gtest_install
|
||||
@ -60,14 +61,14 @@ ifeq ($(UNAME), Linux)
|
||||
ifeq ($(ARCH), x86_64)
|
||||
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2
|
||||
ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2/+md5
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.2/5.2.1/qt-opensource-linux-x64-5.2.1.run
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-opensource-linux-x64-5.2.1.run.md5
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-linux-x64-5.3.1.run
|
||||
QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-linux-x64-5.3.1.run.md5
|
||||
QT_SDK_ARCH := gcc_64
|
||||
else
|
||||
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2
|
||||
ARM_SDK_MD5_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2/+md5
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.2/5.2.1/qt-opensource-linux-x86-5.2.1.run
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-opensource-linux-x86-5.2.1.run.md5
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-linux-x86-5.3.1.run
|
||||
QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-linux-x86-5.3.1.run.md5
|
||||
QT_SDK_ARCH := gcc
|
||||
endif
|
||||
UNCRUSTIFY_URL := http://wiki.openpilot.org/download/attachments/18612236/uncrustify-0.60.tar.gz
|
||||
@ -75,27 +76,33 @@ ifeq ($(UNAME), Linux)
|
||||
else ifeq ($(UNAME), Darwin)
|
||||
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-mac.tar.bz2
|
||||
ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-mac.tar.bz2/+md5
|
||||
QT_SDK_URL := "Please install native Qt 5.1.x SDK using package manager"
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-mac-x64-clang-5.3.1.dmg
|
||||
QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-mac-x64-clang-5.3.1.dmg.md5
|
||||
QT_SDK_ARCH := clang_64
|
||||
QT_SDK_MAINTENANCE_TOOL := /Volumes/qt-opensource-mac-x64-clang-5.3.1/qt-opensource-mac-x64-clang-5.3.1.app/Contents/MacOS/qt-opensource-mac-x64-clang-5.3.1
|
||||
QT_SDK_MOUNT_DIR := /Volumes/qt-opensource-mac-x64-clang-5.3.1
|
||||
QT_SDK_INSTALLER_DAT := /Volumes/qt-opensource-mac-x64-clang-5.3.1/qt-opensource-mac-x64-clang-5.3.1.app/Contents/Resources/installer.dat
|
||||
UNCRUSTIFY_URL := http://wiki.openpilot.org/download/attachments/18612236/uncrustify-0.60.tar.gz
|
||||
DOXYGEN_URL := http://wiki.openpilot.org/download/attachments/18612236/doxygen-1.8.3.1.src.tar.gz
|
||||
else ifeq ($(UNAME), Windows)
|
||||
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-win32.zip
|
||||
ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-win32.zip/+md5
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.2/5.2.1/qt-opensource-windows-x86-mingw48_opengl-5.2.1.exe
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-opensource-windows-x86-mingw48_opengl-5.2.1.exe.md5
|
||||
QT_SDK_ARCH := mingw48_32
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-windows-x86-mingw482_opengl-5.3.1.exe
|
||||
QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-windows-x86-mingw482_opengl-5.3.1.exe.md5
|
||||
QT_SDK_ARCH := mingw482_32
|
||||
NSIS_URL := http://wiki.openpilot.org/download/attachments/18612236/nsis-2.46-unicode.tar.bz2
|
||||
SDL_URL := http://wiki.openpilot.org/download/attachments/18612236/SDL-devel-1.2.15-mingw32.tar.gz
|
||||
OPENSSL_URL := http://wiki.openpilot.org/download/attachments/18612236/openssl-1.0.1e-win32.tar.bz2
|
||||
UNCRUSTIFY_URL := http://wiki.openpilot.org/download/attachments/18612236/uncrustify-0.60-windows.tar.bz2
|
||||
DOXYGEN_URL := http://wiki.openpilot.org/download/attachments/18612236/doxygen-1.8.3.1-windows.tar.bz2
|
||||
MESAWIN_URL := http://wiki.openpilot.org/download/attachments/18612236/mesawin.tar.gz
|
||||
endif
|
||||
|
||||
GTEST_URL := http://wiki.openpilot.org/download/attachments/18612236/gtest-1.6.0.zip
|
||||
|
||||
# Changing PYTHON_DIR, also update it in ground/openpilotgcs/src/python.pri
|
||||
ARM_SDK_DIR := $(TOOLS_DIR)/gcc-arm-none-eabi-4_8-2014q1
|
||||
QT_SDK_DIR := $(TOOLS_DIR)/qt-5.2.1
|
||||
QT_SDK_DIR := $(TOOLS_DIR)/qt-5.3.1
|
||||
MINGW_DIR := $(QT_SDK_DIR)/Tools/mingw48_32
|
||||
PYTHON_DIR := $(QT_SDK_DIR)/Tools/mingw48_32/opt/bin
|
||||
NSIS_DIR := $(TOOLS_DIR)/nsis-2.46-unicode
|
||||
@ -105,6 +112,15 @@ UNCRUSTIFY_DIR := $(TOOLS_DIR)/uncrustify-0.60
|
||||
DOXYGEN_DIR := $(TOOLS_DIR)/doxygen-1.8.3.1
|
||||
GTEST_DIR := $(TOOLS_DIR)/gtest-1.6.0
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
MINGW_DIR := $(QT_SDK_DIR)/Tools/$(QT_SDK_ARCH)
|
||||
PYTHON_DIR := $(QT_SDK_DIR)/Tools/$(QT_SDK_ARCH)/opt/bin
|
||||
NSIS_DIR := $(TOOLS_DIR)/nsis-2.46-unicode
|
||||
SDL_DIR := $(TOOLS_DIR)/SDL-1.2.15
|
||||
OPENSSL_DIR := $(TOOLS_DIR)/openssl-1.0.1e-win32
|
||||
MESAWIN_DIR := $(TOOLS_DIR)/mesawin
|
||||
endif
|
||||
|
||||
QT_SDK_PREFIX := $(QT_SDK_DIR)
|
||||
|
||||
##############################
|
||||
@ -115,7 +131,7 @@ QT_SDK_PREFIX := $(QT_SDK_DIR)
|
||||
|
||||
BUILD_SDK_TARGETS := arm_sdk qt_sdk
|
||||
ifeq ($(UNAME), Windows)
|
||||
BUILD_SDK_TARGETS += sdl nsis openssl
|
||||
BUILD_SDK_TARGETS += sdl nsis mesawin openssl
|
||||
endif
|
||||
ALL_SDK_TARGETS := $(BUILD_SDK_TARGETS) gtest uncrustify doxygen
|
||||
|
||||
@ -350,14 +366,14 @@ qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR)
|
||||
$(V1) $(DL_DIR)/$(5) --dump-binary-data -o $(1)
|
||||
# Extract packages under tool directory
|
||||
$(V1) $(MKDIR) -p $$(call toprel, $(dir $(2)))
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0qt-project-url.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/1.0.0ThirdPartySoftware_Listing.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0readme.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.win32_mingw48.essentials/5.2.1mingw48_essentials.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.win32_mingw48.essentials/5.2.1x32-4.8.0-release-posix-dwarf-rev2-runtime.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.win32_mingw48.essentials/5.2.1icu_51_1_mingw_builds_4_8_0_posix_dwarf_32.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.win32_mingw48.addons/5.2.1mingw48_addons.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.tools.win32_mingw48/4.8.0-1-1x32-4.8.0-release-posix-dwarf-rev2.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0qt-project-url.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.1ThirdPartySoftware_Listing.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0readme.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.1-0qt5_essentials.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.1-0i686-4.8.2-release-posix-dwarf-rt_v3-rev3-runtime.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.1-0icu_52_1_mingw_builds_32_4_8_2_posix_dwarf.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.1-0qt5_addons.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.tools.win32_mingw482/4.8.2i686-4.8.2-release-posix-dwarf-rt_v3-rev3.7z" | grep -v Extracting
|
||||
# Run patcher
|
||||
@$(ECHO)
|
||||
@$(ECHO) "Executing QtPatch in" $$(call toprel, $(QT_SDK_PREFIX))
|
||||
@ -406,7 +422,7 @@ define LINUX_QT_INSTALL_TEMPLATE
|
||||
|
||||
qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR)
|
||||
$(V1) if ! $(SEVENZIP) >/dev/null 2>&1; then \
|
||||
$(ECHO) $(MSG_NOTICE) "Please install the p7zip for your distribution. i.e.: sudo apt-get install p7zip." && \
|
||||
$(ECHO) $(MSG_NOTICE) "Please install the p7zip for your distribution. i.e.: sudo apt-get install p7zip-full" && \
|
||||
exit 1; \
|
||||
fi
|
||||
$(call DOWNLOAD_TEMPLATE,$(3),$(5),"$(4)")
|
||||
@ -417,15 +433,15 @@ qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR)
|
||||
$(V1) $(DL_DIR)/$(5) --dump-binary-data -o $(1)
|
||||
# Extract packages under tool directory
|
||||
$(V1) $(MKDIR) -p $$(call toprel, $(dir $(2)))
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0qt-project-url.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/1.0.0ThirdPartySoftware_Listing.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0readme.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.$(6).essentials/5.2.1$(6)_qt5_essentials.7z" | grep -v Extracting
|
||||
$(V1) if [ -f "$(1)/qt.521.$(6).essentials/5.2.1icu_51_1_ubuntu_11_10_64.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.$(6).essentials/5.2.1icu_51_1_ubuntu_11_10_64.7z" | grep -v Extracting; fi
|
||||
$(V1) if [ -f "$(1)/qt.521.$(6).essentials/5.2.1icu_51_1_ubuntu_11_10_32.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.$(6).essentials/5.2.1icu_51_1_ubuntu_11_10_32.7z" | grep -v Extracting; fi
|
||||
# $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.$(6).essentials/5.2.1icu_path_patcher.sh.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.$(6).addons/5.2.1$(6)_qt5_addons.7z" | grep -v Extracting
|
||||
# go to OpenPilot/tools/5.1.1/gcc_64 and call patcher.sh
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0qt-project-url.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.1ThirdPartySoftware_Listing.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0readme.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_essentials.7z" | grep -v Extracting
|
||||
$(V1) if [ -f "$(1)/qt.53.$(6)/5.3.1-0icu_51_1_ubuntu_11_10_64.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0icu_51_1_ubuntu_11_10_64.7z" | grep -v Extracting; fi
|
||||
$(V1) if [ -f "$(1)/qt.53.$(6)/5.3.1-0icu_51_1_ubuntu_11_10_32.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0icu_51_1_ubuntu_11_10_32.7z" | grep -v Extracting; fi
|
||||
# $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6).essentials/5.3.1icu_path_patcher.sh.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_addons.7z" | grep -v Extracting
|
||||
# go to OpenPilot/tools/5.3.1/gcc_64 and call patcher.sh
|
||||
@$(ECHO)
|
||||
@$(ECHO) "Running patcher in" $$(call toprel, $(QT_SDK_PREFIX))
|
||||
$(V1) $(CD) $(QT_SDK_PREFIX)
|
||||
@ -456,6 +472,79 @@ qt_sdk_distclean:
|
||||
|
||||
endef
|
||||
|
||||
|
||||
##############################
|
||||
#
|
||||
# Mac QT install template
|
||||
# $(1) = tool temp extract/build directory
|
||||
# $(2) = tool install directory
|
||||
# $(3) = tool distribution URL
|
||||
# $(4) = tool distribution .md5 URL
|
||||
# $(5) = tool distribution file
|
||||
# $(6) = QT architecture
|
||||
# $(7) = optional extra build recipes template
|
||||
# $(8) = optional extra clean recipes template
|
||||
#
|
||||
##############################
|
||||
|
||||
define MAC_QT_INSTALL_TEMPLATE
|
||||
|
||||
.PHONY: $(addprefix qt_sdk_, install clean distclean)
|
||||
|
||||
qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR)
|
||||
$(V1) if ! $(SEVENZIP) >/dev/null 2>&1; then \
|
||||
$(ECHO) $(MSG_NOTICE) "Please install the p7zip for your distribution. i.e.: sudo brew install p7zip." && \
|
||||
exit 1; \
|
||||
fi
|
||||
$(call DOWNLOAD_TEMPLATE,$(3),$(5),"$(4)")
|
||||
# Mount .dmg file
|
||||
$(V1) hdiutil attach -nobrowse $(DL_DIR)/$(5)
|
||||
# Explode .dmg file into install packages
|
||||
@$(ECHO) $(MSG_EXTRACTING) $$(call toprel, $(1))
|
||||
$(V1) $(MKDIR) -p $$(call toprel, $(dir $(1)))
|
||||
$(V1) $(QT_SDK_MAINTENANCE_TOOL) --dump-binary-data -i $(QT_SDK_INSTALLER_DAT) -o $(1)
|
||||
# Extract packages under tool directory
|
||||
$(V1) $(MKDIR) -p $$(call toprel, $(dir $(2)))
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0qt-project-url.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.1ThirdPartySoftware_Listing.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0readme.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_essentials.7z" | grep -v Extracting
|
||||
# $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6).essentials/5.3.1icu_path_patcher.sh.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_addons.7z" | grep -v Extracting
|
||||
# go to OpenPilot/tools/5.3.1/gcc_64 and call patcher.sh
|
||||
@$(ECHO)
|
||||
@$(ECHO) "Running patcher in" $$(call toprel, $(QT_SDK_PREFIX))
|
||||
$(V1) $(CD) $(QT_SDK_PREFIX)
|
||||
# $(V1) "$(QT_SDK_PREFIX)/patcher.sh" $(QT_SDK_PREFIX)
|
||||
# call qmake patcher
|
||||
@$(ECHO) "Executing QtPatch in" $$(call toprel, $(QT_SDK_PREFIX))
|
||||
$(V1) $(QT_SDK_MAINTENANCE_TOOL) --runoperation QtPatch mac $(QT_SDK_PREFIX) qt5
|
||||
|
||||
#Unmount the .dmg file
|
||||
$(V1) hdiutil detach $(QT_SDK_MOUNT_DIR)
|
||||
|
||||
# Execute post build templates
|
||||
$(7)
|
||||
|
||||
# Clean up temporary files
|
||||
@$(ECHO) $(MSG_CLEANING) $$(call toprel, $(1))
|
||||
$(V1) [ ! -d "$(1)" ] || $(RM) -rf "$(1)"
|
||||
|
||||
qt_sdk_clean:
|
||||
@$(ECHO) $(MSG_CLEANING) $$(call toprel, $(1))
|
||||
$(V1) [ ! -d "$(1)" ] || $(RM) -rf "$(1)"
|
||||
@$(ECHO) $(MSG_CLEANING) $$(call toprel, "$(2)")
|
||||
$(V1) [ ! -d "$(2)" ] || $(RM) -rf "$(2)"
|
||||
|
||||
$(8)
|
||||
|
||||
qt_sdk_distclean:
|
||||
@$(ECHO) $(MSG_DISTCLEANING) $$(call toprel, $(DL_DIR)/$(5))
|
||||
$(V1) [ ! -f "$(DL_DIR)/$(5)" ] || $(RM) "$(DL_DIR)/$(5)"
|
||||
$(V1) [ ! -f "$(DL_DIR)/$(5).md5" ] || $(RM) "$(DL_DIR)/$(5).md5"
|
||||
|
||||
endef
|
||||
|
||||
##############################
|
||||
#
|
||||
# ARM SDK
|
||||
@ -493,13 +582,11 @@ endef
|
||||
#
|
||||
# Qt SDK
|
||||
#
|
||||
# Mac OS X: user should install native Qt SDK package
|
||||
#
|
||||
##############################
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
QT_SDK_PREFIX := $(QT_SDK_DIR)/5.2.1/$(QT_SDK_ARCH)
|
||||
QT_SDK_PREFIX := $(QT_SDK_DIR)/5.3/$(QT_SDK_ARCH)
|
||||
|
||||
# This additional configuration step should not be necessary
|
||||
# but it is needed as a workaround to https://bugreports.qt-project.org/browse/QTBUG-33254
|
||||
@ -514,10 +601,16 @@ QT_BUILD_DIR := $(BUILD_DIR)/QT_BUILD
|
||||
|
||||
else ifeq ($(UNAME), Linux)
|
||||
|
||||
QT_SDK_PREFIX := "$(QT_SDK_DIR)/5.2.1/$(QT_SDK_ARCH)"
|
||||
QT_SDK_PREFIX := "$(QT_SDK_DIR)/5.3/$(QT_SDK_ARCH)"
|
||||
QT_BUILD_DIR := $(BUILD_DIR)/QT_BUILD
|
||||
$(eval $(call LINUX_QT_INSTALL_TEMPLATE,$(QT_BUILD_DIR),$(QT_SDK_DIR),$(QT_SDK_URL),$(QT_SDK_MD5_URL),$(notdir $(QT_SDK_URL)),$(QT_SDK_ARCH)))
|
||||
|
||||
else ifeq ($(UNAME), Darwin)
|
||||
|
||||
QT_SDK_PREFIX := "$(QT_SDK_DIR)/5.3/$(QT_SDK_ARCH)"
|
||||
QT_BUILD_DIR := $(BUILD_DIR)/QT_BUILD
|
||||
$(eval $(call MAC_QT_INSTALL_TEMPLATE,$(QT_BUILD_DIR),$(QT_SDK_DIR),$(QT_SDK_URL),$(QT_SDK_MD5_URL),$(notdir $(QT_SDK_URL)),$(QT_SDK_ARCH)))
|
||||
|
||||
else
|
||||
|
||||
QT_SDK_PREFIX := $(QT_SDK_DIR)
|
||||
@ -525,7 +618,7 @@ QT_SDK_PREFIX := $(QT_SDK_DIR)
|
||||
.PHONY: qt_sdk_install
|
||||
qt_sdk_install:
|
||||
@$(ECHO) $(MSG_NOTICE) --------------------------------------------------------
|
||||
@$(ECHO) $(MSG_NOTICE) Please install native Qt 5.2.x SDK using package manager
|
||||
@$(ECHO) $(MSG_NOTICE) Please install native Qt 5.3.x SDK using package manager
|
||||
@$(ECHO) $(MSG_NOTICE) --------------------------------------------------------
|
||||
|
||||
.PHONY: qt_sdk_clean
|
||||
@ -651,6 +744,29 @@ sdl_version:
|
||||
|
||||
endif
|
||||
|
||||
##################################
|
||||
#
|
||||
# Mesa OpenGL DLL (Windows only)
|
||||
#
|
||||
##################################
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,mesawin,$(MESAWIN_DIR),$(MESAWIN_URL),,$(notdir $(MESAWIN_URL))))
|
||||
|
||||
ifeq ($(shell [ -d "$(MESAWIN_DIR)" ] && $(ECHO) "exists"), exists)
|
||||
export MESAWIN_DIR := $(MESAWIN_DIR)
|
||||
else
|
||||
# not installed, hope it's in the path...
|
||||
#$(info $(EMPTY) WARNING $(call toprel, $(MESA_WIN_DIR)) not found (make mesawin_install), using system PATH)
|
||||
endif
|
||||
|
||||
.PHONY: mesawin_version
|
||||
mesawin_version:
|
||||
-$(V1) $(ECHO) "MesaOpenGL vXX"
|
||||
|
||||
endif
|
||||
|
||||
##############################
|
||||
#
|
||||
# OpenSSL (Windows only)
|
||||
|
@ -253,6 +253,12 @@ Section "CDC driver" InSecInstallDrivers
|
||||
ExecWait '"$PLUGINSDIR\dpinst.exe" /lm /path "$INSTDIR\drivers"'
|
||||
SectionEnd
|
||||
|
||||
; Copy Opengl32.dll if needed (disabled by default)
|
||||
Section /o "Mesa OpenGL driver" InSecInstallOpenGL
|
||||
SetOutPath "$INSTDIR\bin"
|
||||
File /r "${GCS_BUILD_TREE}\bin\opengl32_32\opengl32.dll"
|
||||
SectionEnd
|
||||
|
||||
; AeroSimRC plugin files
|
||||
Section "AeroSimRC plugin" InSecAeroSimRC
|
||||
SetOutPath "$INSTDIR\misc\AeroSIM-RC"
|
||||
@ -319,6 +325,7 @@ SectionEnd
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecUtilities} $(DESC_InSecUtilities)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecDrivers} $(DESC_InSecDrivers)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecInstallDrivers} $(DESC_InSecInstallDrivers)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecInstallOpenGL} $(DESC_InSecInstallOpenGL)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecAeroSimRC} $(DESC_InSecAeroSimRC)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecShortcuts} $(DESC_InSecShortcuts)
|
||||
!insertmacro MUI_FUNCTION_DESCRIPTION_END
|
||||
|
@ -34,6 +34,7 @@
|
||||
LangString DESC_InSecUtilities ${LANG_GERMAN} "OpenPilot Dienstprogramme (Matlab Log Parser)."
|
||||
LangString DESC_InSecDrivers ${LANG_GERMAN} "OpenPilot Hardware Treiberdateien (optionaler OpenPilot CDC Treiber)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_GERMAN} "OpenPilot CDC Treiber (optional)."
|
||||
LangString DESC_InSecInstallOpenGL ${LANG_GERMAN} "Optional OpenGL32.dll for old video cards."
|
||||
LangString DESC_InSecAeroSimRC ${LANG_GERMAN} "AeroSimRC plugin files with sample configuration."
|
||||
LangString DESC_InSecShortcuts ${LANG_GERMAN} "Installiere Verknüpfungen unter Startmenü->Anwendungen."
|
||||
|
||||
|
@ -34,6 +34,7 @@
|
||||
LangString DESC_InSecUtilities ${LANG_ENGLISH} "OpenPilot utilities (Matlab log parser)."
|
||||
LangString DESC_InSecDrivers ${LANG_ENGLISH} "OpenPilot hardware driver files (optional OpenPilot CDC driver)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_ENGLISH} "Optional OpenPilot CDC driver (virtual USB COM port)."
|
||||
LangString DESC_InSecInstallOpenGL ${LANG_ENGLISH} "Optional OpenGL32.dll for old video cards."
|
||||
LangString DESC_InSecAeroSimRC ${LANG_ENGLISH} "AeroSimRC plugin files with sample configuration."
|
||||
LangString DESC_InSecShortcuts ${LANG_ENGLISH} "Install application start menu shortcuts."
|
||||
|
||||
|
@ -34,6 +34,7 @@
|
||||
LangString DESC_InSecUtilities ${LANG_SPANISH} "OpenPilot utilities (Matlab log parser)."
|
||||
LangString DESC_InSecDrivers ${LANG_SPANISH} "OpenPilot hardware driver files (optional OpenPilot CDC driver)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_SPANISH} "Optional OpenPilot CDC driver (virtual USB COM port)."
|
||||
LangString DESC_InSecInstallOpenGL ${LANG_SPANISH} "Optional OpenGL32.dll for old video cards."
|
||||
LangString DESC_InSecAeroSimRC ${LANG_SPANISH} "AeroSimRC plugin files with sample configuration."
|
||||
LangString DESC_InSecShortcuts ${LANG_SPANISH} "Instalar accesos directos de la aplicación (menú inicio y escritorio)."
|
||||
|
||||
|
@ -34,6 +34,7 @@
|
||||
LangString DESC_InSecUtilities ${LANG_FRENCH} "OpenPilot utilities (Matlab log parser)."
|
||||
LangString DESC_InSecDrivers ${LANG_FRENCH} "OpenPilot hardware driver files (optional OpenPilot CDC driver)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_FRENCH} "Optional OpenPilot CDC driver (virtual USB COM port)."
|
||||
LangString DESC_InSecInstallOpenGL ${LANG_FRENCH} "Optional OpenGL32.dll for old video cards."
|
||||
LangString DESC_InSecAeroSimRC ${LANG_FRENCH} "AeroSimRC plugin files with sample configuration."
|
||||
LangString DESC_InSecShortcuts ${LANG_FRENCH} "Installer les raccourcis dans le menu démarrer."
|
||||
|
||||
|
@ -34,6 +34,7 @@
|
||||
LangString DESC_InSecUtilities ${LANG_RUSSIAN} "Утилиты (конвертор логов для Matlab)."
|
||||
LangString DESC_InSecDrivers ${LANG_RUSSIAN} "Файлы драйверов (опциональный драйвер CDC порта)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_RUSSIAN} "Опциональный OpenPilot CDC драйвер (виртуальный USB COM порт)."
|
||||
LangString DESC_InSecInstallOpenGL ${LANG_RUSSIAN} "Optional OpenGL32.dll for old video cards."
|
||||
LangString DESC_InSecAeroSimRC ${LANG_RUSSIAN} "Файлы плагина для симулятора AeroSimRC с примером конфигурации."
|
||||
LangString DESC_InSecShortcuts ${LANG_RUSSIAN} "Установка ярлыков для приложения."
|
||||
|
||||
|
@ -34,6 +34,7 @@
|
||||
LangString DESC_InSecUtilities ${LANG_TRADCHINESE} "OpenPilot utilities (Matlab log parser)."
|
||||
LangString DESC_InSecDrivers ${LANG_TRADCHINESE} "OpenPilot hardware driver files (optional OpenPilot CDC driver)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_TRADCHINESE} "Optional OpenPilot CDC driver (virtual USB COM port)."
|
||||
LangString DESC_InSecInstallOpenGL ${LANG_TRADCHINESE} "Optional OpenGL32.dll for old video cards."
|
||||
LangString DESC_InSecAeroSimRC ${LANG_TRADCHINESE} "AeroSimRC plugin files with sample configuration."
|
||||
LangString DESC_InSecShortcuts ${LANG_TRADCHINESE} "安装开始菜单的快捷方式."
|
||||
|
||||
|