mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-03-15 07:29:15 +01:00
Merge remote-tracking branch 'origin/next' into brian/oplink_ppm_out
This commit is contained in:
commit
e50e645e7b
86
CREDITS.txt
86
CREDITS.txt
@ -6,47 +6,41 @@ It is sorted alphabetically by name and formatted so that it allows for easy gre
|
||||
The fields are:
|
||||
|
||||
Name (N)
|
||||
Email (E),
|
||||
Description of work (D)
|
||||
Current maintainer function (M)
|
||||
|
||||
----------
|
||||
|
||||
N: Connor Abbott
|
||||
E: connor (at) abbott (dot) cx
|
||||
D: Win32 OpenPilot port
|
||||
|
||||
N: David Ankers
|
||||
E: david (at) openpilot (dot) org
|
||||
D: Co-founder, Project Coordination
|
||||
D: Minor GCS infrastructure, updating the credit file
|
||||
M: Admin
|
||||
|
||||
N: Sergiy Anikeyev
|
||||
D: Improvments to Camera Gimbal control
|
||||
|
||||
N: Pedro Assuncao
|
||||
E: pedro (dot) agda (plus) openpilot (at) gmail (dot) com
|
||||
D: Initial GCS Settings Gadget work
|
||||
|
||||
N: Fredrik Arvidsson
|
||||
E: fredrik (at) arvidssons (dot) org
|
||||
W: GCS Setup Wizard
|
||||
D: GCS Setup Wizard
|
||||
M: GCS Setup Wizard
|
||||
|
||||
N: Werner Backes
|
||||
E: werner (at) bit-1 (dot) de
|
||||
D: Port of CopterControl to PS3 Move Controller (MoveCopter)
|
||||
|
||||
N: Jose Barros
|
||||
E: josembarros (at) hotmail (dot) com
|
||||
D: Next-Gen OP Map Lib, Y-Modem Library, Uploader Plugin
|
||||
D: OP Bootloader, AHRS Bootloader, OPUploadTool and much else
|
||||
M: Bootloader, OP MAP Lib
|
||||
|
||||
N: David "Buzz" Carlson
|
||||
E: chebuzz (plus) openpilot (at) gmail (dot) com
|
||||
D: 3D ModelView GCS Plugin, sponsor of HITL merge work and XPlane addition
|
||||
|
||||
N: James Cotton
|
||||
E: peabody124 (plus) openpilot (at) gmail (dot) com
|
||||
D: Multiplatform HID implementation (firmware & GCS), GCS Joystick control
|
||||
D: Posix OpenPilot work and Mac implementation
|
||||
D: Firmware implementation of Professor Schinstock's INS/GPS
|
||||
@ -54,187 +48,159 @@ D: Android GCS and much else
|
||||
M: Architecture co-lead, Android GCS Lead
|
||||
|
||||
N: Steve Doll
|
||||
E: speakfree07 (at) hotmail (dot) com
|
||||
D: Much Artwork, Logo rework, Welcome page design
|
||||
|
||||
N: Piotr Esden-Tempski
|
||||
E: esden (at) esden (dot) net
|
||||
D: Floss-JTAG Rev A, 4-layer initial design
|
||||
|
||||
N: Richard Flay
|
||||
D: Multiple fixes / Review guru
|
||||
|
||||
N: Darren Furniss
|
||||
E: furnibird (plus) openpilot (at) gmail (dot) com
|
||||
W: GCS Artwork and Android GCS Artwork
|
||||
D: GCS Artwork and Android GCS Artwork
|
||||
|
||||
N: Frederic Goddeeris
|
||||
E: fredericgoddeeris (at) hotmail (dot) com
|
||||
D: I2C work and FreeRTOS work, MK integration
|
||||
D: EagleTree OSD implementation
|
||||
|
||||
N: Daniel Godin
|
||||
E: dgodin (at) dnsct (dot) com
|
||||
W: Sponsor: Notify Plugin for the GCS
|
||||
D: Sponsor: Notify Plugin for the GCS
|
||||
|
||||
N: Bani Greyling
|
||||
E: bani (dot) greyling (plus) openpilot (at) gmail (dot) com
|
||||
D: GCS Scope plugin
|
||||
|
||||
N: Nuno Guedes
|
||||
E: muralha (plus) openpilot (at) gmail (dot) com
|
||||
D: 3D artwork, moving surfaces and work on ModelView
|
||||
D: PFD Artwork
|
||||
|
||||
N: Erik Gustavsson
|
||||
D: Attitude LPF improvments to Self Level
|
||||
|
||||
N: Peter Gunnarsson
|
||||
E: peter (at) pyne (dot) se
|
||||
D: GCS Core Developer
|
||||
D: Multiple GCS plugins, Gadget foundations, UAVObject viewer
|
||||
|
||||
N: Dean Hall
|
||||
E: dwhall256 (plus) openpilot (at) gmail (dot) com
|
||||
D: Creator of http://pythononachip.org
|
||||
|
||||
N: Joe Hlebasko
|
||||
E: joe (dot) hlebasko(plus) openpilot (at) gmail (dot) com
|
||||
D: Early versions of Main Board & Production OP GPS
|
||||
M: Hardware Architecture Team
|
||||
|
||||
N: Andy Honecker
|
||||
E: andywh (at) yahoo (dot) com
|
||||
D: Hardware design review and optimisation
|
||||
|
||||
N: Mark James
|
||||
E: mjames (plus) openpilot (at) gmail (dot) com
|
||||
D: Some of Silk Icon set used in GCS - http://www.famfamfam.com/lab/icons/silk
|
||||
|
||||
N: Sami Korhonen
|
||||
E: samik (dot) korhonen (plus) openpilot (at) gmail (dot) com
|
||||
D: GPS Module, Spektrum RC Module, OSD work
|
||||
M: OpenPilot OSD
|
||||
|
||||
N: Thorsten Klose
|
||||
E: thorsten (dot) klose (at) dmx (dot) de
|
||||
D: Embedded STM32 infrastructure
|
||||
|
||||
N: Hallvard Kristiansen
|
||||
E: hal (at) fleshmx (dot) com
|
||||
D: GCS Artwork, Quad layout diagrams
|
||||
|
||||
N: Mike Labranche
|
||||
E: mdlabranche (plus) openpilot (at) gmail (dot) com
|
||||
D: Tab bar Telem Monitor
|
||||
|
||||
N: Edouard Lafargue
|
||||
E: edouard (at) lafargue (dot) name
|
||||
D: GCS Dial Plugins, GCS PFD Plugin, GCS GPS plugin, GCS Config plugin
|
||||
D: Artwork including standard display dials
|
||||
|
||||
N: Matt Lipski
|
||||
E: mattlipski (plus) openpilot (at) gmail (dot) com
|
||||
D: Deluxe Dials Set artwork, (Artificial Horizon, Compass, Turn Indicator)
|
||||
|
||||
N: Les Newell
|
||||
E: les (dot) newell (at) fastmail (dot) co (dot) uk
|
||||
D: Advanced mixer matrix, SPI protocol based on UAVObjects, feedforward
|
||||
|
||||
N: Ken Northup
|
||||
E: helos360 (at) bellsouth (dot) net
|
||||
D: 3D Modelling, Easystar adaption from FMS
|
||||
|
||||
N: Guy McCaldin
|
||||
E: guymcc (at) gmail (dot) com
|
||||
D: Artwork and design including work on the Deluxe Dial Set
|
||||
|
||||
N: Alessio Morale
|
||||
D: Firmware/Architecture Lead
|
||||
|
||||
N: Cathy Moss
|
||||
E: cmoss296 (at) blueyonder (dot) co (dot) uk
|
||||
D: Hardware design Lead: Gen 2 Mainboard, PipXtreme, Current Sensor
|
||||
D: PipXtreme designer, creator OP Map Plugin
|
||||
|
||||
N: Angus Peart
|
||||
E: gussy (at) openpilot (dot) org
|
||||
D: Co-founder, Principal hardware architect.
|
||||
D: Hardware design of early OpenPilot, AHRS, GPS and other hardware
|
||||
|
||||
N: Dmytro Poplavskiy
|
||||
E: dmytro (dot) poplavskiy (plus) openpilot (at) gmail (dot) com
|
||||
W: QML PFD, QML Welcome page
|
||||
D: QML PFD, QML Welcome page
|
||||
M: Qml plugins
|
||||
|
||||
N: Eric Price
|
||||
E: corvus (dot) corax (at) cybertrench (dot) com
|
||||
D: IL2 HITL GCS Plugin, Posix OpenPilot, Advanced stabilisation module
|
||||
M: SITL Posix, SLAM work
|
||||
|
||||
N: Richard Querin
|
||||
E: rfquerin (plus) openpilot (at) gmail (dot) com
|
||||
D: Graphic Design, OpenPilot Logo
|
||||
|
||||
N: Laurent Ribon
|
||||
E: ribon (dot) l (at) club-internet (dot) fr
|
||||
D: The GLC_lib as used in the ModelView Plugin
|
||||
D: See: http://www.glc-lib.net/
|
||||
|
||||
N: Julien Rouviere
|
||||
E: julien (dot) rouviere (plus) openpilot (at) gmail (dot) com
|
||||
D: GCS Framework and Plugins for the GCS
|
||||
|
||||
N: Zik Saleeba
|
||||
E: zik (at) zikzak (dot) net
|
||||
D: Initial schematic based on Zik's Flying Fox schematic
|
||||
|
||||
N: Professor Dale Schinstock
|
||||
E: dales (at) ksu (dot) edu
|
||||
D: Lead AHRS Developer
|
||||
D: Lead INS Developer
|
||||
D: Creator of the OpenPilot INS / EKF
|
||||
|
||||
N: Professor Kenn Sebesta
|
||||
E: kenn (at) openpilot (dot) org
|
||||
D: Lead Fixed Wing Developer
|
||||
M: Fixed Wing support
|
||||
D: Lead Fixed Wing Developer CC3D / Controls
|
||||
D: GCS improvments including HiTL Merge
|
||||
M: Fixed Wing support CC3D
|
||||
|
||||
N: Oleg Semyonov
|
||||
E: os-openpilot-org (at) os-propo (dot) info
|
||||
D: Core tester & Project organisation
|
||||
D: Core Developer & Project organisation
|
||||
D: TxPID module
|
||||
M: CameraStab module
|
||||
M: Common part of multi-platform packaging system
|
||||
M: Windows NSIS Installer
|
||||
M: Russian Documentation Lead
|
||||
|
||||
N: Stacey Sheldon
|
||||
E: stac (at) solidgoldbomb (dot) org
|
||||
D: Core Embedded Developer
|
||||
D: SPI protocol for AHRS, I2C rewrite and much core work
|
||||
|
||||
N: Troy Schultz
|
||||
E: troy (dot) schultz (at) rogers (dot) com
|
||||
D: INS design review and optimisation
|
||||
|
||||
N: Dr. Erhard Siegl
|
||||
E: Erhard (dot) Siegl (at) zogazoga (dot) at
|
||||
D: Configuration engine for the GCS
|
||||
|
||||
N: Pete Stapley
|
||||
E: pete (at) stapleylabs (dot) com
|
||||
D: PPM inputs
|
||||
|
||||
N: Rowan Taubitz
|
||||
E: rowan (at) zantek (dot) com (dot) au
|
||||
D: Hardware debugging and testing, creation of 2-layer Floss-JTAG Rev B
|
||||
D: Creation of Next-Gen FOSS-JTAG board
|
||||
|
||||
N: Andrew Thoms
|
||||
E: electronics (at) andrewspizza (dot) net
|
||||
D: IP Telemtry plugin for the GCS
|
||||
D: Helicopter support code and mixing for CCPM
|
||||
|
||||
N: Vassilis Varveropoulos
|
||||
E: vassilis (at) openpilot (dot) org
|
||||
D: Co-founder, Principal embedded software architect.
|
||||
D: Module architecture and UAVTalk/UAVObjects implementation.
|
||||
|
||||
N: Alex Vrubel
|
||||
E: alex (dot) vrubel (plus) openpilot (at) gmail (dot) com
|
||||
D: Russian translation of the GCS
|
||||
|
||||
N: Brian Webb
|
||||
E: webbbn (plus) openpilot (at) gmail (dot) com
|
||||
W: Modem lead developer
|
||||
D: Modem lead developer
|
||||
M: OP Modems
|
||||
|
||||
N: Dmitriy Zaitsev
|
||||
D: AeroSim-RC HiTL plugin
|
||||
|
31
HISTORY.txt
31
HISTORY.txt
@ -1,5 +1,34 @@
|
||||
Short summary of changes. For a complete list see the git log.
|
||||
|
||||
2012-11-17
|
||||
Advanced camera stabilization features.
|
||||
They include optional manual control input filtering (moved from camera
|
||||
stabilization to manual control input and now available also for main controls),
|
||||
optional airframe attitude filtering used by camera stabilization, and optional
|
||||
camera actuator feed forward to improve gimbal response.
|
||||
|
||||
--- RELEASE-12.10.2 --- Mayan Apocalypse Release ---
|
||||
|
||||
List of issues resolved in this maintenance release:
|
||||
http://progress.openpilot.org/issues/?filter=10361
|
||||
|
||||
OP-459, OP-545, OP-674, OP-679, OP-685, OP-686, OP-687, OP-690, OP-691,
|
||||
OP-702, OP-703, OP-714, OP-715, OP-716, OP-721, OP-728, OP-746, OP-748,
|
||||
OP-749, OP-750, OP-758, OP-759, OP-760
|
||||
|
||||
2012-11-12
|
||||
Implemented smoothing filter for accelerometer data.
|
||||
Added support for Mode 3 and Mode 4 to the TX Configuration Wizard.
|
||||
|
||||
--- RELEASE-12.10.1 ---
|
||||
|
||||
2012-10-26
|
||||
Temporary disabled AutoTune GCS GUI. It was listed as an experimental
|
||||
feature in the previous release, there were however a few cases where
|
||||
it did not behave as expected.
|
||||
|
||||
--- RELEASE-12.10 ---
|
||||
|
||||
2012-10-06
|
||||
Receiver port can now be configured as PPM *and* PWM inputs.
|
||||
Pin 1 is PPM, other pins are PWM inputs.
|
||||
@ -14,7 +43,7 @@ Several UI changes.
|
||||
MixerCurveWidget refactoring, now as a simple and advanced view.
|
||||
|
||||
2012-07-27
|
||||
Added “advanced mode” option to general settings. Right now it only shows the hidden apply buttons.
|
||||
Added "advanced mode" option to general settings. Right now it only shows the hidden apply buttons.
|
||||
To enable go to tools->options->General and click one of the checkboxes to give focus to the form,
|
||||
then press F7
|
||||
|
||||
|
@ -1,10 +1,22 @@
|
||||
+ Halt/Reset buttons don't work if board is armed. But no way to use them if "Always armed". Use rescue as workaround.
|
||||
+ Missing Translations, use English.
|
||||
+ Radio Wizard confused by a reversed throttle, fix it on your transmitter before starting wizard.
|
||||
+ [Windows 8] USB Driver is broken.
|
||||
+ Firmware Update Instructions on Firmware Tab not entirely accurate for all upgrade paths.
|
||||
+ Radio Wizard Throttle display does not show full range properly.
|
||||
+ Tricopter's using Vehicle Wizard need to check servo does not need reversed manually.
|
||||
+ XAircraft ESCs uses non-standard PPM range which may cause issues with Vehicle Wizard.
|
||||
+ Spectrum Satellite Receivers setup in Radio Wizard may have wrong protocol set.
|
||||
+ Old Intel 965 have an OpenGL bug that turns the QML PFD black and while.
|
||||
Here is a list of some known unresolved issues. If an issue has JIRA ID [OP-XXX], you may track it using the
|
||||
following URL: http://bugs.openpilot.org/browse/OP-XXX
|
||||
|
||||
+ Missing Translations, use English.
|
||||
+ Radio Wizard confused by a reversed throttle, fix it on your transmitter before starting wizard.
|
||||
+ Radio Wizard Throttle display does not show full range properly.
|
||||
+ [Windows 8] USB Driver is broken.
|
||||
+ Firmware Update Instructions on Firmware Tab not entirely accurate for all upgrade paths.
|
||||
+ Tricopter's using Vehicle Wizard need to check servo does not need reversed manually.
|
||||
+ XAircraft ESCs uses non-standard PPM range which may cause issues with Vehicle Wizard.
|
||||
+ Spectrum Satellite Receivers setup in Radio Wizard may have wrong protocol set.
|
||||
+ Old Intel 965 have an OpenGL bug that turns the QML PFD black and while.
|
||||
+ [OP-732] Import UAV Settings for inactive modules crashes the running firmware (board restarts).
|
||||
Workaround: update firmware, power cycle, enable modules, power cycle, import configuration.
|
||||
+ [OP-747] Board infinitely reboots itself after firmware upgrade (settings erase firmware is a workaround).
|
||||
+ [OP-723] GCS uses the system language ot the 1st run. After restart it uses English (can be changed later).
|
||||
+ [OP-725] GCS camera stab config error message disappears too fast (but config error is cleared as it should)
|
||||
+ [OP-767] GCS does not send AttitudeActual packets over serial port when GPS is connected and system is armed
|
||||
+ [OP-768] GCS does not show UAV position on the map (master or next CC branches, but works in Revo branches)
|
||||
+ [OP-682] GCS crashes on firmware page. Noted on Windows and OSX platforms, difficult to reproduce.
|
||||
Workaround: use Vehicle setup wizard to update the firmware.
|
||||
+ [OP-769] Can't enter "12,45" on German system. Workaround: change GCS language (in fact, locale) to German.
|
||||
|
@ -240,8 +240,8 @@ C:
|
||||
D:
|
||||
V:
|
||||
|
||||
M: First Auto landing on a fixed Wing using Revo
|
||||
C:
|
||||
M: First Auto spot landing on a fixed Wing using Revo
|
||||
C:
|
||||
D:
|
||||
V:
|
||||
|
||||
|
20
Makefile
20
Makefile
@ -445,7 +445,7 @@ dfuutil_clean:
|
||||
# see http://developer.android.com/sdk/ for latest versions
|
||||
ANDROID_SDK_DIR := $(TOOLS_DIR)/android-sdk-linux
|
||||
.PHONY: android_sdk_install
|
||||
android_sdk_install: ANDROID_SDK_URL := http://dl.google.com/android/android-sdk_r20.0.3-linux.tgz
|
||||
android_sdk_install: ANDROID_SDK_URL := http://dl.google.com/android/android-sdk_r21.0.1-linux.tgz
|
||||
android_sdk_install: ANDROID_SDK_FILE := $(notdir $(ANDROID_SDK_URL))
|
||||
# order-only prereq on directory existance:
|
||||
android_sdk_install: | $(DL_DIR) $(TOOLS_DIR)
|
||||
@ -466,7 +466,7 @@ android_sdk_clean:
|
||||
.PHONY: android_sdk_update
|
||||
android_sdk_update:
|
||||
$(V0) @echo " UPDATE $(ANDROID_SDK_DIR)"
|
||||
$(ANDROID_SDK_DIR)/tools/android update sdk --no-ui -t platform-tools,android-16,addon-google_apis-google-16
|
||||
$(ANDROID_SDK_DIR)/tools/android update sdk --no-ui -t platform-tools,android-14,addon-google_apis-google-14
|
||||
|
||||
##############################
|
||||
#
|
||||
@ -579,6 +579,7 @@ uavobjects_clean:
|
||||
#
|
||||
################################
|
||||
|
||||
ANDROIDGCS_BUILD_CONF ?= debug
|
||||
|
||||
# Build the output directory for the Android GCS build
|
||||
ANDROIDGCS_OUT_DIR := $(BUILD_DIR)/androidgcs
|
||||
@ -601,12 +602,12 @@ endif
|
||||
androidgcs: uavo-collections_java
|
||||
$(V0) @echo " ANDROID $(call toprel, $(ANDROIDGCS_OUT_DIR))"
|
||||
$(V1) mkdir -p $(ANDROIDGCS_OUT_DIR)
|
||||
$(V1) $(ANDROID) $(ANDROID_SILENT) update project --target 'Google Inc.:Google APIs:16' --name androidgcs --path ./androidgcs
|
||||
$(V1) $(ANDROID) $(ANDROID_SILENT) update project --target 'Google Inc.:Google APIs:14' --name androidgcs --path ./androidgcs
|
||||
$(V1) ant -f ./androidgcs/build.xml \
|
||||
$(ANT_QUIET) \
|
||||
-Dout.dir="../$(call toprel, $(ANDROIDGCS_OUT_DIR)/bin)" \
|
||||
-Dgen.absolute.dir="$(ANDROIDGCS_OUT_DIR)/gen" \
|
||||
debug
|
||||
$(ANDROIDGCS_BUILD_CONF)
|
||||
|
||||
.PHONY: androidgcs_clean
|
||||
androidgcs_clean:
|
||||
@ -618,7 +619,7 @@ androidgcs_clean:
|
||||
#
|
||||
# Find the git hashes of each commit that changes uavobjects with:
|
||||
# git log --format=%h -- shared/uavobjectdefinition/ | head -n 2
|
||||
UAVO_GIT_VERSIONS := 684620d 43f85d9
|
||||
UAVO_GIT_VERSIONS := 5e14f53
|
||||
|
||||
# All versions includes a pseudo collection called "working" which represents
|
||||
# the UAVOs in the source tree
|
||||
@ -980,3 +981,12 @@ package:
|
||||
.PHONY: package_resources
|
||||
package_resources:
|
||||
$(V1) cd package && $(MAKE) --no-print-directory opfw_resource
|
||||
|
||||
.PHONY: build-info
|
||||
build-info:
|
||||
$(V1) mkdir -p $(BUILD_DIR)
|
||||
$(V1) python $(ROOT_DIR)/make/scripts/version-info.py \
|
||||
--path=$(ROOT_DIR) \
|
||||
--uavodir=$(ROOT_DIR)/shared/uavobjectdefinition \
|
||||
--template="make/templates/$@.txt" \
|
||||
--outfile="$(BUILD_DIR)/$@.txt"
|
||||
|
@ -1,46 +1,26 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file waypointeditorplugin.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup Waypoint Editor GCS Plugins
|
||||
* @{
|
||||
* @addtogroup WaypointEditorGadgetPlugin Waypoint Editor Gadget Plugin
|
||||
* @{
|
||||
* @brief A gadget to edit a list of waypoints
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 WaypointEditorPLUGIN_H_
|
||||
#define WaypointEditorPLUGIN_H_
|
||||
|
||||
#include <extensionsystem/iplugin.h>
|
||||
|
||||
class WaypointEditorGadgetFactory;
|
||||
|
||||
class WaypointEditorPlugin : public ExtensionSystem::IPlugin
|
||||
{
|
||||
public:
|
||||
WaypointEditorPlugin();
|
||||
~WaypointEditorPlugin();
|
||||
|
||||
void extensionsInitialized();
|
||||
bool initialize(const QStringList & arguments, QString * errorString);
|
||||
void shutdown();
|
||||
private:
|
||||
WaypointEditorGadgetFactory *mf;
|
||||
};
|
||||
#endif /* WaypointEditorPLUGIN_H_ */
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file %FILENAME%
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup [Group]
|
||||
* @{
|
||||
* @addtogroup %CLASS%
|
||||
* @{
|
||||
* @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
|
||||
*/
|
@ -77,6 +77,11 @@ USE_ALTITUDE ?= NO
|
||||
USE_AUTOTUNE ?= YES
|
||||
TEST_FAULTS ?= NO
|
||||
|
||||
# Camera gimbal options
|
||||
USE_INPUT_LPF ?= YES
|
||||
USE_GIMBAL_LPF ?= YES
|
||||
USE_GIMBAL_FF ?= YES
|
||||
|
||||
# List of optional modules to include
|
||||
OPTMODULES =
|
||||
ifeq ($(USE_CAMERASTAB), YES)
|
||||
@ -460,6 +465,18 @@ ifeq ($(USE_I2C), YES)
|
||||
CDEFS += -DUSE_I2C
|
||||
endif
|
||||
|
||||
ifeq ($(USE_INPUT_LPF), YES)
|
||||
CDEFS += -DUSE_INPUT_LPF
|
||||
endif
|
||||
|
||||
ifeq ($(USE_GIMBAL_LPF), YES)
|
||||
CDEFS += -DUSE_GIMBAL_LPF
|
||||
endif
|
||||
|
||||
ifeq ($(USE_GIMBAL_FF), YES)
|
||||
CDEFS += -DUSE_GIMBAL_FF
|
||||
endif
|
||||
|
||||
# Declare all non-optional modules as built-in to force inclusion
|
||||
CDEFS += ${foreach MOD, ${MODULES}, -DMODULE_$(MOD)_BUILTIN }
|
||||
|
||||
|
@ -57,6 +57,8 @@
|
||||
#define FAILSAFE_TIMEOUT_MS 100
|
||||
#define MAX_MIX_ACTUATORS ACTUATORCOMMAND_CHANNEL_NUMELEM
|
||||
|
||||
#define CAMERA_BOOT_DELAY_MS 7000
|
||||
|
||||
// Private types
|
||||
|
||||
|
||||
@ -205,7 +207,7 @@ static void actuatorTask(void* parameters)
|
||||
// Check how long since last update
|
||||
thisSysTime = xTaskGetTickCount();
|
||||
if(thisSysTime > lastSysTime) // reuse dt in case of wraparound
|
||||
dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f;
|
||||
dT = (thisSysTime - lastSysTime) * (portTICK_RATE_MS * 0.001f);
|
||||
lastSysTime = thisSysTime;
|
||||
|
||||
FlightStatusGet(&flightStatus);
|
||||
@ -277,10 +279,15 @@ static void actuatorTask(void* parameters)
|
||||
|
||||
for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++)
|
||||
{
|
||||
// During boot all camera actuators should be completely disabled (PWM pulse = 0).
|
||||
// command.Channel[i] is reused below as a channel PWM activity flag:
|
||||
// 0 - PWM disabled, >0 - PWM set to real mixer value using scaleChannel() later.
|
||||
// Setting it to 1 by default means "Rescale this channel and enable PWM on its output".
|
||||
command.Channel[ct] = 1;
|
||||
|
||||
if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_DISABLED) {
|
||||
// Set to minimum if disabled. This is not the same as saying PWM pulse = 0 us
|
||||
status[ct] = -1;
|
||||
command.Channel[ct] = 0;
|
||||
continue;
|
||||
}
|
||||
|
||||
@ -289,8 +296,6 @@ static void actuatorTask(void* parameters)
|
||||
else
|
||||
status[ct] = -1;
|
||||
|
||||
|
||||
|
||||
// Motors have additional protection for when to be on
|
||||
if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) {
|
||||
|
||||
@ -322,6 +327,7 @@ static void actuatorTask(void* parameters)
|
||||
else
|
||||
status[ct] = -1;
|
||||
}
|
||||
|
||||
if( (mixers[ct].type >= MIXERSETTINGS_MIXER1TYPE_CAMERAROLL) &&
|
||||
(mixers[ct].type <= MIXERSETTINGS_MIXER1TYPE_CAMERAYAW))
|
||||
{
|
||||
@ -343,19 +349,26 @@ static void actuatorTask(void* parameters)
|
||||
}
|
||||
else
|
||||
status[ct] = -1;
|
||||
|
||||
// Disable camera actuators for CAMERA_BOOT_DELAY_MS after boot
|
||||
if (thisSysTime < (CAMERA_BOOT_DELAY_MS / portTICK_RATE_MS))
|
||||
command.Channel[ct] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
for(int i = 0; i < MAX_MIX_ACTUATORS; i++)
|
||||
command.Channel[i] = scaleChannel(status[i],
|
||||
|
||||
// Set real actuator output values scaling them from mixers. All channels
|
||||
// will be set except explicitly disabled (which will have PWM pulse = 0).
|
||||
for (int i = 0; i < MAX_MIX_ACTUATORS; i++)
|
||||
if (command.Channel[i])
|
||||
command.Channel[i] = scaleChannel(status[i],
|
||||
actuatorSettings.ChannelMax[i],
|
||||
actuatorSettings.ChannelMin[i],
|
||||
actuatorSettings.ChannelNeutral[i]);
|
||||
|
||||
|
||||
// Store update time
|
||||
command.UpdateTime = 1000.0f*dT;
|
||||
if(1000.0f*dT > command.MaxUpdateTime)
|
||||
command.MaxUpdateTime = 1000.0f*dT;
|
||||
command.UpdateTime = dT * 1000.0f;
|
||||
if (command.UpdateTime > command.MaxUpdateTime)
|
||||
command.MaxUpdateTime = command.UpdateTime;
|
||||
|
||||
// Update output object
|
||||
ActuatorCommandSet(&command);
|
||||
|
@ -86,6 +86,10 @@ static void settingsUpdatedCb(UAVObjEvent * objEv);
|
||||
|
||||
static float accelKi = 0;
|
||||
static float accelKp = 0;
|
||||
static float accel_alpha = 0;
|
||||
static bool accel_filter_enabled = false;
|
||||
static float accels_filtered[3];
|
||||
static float grot_filtered[3];
|
||||
static float yawBiasRate = 0;
|
||||
static float gyroGain = 0.42;
|
||||
static int16_t accelbias[3];
|
||||
@ -215,18 +219,22 @@ static void AttitudeTask(void *parameters)
|
||||
accelKp = 1;
|
||||
accelKi = 0.9;
|
||||
yawBiasRate = 0.23;
|
||||
accel_filter_enabled = false;
|
||||
init = 0;
|
||||
}
|
||||
else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) {
|
||||
accelKp = 1;
|
||||
accelKi = 0.9;
|
||||
yawBiasRate = 0.23;
|
||||
accel_filter_enabled = false;
|
||||
init = 0;
|
||||
} else if (init == 0) {
|
||||
// Reload settings (all the rates)
|
||||
AttitudeSettingsAccelKiGet(&accelKi);
|
||||
AttitudeSettingsAccelKpGet(&accelKp);
|
||||
AttitudeSettingsYawBiasRateGet(&yawBiasRate);
|
||||
if (accel_alpha > 0.0f)
|
||||
accel_filter_enabled = true;
|
||||
init = 1;
|
||||
}
|
||||
|
||||
@ -407,7 +415,6 @@ static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData)
|
||||
accelsData->x = accels[0] - accelbias[0] * ACCEL_SCALE; // Applying arbitrary scale here to match CC v1
|
||||
accelsData->y = accels[1] - accelbias[1] * ACCEL_SCALE;
|
||||
accelsData->z = accels[2] - accelbias[2] * ACCEL_SCALE;
|
||||
AccelsSet(&accelsData);
|
||||
|
||||
gyrosData->x = gyros[0];
|
||||
gyrosData->y = gyros[1];
|
||||
@ -430,6 +437,19 @@ static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData)
|
||||
return 0;
|
||||
}
|
||||
|
||||
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];
|
||||
}
|
||||
}
|
||||
|
||||
static void updateAttitude(AccelsData * accelsData, GyrosData * gyrosData)
|
||||
{
|
||||
float dT;
|
||||
@ -445,21 +465,38 @@ static void updateAttitude(AccelsData * accelsData, GyrosData * gyrosData)
|
||||
|
||||
float grot[3];
|
||||
float accel_err[3];
|
||||
|
||||
// Apply smoothing to accel values, to reduce vibration noise before main calculations.
|
||||
apply_accel_filter(accels, accels_filtered);
|
||||
|
||||
// Rotate gravity to body frame and cross with accels
|
||||
// Rotate gravity unit vector to body frame, filter and cross with accels
|
||||
grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2]));
|
||||
grot[1] = -(2 * (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]);
|
||||
CrossProduct((const float *) accels, (const float *) grot, accel_err);
|
||||
|
||||
apply_accel_filter(grot, grot_filtered);
|
||||
|
||||
CrossProduct((const float *)accels_filtered, (const float *)grot_filtered, accel_err);
|
||||
|
||||
// Account for accel magnitude
|
||||
float accel_mag = sqrtf(accels[0]*accels[0] + accels[1]*accels[1] + accels[2]*accels[2]);
|
||||
if(accel_mag < 1.0e-3f)
|
||||
float accel_mag = sqrtf(accels_filtered[0]*accels_filtered[0] + accels_filtered[1]*accels_filtered[1] + accels_filtered[2]*accels_filtered[2]);
|
||||
if (accel_mag < 1.0e-3f)
|
||||
return;
|
||||
|
||||
accel_err[0] /= accel_mag;
|
||||
accel_err[1] /= accel_mag;
|
||||
accel_err[2] /= accel_mag;
|
||||
// Account for filtered gravity vector magnitude
|
||||
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;
|
||||
|
||||
if (grot_mag < 1.0e-3f)
|
||||
return;
|
||||
|
||||
accel_err[0] /= (accel_mag*grot_mag);
|
||||
accel_err[1] /= (accel_mag*grot_mag);
|
||||
accel_err[2] /= (accel_mag*grot_mag);
|
||||
|
||||
// Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s
|
||||
gyro_correct_int[0] += accel_err[0] * accelKi;
|
||||
@ -531,6 +568,16 @@ static void settingsUpdatedCb(UAVObjEvent * objEv) {
|
||||
accelKi = attitudeSettings.AccelKi;
|
||||
yawBiasRate = attitudeSettings.YawBiasRate;
|
||||
gyroGain = attitudeSettings.GyroGain;
|
||||
|
||||
// Calculate accel filter alpha, in the same way as for gyro data in stabilization module.
|
||||
const float fakeDt = 0.0025;
|
||||
if (attitudeSettings.AccelTau < 0.0001) {
|
||||
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;
|
||||
}
|
||||
|
||||
zero_during_arming = attitudeSettings.ZeroDuringArming == ATTITUDESETTINGS_ZERODURINGARMING_TRUE;
|
||||
bias_correct_gyro = attitudeSettings.BiasCorrectGyro == ATTITUDESETTINGS_BIASCORRECTGYRO_TRUE;
|
||||
|
@ -64,13 +64,28 @@
|
||||
static struct CameraStab_data {
|
||||
portTickType lastSysTime;
|
||||
float inputs[CAMERASTABSETTINGS_INPUT_NUMELEM];
|
||||
float inputs_filtered[CAMERASTABSETTINGS_INPUT_NUMELEM];
|
||||
|
||||
#ifdef USE_GIMBAL_LPF
|
||||
float attitudeFiltered[CAMERASTABSETTINGS_INPUT_NUMELEM];
|
||||
#endif
|
||||
|
||||
#ifdef USE_GIMBAL_FF
|
||||
float ffLastAttitude[CAMERASTABSETTINGS_INPUT_NUMELEM];
|
||||
float ffLastAttitudeFiltered[CAMERASTABSETTINGS_INPUT_NUMELEM];
|
||||
float ffFilterAccumulator[CAMERASTABSETTINGS_INPUT_NUMELEM];
|
||||
#endif
|
||||
|
||||
} *csd;
|
||||
|
||||
// Private functions
|
||||
static void attitudeUpdated(UAVObjEvent* ev);
|
||||
static float bound(float val, float limit);
|
||||
|
||||
#ifdef USE_GIMBAL_FF
|
||||
static void applyFeedForward(uint8_t index, float dT, float *attitude, CameraStabSettingsData *cameraStab);
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
@ -100,7 +115,7 @@ int32_t CameraStabInitialize(void)
|
||||
if (!csd)
|
||||
return -1;
|
||||
|
||||
// make sure that all inputs[] and inputs_filtered[] are zeroed
|
||||
// initialize camera state variables
|
||||
memset(csd, 0, sizeof(struct CameraStab_data));
|
||||
csd->lastSysTime = xTaskGetTickCount();
|
||||
|
||||
@ -139,15 +154,17 @@ static void attitudeUpdated(UAVObjEvent* ev)
|
||||
CameraStabSettingsData cameraStab;
|
||||
CameraStabSettingsGet(&cameraStab);
|
||||
|
||||
// Check how long since last update, time delta between calls in ms
|
||||
// check how long since last update, time delta between calls in ms
|
||||
portTickType thisSysTime = xTaskGetTickCount();
|
||||
float dT = (thisSysTime > csd->lastSysTime) ?
|
||||
(thisSysTime - csd->lastSysTime) / portTICK_RATE_MS :
|
||||
(float)SAMPLE_PERIOD_MS / 1000.0f;
|
||||
float dT_millis = (thisSysTime > csd->lastSysTime) ?
|
||||
(float)((thisSysTime - csd->lastSysTime) * portTICK_RATE_MS) :
|
||||
(float)SAMPLE_PERIOD_MS;
|
||||
csd->lastSysTime = thisSysTime;
|
||||
|
||||
// Read any input channels and apply LPF
|
||||
// process axes
|
||||
for (uint8_t i = 0; i < CAMERASTABSETTINGS_INPUT_NUMELEM; i++) {
|
||||
|
||||
// read and process control input
|
||||
if (cameraStab.Input[i] != CAMERASTABSETTINGS_INPUT_NONE) {
|
||||
if (AccessoryDesiredInstGet(cameraStab.Input[i] - CAMERASTABSETTINGS_INPUT_ACCESSORY0, &accessory) == 0) {
|
||||
float input_rate;
|
||||
@ -158,38 +175,59 @@ static void attitudeUpdated(UAVObjEvent* ev)
|
||||
case CAMERASTABSETTINGS_STABILIZATIONMODE_AXISLOCK:
|
||||
input_rate = accessory.AccessoryVal * cameraStab.InputRate[i];
|
||||
if (fabs(input_rate) > cameraStab.MaxAxisLockRate)
|
||||
csd->inputs[i] = bound(csd->inputs[i] + input_rate * dT / 1000.0f, cameraStab.InputRange[i]);
|
||||
csd->inputs[i] = bound(csd->inputs[i] + input_rate * 0.001f * dT_millis, cameraStab.InputRange[i]);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
// bypass LPF calculation if ResponseTime is zero
|
||||
float rt = (float)cameraStab.ResponseTime[i];
|
||||
if (rt)
|
||||
csd->inputs_filtered[i] = (rt / (rt + dT)) * csd->inputs_filtered[i]
|
||||
+ (dT / (rt + dT)) * csd->inputs[i];
|
||||
else
|
||||
csd->inputs_filtered[i] = csd->inputs[i];
|
||||
}
|
||||
}
|
||||
|
||||
// calculate servo output
|
||||
float attitude;
|
||||
|
||||
switch (i) {
|
||||
case CAMERASTABSETTINGS_INPUT_ROLL:
|
||||
AttitudeActualRollGet(&attitude);
|
||||
break;
|
||||
case CAMERASTABSETTINGS_INPUT_PITCH:
|
||||
AttitudeActualPitchGet(&attitude);
|
||||
break;
|
||||
case CAMERASTABSETTINGS_INPUT_YAW:
|
||||
AttitudeActualYawGet(&attitude);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
#ifdef USE_GIMBAL_LPF
|
||||
if (cameraStab.ResponseTime) {
|
||||
float rt = (float)cameraStab.ResponseTime[i];
|
||||
attitude = csd->attitudeFiltered[i] = ((rt * csd->attitudeFiltered[i]) + (dT_millis * attitude)) / (rt + dT_millis);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_GIMBAL_FF
|
||||
if (cameraStab.FeedForward[i])
|
||||
applyFeedForward(i, dT_millis, &attitude, &cameraStab);
|
||||
#endif
|
||||
|
||||
// set output channels
|
||||
float output = bound((attitude + csd->inputs[i]) / cameraStab.OutputRange[i], 1.0f);
|
||||
switch (i) {
|
||||
case CAMERASTABSETTINGS_INPUT_ROLL:
|
||||
CameraDesiredRollSet(&output);
|
||||
break;
|
||||
case CAMERASTABSETTINGS_INPUT_PITCH:
|
||||
CameraDesiredPitchSet(&output);
|
||||
break;
|
||||
case CAMERASTABSETTINGS_INPUT_YAW:
|
||||
CameraDesiredYawSet(&output);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
|
||||
// Set output channels
|
||||
float attitude;
|
||||
float output;
|
||||
|
||||
AttitudeActualRollGet(&attitude);
|
||||
output = bound((attitude + csd->inputs_filtered[CAMERASTABSETTINGS_INPUT_ROLL]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_ROLL], 1.0f);
|
||||
CameraDesiredRollSet(&output);
|
||||
|
||||
AttitudeActualPitchGet(&attitude);
|
||||
output = bound((attitude + csd->inputs_filtered[CAMERASTABSETTINGS_INPUT_PITCH]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_PITCH], 1.0f);
|
||||
CameraDesiredPitchSet(&output);
|
||||
|
||||
AttitudeActualYawGet(&attitude);
|
||||
output = bound((attitude + csd->inputs_filtered[CAMERASTABSETTINGS_INPUT_YAW]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_YAW], 1.0f);
|
||||
CameraDesiredYawSet(&output);
|
||||
}
|
||||
|
||||
float bound(float val, float limit)
|
||||
@ -198,6 +236,62 @@ float bound(float val, float limit)
|
||||
(val < -limit) ? -limit :
|
||||
val;
|
||||
}
|
||||
|
||||
#ifdef USE_GIMBAL_FF
|
||||
void applyFeedForward(uint8_t index, float dT_millis, float *attitude, CameraStabSettingsData *cameraStab)
|
||||
{
|
||||
// compensate high feed forward values depending on gimbal type
|
||||
float gimbalTypeCorrection = 1.0f;
|
||||
|
||||
switch (cameraStab->GimbalType) {
|
||||
case CAMERASTABSETTINGS_GIMBALTYPE_GENERIC:
|
||||
// no correction
|
||||
break;
|
||||
case CAMERASTABSETTINGS_GIMBALTYPE_YAWROLLPITCH:
|
||||
if (index == CAMERASTABSETTINGS_INPUT_ROLL) {
|
||||
float pitch;
|
||||
AttitudeActualPitchGet(&pitch);
|
||||
gimbalTypeCorrection = (cameraStab->OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_PITCH] - fabs(pitch))
|
||||
/ cameraStab->OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_PITCH];
|
||||
}
|
||||
break;
|
||||
case CAMERASTABSETTINGS_GIMBALTYPE_YAWPITCHROLL:
|
||||
if (index == CAMERASTABSETTINGS_INPUT_PITCH) {
|
||||
float roll;
|
||||
AttitudeActualRollGet(&roll);
|
||||
gimbalTypeCorrection = (cameraStab->OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_ROLL] - fabs(roll))
|
||||
/ cameraStab->OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_ROLL];
|
||||
}
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
// apply feed forward
|
||||
float accumulator = csd->ffFilterAccumulator[index];
|
||||
accumulator += (*attitude - csd->ffLastAttitude[index]) * (float)cameraStab->FeedForward[index] * gimbalTypeCorrection;
|
||||
csd->ffLastAttitude[index] = *attitude;
|
||||
*attitude += accumulator;
|
||||
|
||||
float filter = (float)((accumulator > 0.0f) ? cameraStab->AccelTime[index] : cameraStab->DecelTime[index]) / dT_millis;
|
||||
if (filter < 1.0f)
|
||||
filter = 1.0f;
|
||||
accumulator -= accumulator / filter;
|
||||
csd->ffFilterAccumulator[index] = accumulator;
|
||||
*attitude += accumulator;
|
||||
|
||||
// apply acceleration limit
|
||||
float delta = *attitude - csd->ffLastAttitudeFiltered[index];
|
||||
float maxDelta = (float)cameraStab->MaxAccel * 0.001f * dT_millis;
|
||||
|
||||
if (fabs(delta) > maxDelta) {
|
||||
// we are accelerating too hard
|
||||
*attitude = csd->ffLastAttitudeFiltered[index] + ((delta > 0.0f) ? maxDelta : -maxDelta);
|
||||
}
|
||||
csd->ffLastAttitudeFiltered[index] = *attitude;
|
||||
}
|
||||
#endif // USE_GIMBAL_FF
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
@ -83,6 +83,11 @@ static xTaskHandle taskHandle;
|
||||
static ArmState_t armState;
|
||||
static portTickType lastSysTime;
|
||||
|
||||
#ifdef USE_INPUT_LPF
|
||||
static portTickType lastSysTimeLPF;
|
||||
static float inputFiltered[MANUALCONTROLSETTINGS_RESPONSETIME_NUMELEM];
|
||||
#endif
|
||||
|
||||
// Private functions
|
||||
static void updateActuatorDesired(ManualControlCommandData * cmd);
|
||||
static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualControlSettingsData * settings);
|
||||
@ -99,6 +104,10 @@ static bool okToArm(void);
|
||||
static bool validInputRange(int16_t min, int16_t max, uint16_t value);
|
||||
static void applyDeadband(float *value, float deadband);
|
||||
|
||||
#ifdef USE_INPUT_LPF
|
||||
static void applyLPF(float *value, ManualControlSettingsResponseTimeElem channel, ManualControlSettingsData *settings, float dT);
|
||||
#endif
|
||||
|
||||
#define RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP 12
|
||||
#define RCVR_ACTIVITY_MONITOR_MIN_RANGE 10
|
||||
struct rcvr_activity_fsm {
|
||||
@ -337,7 +346,18 @@ static void manualControlTask(void *parameters)
|
||||
applyDeadband(&cmd.Pitch, settings.Deadband);
|
||||
applyDeadband(&cmd.Yaw, settings.Deadband);
|
||||
}
|
||||
#ifdef USE_INPUT_LPF
|
||||
// Apply Low Pass Filter to input channels, time delta between calls in ms
|
||||
portTickType thisSysTime = xTaskGetTickCount();
|
||||
float dT = (thisSysTime > lastSysTimeLPF) ?
|
||||
(float)((thisSysTime - lastSysTimeLPF) * portTICK_RATE_MS) :
|
||||
(float)UPDATE_PERIOD_MS;
|
||||
lastSysTimeLPF = thisSysTime;
|
||||
|
||||
applyLPF(&cmd.Roll, MANUALCONTROLSETTINGS_RESPONSETIME_ROLL, &settings, dT);
|
||||
applyLPF(&cmd.Pitch, MANUALCONTROLSETTINGS_RESPONSETIME_PITCH, &settings, dT);
|
||||
applyLPF(&cmd.Yaw, MANUALCONTROLSETTINGS_RESPONSETIME_YAW, &settings, dT);
|
||||
#endif // USE_INPUT_LPF
|
||||
if(cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t) PIOS_RCVR_INVALID &&
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t) PIOS_RCVR_NODRIVER &&
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t) PIOS_RCVR_TIMEOUT)
|
||||
@ -348,6 +368,9 @@ static void manualControlTask(void *parameters)
|
||||
if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY0] !=
|
||||
MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) {
|
||||
accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY0];
|
||||
#ifdef USE_INPUT_LPF
|
||||
applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY0, &settings, dT);
|
||||
#endif
|
||||
if(AccessoryDesiredInstSet(0, &accessory) != 0)
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
@ -355,6 +378,9 @@ static void manualControlTask(void *parameters)
|
||||
if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1] !=
|
||||
MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) {
|
||||
accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1];
|
||||
#ifdef USE_INPUT_LPF
|
||||
applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY1, &settings, dT);
|
||||
#endif
|
||||
if(AccessoryDesiredInstSet(1, &accessory) != 0)
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
@ -362,6 +388,9 @@ static void manualControlTask(void *parameters)
|
||||
if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2] !=
|
||||
MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) {
|
||||
accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2];
|
||||
#ifdef USE_INPUT_LPF
|
||||
applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY2, &settings, dT);
|
||||
#endif
|
||||
if(AccessoryDesiredInstSet(2, &accessory) != 0)
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
@ -1033,6 +1062,20 @@ static void applyDeadband(float *value, float deadband)
|
||||
*value += deadband;
|
||||
}
|
||||
|
||||
#ifdef USE_INPUT_LPF
|
||||
/**
|
||||
* @brief Apply Low Pass Filter to Throttle/Roll/Pitch/Yaw or Accessory channel
|
||||
*/
|
||||
static void applyLPF(float *value, ManualControlSettingsResponseTimeElem channel, ManualControlSettingsData *settings, float dT)
|
||||
{
|
||||
if (settings->ResponseTime[channel]) {
|
||||
float rt = (float)settings->ResponseTime[channel];
|
||||
inputFiltered[channel] = ((rt * inputFiltered[channel]) + (dT * (*value))) / (rt + dT);
|
||||
*value = inputFiltered[channel];
|
||||
}
|
||||
}
|
||||
#endif // USE_INPUT_LPF
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
|
@ -79,6 +79,7 @@ uint8_t max_axislock_rate = 0;
|
||||
float weak_leveling_kp = 0;
|
||||
uint8_t weak_leveling_max = 0;
|
||||
bool lowThrottleZeroIntegral;
|
||||
bool lowThrottleZeroAxis[MAX_AXES];
|
||||
float vbar_decay = 0.991f;
|
||||
struct pid pids[PID_MAX];
|
||||
|
||||
@ -357,6 +358,18 @@ static void stabilizationTask(void* parameters)
|
||||
actuatorDesired.UpdateTime = dT * 1000;
|
||||
actuatorDesired.Throttle = stabDesired.Throttle;
|
||||
|
||||
// Suppress desired output while disarmed or throttle low, for configured axis
|
||||
if (flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED || stabDesired.Throttle < 0) {
|
||||
if (lowThrottleZeroAxis[ROLL])
|
||||
actuatorDesired.Roll = 0.0f;
|
||||
|
||||
if (lowThrottleZeroAxis[PITCH])
|
||||
actuatorDesired.Pitch = 0.0f;
|
||||
|
||||
if (lowThrottleZeroAxis[YAW])
|
||||
actuatorDesired.Yaw = 0.0f;
|
||||
}
|
||||
|
||||
if(PARSE_FLIGHT_MODE(flightStatus.FlightMode) != FLIGHTMODE_MANUAL) {
|
||||
ActuatorDesiredSet(&actuatorDesired);
|
||||
} else {
|
||||
@ -460,7 +473,12 @@ static void SettingsUpdatedCb(UAVObjEvent * ev)
|
||||
|
||||
// Whether to zero the PID integrals while throttle is low
|
||||
lowThrottleZeroIntegral = settings.LowThrottleZeroIntegral == STABILIZATIONSETTINGS_LOWTHROTTLEZEROINTEGRAL_TRUE;
|
||||
|
||||
|
||||
// Whether to suppress (zero) the StabilizationDesired output for each axis while disarmed or throttle is low
|
||||
lowThrottleZeroAxis[ROLL] = settings.LowThrottleZeroAxis[STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_ROLL] == STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_TRUE;
|
||||
lowThrottleZeroAxis[PITCH] = settings.LowThrottleZeroAxis[STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_PITCH] == STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_TRUE;
|
||||
lowThrottleZeroAxis[YAW] = settings.LowThrottleZeroAxis[STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_YAW] == STABILIZATIONSETTINGS_LOWTHROTTLEZEROAXIS_TRUE;
|
||||
|
||||
// The dT has some jitter iteration to iteration that we don't want to
|
||||
// make thie result unpredictable. Still, it's nicer to specify the constant
|
||||
// based on a time (in ms) rather than a fixed multiplier. The error between
|
||||
|
@ -74,7 +74,6 @@ static void telemetryRxTask(void *parameters);
|
||||
static int32_t transmitData(uint8_t * data, int32_t length);
|
||||
static void registerObject(UAVObjHandle obj);
|
||||
static void updateObject(UAVObjHandle obj, int32_t eventType);
|
||||
static int32_t addObject(UAVObjHandle obj);
|
||||
static int32_t setUpdatePeriod(UAVObjHandle obj, int32_t updatePeriodMs);
|
||||
static void processObjEvent(UAVObjEvent * ev);
|
||||
static void updateTelemetryStats();
|
||||
@ -155,11 +154,31 @@ MODULE_INITCALL(TelemetryInitialize, TelemetryStart)
|
||||
*/
|
||||
static void registerObject(UAVObjHandle obj)
|
||||
{
|
||||
// Setup object for periodic updates
|
||||
addObject(obj);
|
||||
if (UAVObjIsMetaobject(obj)) {
|
||||
/* Only connect change notifications for meta objects. No periodic updates */
|
||||
UAVObjConnectQueue(obj, priorityQueue, EV_MASK_ALL_UPDATES);
|
||||
return;
|
||||
} else {
|
||||
UAVObjMetadata metadata;
|
||||
UAVObjUpdateMode updateMode;
|
||||
UAVObjGetMetadata(obj, &metadata);
|
||||
updateMode = UAVObjGetTelemetryUpdateMode(&metadata);
|
||||
|
||||
// Setup object for telemetry updates
|
||||
updateObject(obj, EV_NONE);
|
||||
/* Only create a periodic event for objects that are periodic */
|
||||
if ((updateMode == UPDATEMODE_PERIODIC) ||
|
||||
(updateMode == UPDATEMODE_THROTTLED)) {
|
||||
// Setup object for periodic updates
|
||||
UAVObjEvent ev = {
|
||||
.obj = obj,
|
||||
.instId = UAVOBJ_ALL_INSTANCES,
|
||||
.event = EV_UPDATED_PERIODIC,
|
||||
};
|
||||
EventPeriodicQueueCreate(&ev, queue, 0);
|
||||
}
|
||||
|
||||
// Setup object for telemetry updates
|
||||
updateObject(obj, EV_NONE);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -172,30 +191,35 @@ static void updateObject(UAVObjHandle obj, int32_t eventType)
|
||||
UAVObjUpdateMode updateMode;
|
||||
int32_t eventMask;
|
||||
|
||||
if (UAVObjIsMetaobject(obj)) {
|
||||
/* This function updates the periodic updates for the object.
|
||||
* Meta Objects cannot have periodic updates.
|
||||
*/
|
||||
PIOS_Assert(false);
|
||||
return;
|
||||
}
|
||||
|
||||
// Get metadata
|
||||
UAVObjGetMetadata(obj, &metadata);
|
||||
updateMode = UAVObjGetTelemetryUpdateMode(&metadata);
|
||||
|
||||
// Setup object depending on update mode
|
||||
if (updateMode == UPDATEMODE_PERIODIC) {
|
||||
switch (updateMode) {
|
||||
case UPDATEMODE_PERIODIC:
|
||||
// Set update period
|
||||
setUpdatePeriod(obj, metadata.telemetryUpdatePeriod);
|
||||
// Connect queue
|
||||
eventMask = EV_UPDATED_PERIODIC | EV_UPDATED_MANUAL | EV_UPDATE_REQ;
|
||||
if (UAVObjIsMetaobject(obj)) {
|
||||
eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events)
|
||||
}
|
||||
UAVObjConnectQueue(obj, priorityQueue, eventMask);
|
||||
} else if (updateMode == UPDATEMODE_ONCHANGE) {
|
||||
break;
|
||||
case UPDATEMODE_ONCHANGE:
|
||||
// Set update period
|
||||
setUpdatePeriod(obj, 0);
|
||||
// Connect queue
|
||||
eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ;
|
||||
if (UAVObjIsMetaobject(obj)) {
|
||||
eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events)
|
||||
}
|
||||
UAVObjConnectQueue(obj, priorityQueue, eventMask);
|
||||
} else if (updateMode == UPDATEMODE_THROTTLED) {
|
||||
break;
|
||||
case UPDATEMODE_THROTTLED:
|
||||
if ((eventType == EV_UPDATED_PERIODIC) || (eventType == EV_NONE)) {
|
||||
// If we received a periodic update, we can change back to update on change
|
||||
eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ;
|
||||
@ -206,19 +230,15 @@ static void updateObject(UAVObjHandle obj, int32_t eventType)
|
||||
// Otherwise, we just received an object update, so switch to periodic for the timeout period to prevent more updates
|
||||
eventMask = EV_UPDATED_PERIODIC | EV_UPDATED_MANUAL | EV_UPDATE_REQ;
|
||||
}
|
||||
if (UAVObjIsMetaobject(obj)) {
|
||||
eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events)
|
||||
}
|
||||
UAVObjConnectQueue(obj, priorityQueue, eventMask);
|
||||
} else if (updateMode == UPDATEMODE_MANUAL) {
|
||||
break;
|
||||
case UPDATEMODE_MANUAL:
|
||||
// Set update period
|
||||
setUpdatePeriod(obj, 0);
|
||||
// Connect queue
|
||||
eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ;
|
||||
if (UAVObjIsMetaobject(obj)) {
|
||||
eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events)
|
||||
}
|
||||
UAVObjConnectQueue(obj, priorityQueue, eventMask);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
@ -272,11 +292,11 @@ static void processObjEvent(UAVObjEvent * ev)
|
||||
// If this is a metaobject then make necessary telemetry updates
|
||||
if (UAVObjIsMetaobject(ev->obj)) {
|
||||
updateObject(UAVObjGetLinkedObj(ev->obj), EV_NONE); // linked object will be the actual object the metadata are for
|
||||
}
|
||||
|
||||
if((updateMode == UPDATEMODE_THROTTLED) && !UAVObjIsMetaobject(ev->obj)) {
|
||||
// If this is UPDATEMODE_THROTTLED, the event mask changes on every event.
|
||||
updateObject(ev->obj, ev->event);
|
||||
} else {
|
||||
if (updateMode == UPDATEMODE_THROTTLED) {
|
||||
// If this is UPDATEMODE_THROTTLED, the event mask changes on every event.
|
||||
updateObject(ev->obj, ev->event);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -361,23 +381,6 @@ static int32_t transmitData(uint8_t * data, int32_t length)
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Setup object for periodic updates.
|
||||
* \param[in] obj The object to update
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
static int32_t addObject(UAVObjHandle obj)
|
||||
{
|
||||
UAVObjEvent ev;
|
||||
|
||||
// Add object for periodic updates
|
||||
ev.obj = obj;
|
||||
ev.instId = UAVOBJ_ALL_INSTANCES;
|
||||
ev.event = EV_UPDATED_PERIODIC;
|
||||
return EventPeriodicQueueCreate(&ev, queue, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set update period of object (it must be already setup for periodic updates)
|
||||
* \param[in] obj The object to update
|
||||
|
@ -196,7 +196,6 @@ int32_t PIOS_Flash_Jedec_Init(uint32_t spi_id, uint32_t slave_num, const struct
|
||||
*/
|
||||
int32_t PIOS_Flash_Jedec_StartTransaction()
|
||||
{
|
||||
return 0;
|
||||
#if defined(FLASH_FREERTOS)
|
||||
if(PIOS_Flash_Jedec_Validate(flash_dev) != 0)
|
||||
return -1;
|
||||
@ -213,7 +212,6 @@ int32_t PIOS_Flash_Jedec_StartTransaction()
|
||||
*/
|
||||
int32_t PIOS_Flash_Jedec_EndTransaction()
|
||||
{
|
||||
return 0;
|
||||
#if defined(FLASH_FREERTOS)
|
||||
if(PIOS_Flash_Jedec_Validate(flash_dev) != 0)
|
||||
return -1;
|
||||
|
@ -272,7 +272,7 @@ static int32_t PIOS_MPU6000_SetReg(uint8_t reg, uint8_t data)
|
||||
/**
|
||||
* @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
|
||||
* \returns The number of samples remaining in the fifo
|
||||
* \returns 0 if succesful
|
||||
*/
|
||||
int32_t PIOS_MPU6000_ReadGyros(struct pios_mpu6000_data * data)
|
||||
{
|
||||
|
@ -103,7 +103,7 @@ extern "C" {
|
||||
/* Architecture specifics. */
|
||||
#define portSTACK_GROWTH ( -1 )
|
||||
#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ )
|
||||
#define portBYTE_ALIGNMENT 8
|
||||
#define portBYTE_ALIGNMENT 4
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
|
||||
|
@ -94,6 +94,9 @@ uint16_t PIOS_WDG_Init()
|
||||
*/
|
||||
bool PIOS_WDG_RegisterFlag(uint16_t flag_requested)
|
||||
{
|
||||
// flag are being registered so we are in module initialization phase
|
||||
// clear the WDG to prevent timeout while initializing modules. (OP-815)
|
||||
PIOS_WDG_Clear();
|
||||
|
||||
/* Fail if flag already registered */
|
||||
if(wdg_configuration.used_flags & flag_requested)
|
||||
|
@ -47,26 +47,8 @@ struct pios_tim_dev {
|
||||
const struct pios_tim_callbacks * callbacks;
|
||||
uint32_t context;
|
||||
};
|
||||
#define PIOS_TIM_ALL_FLAGS TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4 | TIM_IT_Trigger | TIM_IT_Update
|
||||
|
||||
#if 0
|
||||
static bool PIOS_TIM_validate(struct pios_tim_dev * tim_dev)
|
||||
{
|
||||
return (tim_dev->magic == PIOS_TIM_DEV_MAGIC);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS) && 0
|
||||
static struct pios_tim_dev * PIOS_TIM_alloc(void)
|
||||
{
|
||||
struct pios_tim_dev * tim_dev;
|
||||
|
||||
tim_dev = (struct pios_tim_dev *)malloc(sizeof(*tim_dev));
|
||||
if (!tim_dev) return(NULL);
|
||||
|
||||
tim_dev->magic = PIOS_TIM_DEV_MAGIC;
|
||||
return(tim_dev);
|
||||
}
|
||||
#else
|
||||
static struct pios_tim_dev pios_tim_devs[PIOS_TIM_MAX_DEVS];
|
||||
static uint8_t pios_tim_num_devs;
|
||||
static struct pios_tim_dev * PIOS_TIM_alloc(void)
|
||||
@ -82,8 +64,6 @@ static struct pios_tim_dev * PIOS_TIM_alloc(void)
|
||||
|
||||
return (tim_dev);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
@ -105,7 +85,6 @@ int32_t PIOS_TIM_InitClock(const struct pios_tim_clock_cfg * cfg)
|
||||
case (uint32_t)TIM4:
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE);
|
||||
break;
|
||||
#ifdef STM32F10X_HD
|
||||
case (uint32_t)TIM5:
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE);
|
||||
break;
|
||||
@ -127,16 +106,15 @@ int32_t PIOS_TIM_InitClock(const struct pios_tim_clock_cfg * cfg)
|
||||
case (uint32_t)TIM11:
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM11, ENABLE);
|
||||
break;
|
||||
case (uint32_t)TIM12:
|
||||
case (uint32_t)TIM12:
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM12, ENABLE);
|
||||
break;
|
||||
case (uint32_t)TIM13:
|
||||
case (uint32_t)TIM13:
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM13, ENABLE);
|
||||
break;
|
||||
case (uint32_t)TIM14:
|
||||
case (uint32_t)TIM14:
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM14, ENABLE);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Configure the dividers for this timer */
|
||||
@ -348,68 +326,6 @@ static void PIOS_TIM_generic_irq_handler(TIM_TypeDef * timer)
|
||||
}
|
||||
}
|
||||
}
|
||||
#if 0
|
||||
uint16_t val = 0;
|
||||
for(uint8_t i = 0; i < pios_pwm_cfg.num_channels; i++) {
|
||||
struct pios_pwm_channel channel = pios_pwm_cfg.channels[i];
|
||||
if ((channel.timer == timer) && (TIM_GetITStatus(channel.timer, channel.ccr) == SET)) {
|
||||
|
||||
TIM_ClearITPendingBit(channel.timer, channel.ccr);
|
||||
|
||||
switch(channel.channel) {
|
||||
case TIM_Channel_1:
|
||||
val = TIM_GetCapture1(channel.timer);
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
val = TIM_GetCapture2(channel.timer);
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
val = TIM_GetCapture3(channel.timer);
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
val = TIM_GetCapture4(channel.timer);
|
||||
break;
|
||||
}
|
||||
|
||||
if (CaptureState[i] == 0) {
|
||||
RiseValue[i] = val;
|
||||
} else {
|
||||
FallValue[i] = val;
|
||||
}
|
||||
|
||||
// flip state machine and capture value here
|
||||
/* Simple rise or fall state machine */
|
||||
TIM_ICInitTypeDef TIM_ICInitStructure = pios_pwm_cfg.tim_ic_init;
|
||||
if (CaptureState[i] == 0) {
|
||||
/* Switch states */
|
||||
CaptureState[i] = 1;
|
||||
|
||||
/* Switch polarity of input capture */
|
||||
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling;
|
||||
TIM_ICInitStructure.TIM_Channel = channel.channel;
|
||||
TIM_ICInit(channel.timer, &TIM_ICInitStructure);
|
||||
} else {
|
||||
/* Capture computation */
|
||||
if (FallValue[i] > RiseValue[i]) {
|
||||
CaptureValue[i] = (FallValue[i] - RiseValue[i]);
|
||||
} else {
|
||||
CaptureValue[i] = ((channel.timer->ARR - RiseValue[i]) + FallValue[i]);
|
||||
}
|
||||
|
||||
/* Switch states */
|
||||
CaptureState[i] = 0;
|
||||
|
||||
/* Increase supervisor counter */
|
||||
CapCounter[i]++;
|
||||
|
||||
/* Switch polarity of input capture */
|
||||
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
|
||||
TIM_ICInitStructure.TIM_Channel = channel.channel;
|
||||
TIM_ICInit(channel.timer, &TIM_ICInitStructure);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Bind Interrupt Handlers
|
||||
*
|
||||
@ -422,31 +338,6 @@ static void PIOS_TIM_1_CC_irq_handler (void)
|
||||
PIOS_TIM_generic_irq_handler (TIM1);
|
||||
}
|
||||
|
||||
// The rest of TIM1 interrupts are overlapped
|
||||
void TIM1_BRK_TIM9_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_9_CC_irq_handler")));
|
||||
static void PIOS_TIM_9_CC_irq_handler (void)
|
||||
{
|
||||
// TODO: Check for TIM1_BRK
|
||||
PIOS_TIM_generic_irq_handler (TIM9);
|
||||
}
|
||||
|
||||
void TIM1_UP_TIM10_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_10_CC_irq_handler")));
|
||||
static void PIOS_TIM_10_CC_irq_handler (void)
|
||||
{
|
||||
if (TIM_GetITStatus(TIM1, TIM_IT_Update)) {
|
||||
PIOS_TIM_generic_irq_handler(TIM1);
|
||||
} else if (TIM_GetITStatus(TIM10, TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4)) {
|
||||
PIOS_TIM_generic_irq_handler (TIM10);
|
||||
}
|
||||
}
|
||||
|
||||
void TIM1_TRG_COM_TIM11_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_11_CC_irq_handler")));
|
||||
static void PIOS_TIM_11_CC_irq_handler (void)
|
||||
{
|
||||
// TODO: Check for TIM1_TRG
|
||||
PIOS_TIM_generic_irq_handler (TIM11);
|
||||
}
|
||||
|
||||
void TIM2_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_2_irq_handler")));
|
||||
static void PIOS_TIM_2_irq_handler (void)
|
||||
{
|
||||
@ -495,12 +386,84 @@ static void PIOS_TIM_8_CC_irq_handler (void)
|
||||
PIOS_TIM_generic_irq_handler (TIM8);
|
||||
}
|
||||
|
||||
// The rest of TIM1 interrupts are overlapped
|
||||
void TIM1_BRK_TIM9_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_9_CC_irq_handler")));
|
||||
static void PIOS_TIM_9_CC_irq_handler (void)
|
||||
{
|
||||
if (TIM_GetITStatus(TIM1, TIM_IT_Break))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM1);
|
||||
}
|
||||
else if (TIM_GetITStatus(TIM9, PIOS_TIM_ALL_FLAGS))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM9);
|
||||
}
|
||||
}
|
||||
|
||||
void TIM1_UP_TIM10_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_10_CC_irq_handler")));
|
||||
static void PIOS_TIM_10_CC_irq_handler (void)
|
||||
{
|
||||
if (TIM_GetITStatus(TIM1, TIM_IT_Update))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM1);
|
||||
}
|
||||
else if (TIM_GetITStatus(TIM10, PIOS_TIM_ALL_FLAGS))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM10);
|
||||
}
|
||||
}
|
||||
|
||||
void TIM1_TRG_COM_TIM11_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_11_CC_irq_handler")));
|
||||
static void PIOS_TIM_11_CC_irq_handler (void)
|
||||
{
|
||||
if(TIM_GetITStatus(TIM1, TIM_IT_COM | TIM_IT_Trigger))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM1);
|
||||
}
|
||||
else if (TIM_GetITStatus(TIM11, PIOS_TIM_ALL_FLAGS))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM11);
|
||||
}
|
||||
}
|
||||
|
||||
void TIM8_BRK_TIM12_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_12_irq_handler")));
|
||||
static void PIOS_TIM_12_irq_handler (void)
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM12);
|
||||
if(TIM_GetITStatus(TIM8, TIM_IT_Break))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM8);
|
||||
}
|
||||
else if (TIM_GetITStatus(TIM12, PIOS_TIM_ALL_FLAGS))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM12);
|
||||
}
|
||||
}
|
||||
|
||||
void TIM8_UP_TIM13_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM8_UP_TIM13_IRQHandler")));
|
||||
static void PIOS_TIM8_UP_TIM13_IRQHandler (void)
|
||||
{
|
||||
if(TIM_GetITStatus(TIM8, TIM_IT_Update))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM8);
|
||||
}
|
||||
else if (TIM_GetITStatus(TIM13, PIOS_TIM_ALL_FLAGS))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM13);
|
||||
}
|
||||
}
|
||||
|
||||
void TIM8_TRG_COM_TIM14_IRQHandler (void) __attribute__ ((alias ("PIOS_TIM8_TRG_COM_TIM14_IRQHandler")));
|
||||
static void PIOS_TIM8_TRG_COM_TIM14_IRQHandler (void)
|
||||
{
|
||||
if(TIM_GetITStatus(TIM8, TIM_IT_COM | TIM_IT_Trigger))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM8);
|
||||
}
|
||||
else if (TIM_GetITStatus(TIM14, PIOS_TIM_ALL_FLAGS))
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler (TIM14);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -98,7 +98,10 @@ uint16_t PIOS_WDG_Init()
|
||||
*/
|
||||
bool PIOS_WDG_RegisterFlag(uint16_t flag_requested)
|
||||
{
|
||||
|
||||
// flag are being registered so we are in module initialization phase
|
||||
// clear the WDG to prevent timeout while initializing modules. (OP-815)
|
||||
PIOS_WDG_Clear();
|
||||
|
||||
/* Fail if flag already registered */
|
||||
if(wdg_configuration.used_flags & flag_requested)
|
||||
return false;
|
||||
|
@ -46,40 +46,53 @@
|
||||
#define $(NAMEUC)_ISSETTINGS $(ISSETTINGS)
|
||||
#define $(NAMEUC)_NUMBYTES sizeof($(NAME)Data)
|
||||
|
||||
// Object access macros
|
||||
/**
|
||||
* @function $(NAME)Get(dataOut)
|
||||
* @brief Populate a $(NAME)Data object
|
||||
* @param[out] dataOut
|
||||
*/
|
||||
#define $(NAME)Get(dataOut) UAVObjGetData($(NAME)Handle(), dataOut)
|
||||
#define $(NAME)Set(dataIn) UAVObjSetData($(NAME)Handle(), dataIn)
|
||||
#define $(NAME)InstGet(instId, dataOut) UAVObjGetInstanceData($(NAME)Handle(), instId, dataOut)
|
||||
#define $(NAME)InstSet(instId, dataIn) UAVObjSetInstanceData($(NAME)Handle(), instId, dataIn)
|
||||
#define $(NAME)ConnectQueue(queue) UAVObjConnectQueue($(NAME)Handle(), queue, EV_MASK_ALL_UPDATES)
|
||||
#define $(NAME)ConnectCallback(cb) UAVObjConnectCallback($(NAME)Handle(), cb, EV_MASK_ALL_UPDATES)
|
||||
#define $(NAME)CreateInstance() UAVObjCreateInstance($(NAME)Handle(),&$(NAME)SetDefaults)
|
||||
#define $(NAME)RequestUpdate() UAVObjRequestUpdate($(NAME)Handle())
|
||||
#define $(NAME)RequestInstUpdate(instId) UAVObjRequestInstanceUpdate($(NAME)Handle(), instId)
|
||||
#define $(NAME)Updated() UAVObjUpdated($(NAME)Handle())
|
||||
#define $(NAME)InstUpdated(instId) UAVObjUpdated($(NAME)Handle(), instId)
|
||||
#define $(NAME)GetMetadata(dataOut) UAVObjGetMetadata($(NAME)Handle(), dataOut)
|
||||
#define $(NAME)SetMetadata(dataIn) UAVObjSetMetadata($(NAME)Handle(), dataIn)
|
||||
#define $(NAME)ReadOnly() UAVObjReadOnly($(NAME)Handle())
|
||||
// Generic interface functions
|
||||
int32_t $(NAME)Initialize();
|
||||
UAVObjHandle $(NAME)Handle();
|
||||
void $(NAME)SetDefaults(UAVObjHandle obj, uint16_t instId);
|
||||
|
||||
// Object data
|
||||
typedef struct {
|
||||
$(DATAFIELDS)
|
||||
} __attribute__((packed)) $(NAME)Data;
|
||||
|
||||
// Typesafe Object access functions
|
||||
/**
|
||||
* @function $(NAME)Get(dataOut)
|
||||
* @brief Populate a $(NAME)Data object
|
||||
* @param[out] dataOut
|
||||
*/
|
||||
static inline int32_t $(NAME)Get($(NAME)Data *dataOut) { return UAVObjGetData($(NAME)Handle(), dataOut); }
|
||||
|
||||
static inline int32_t $(NAME)Set(const $(NAME)Data *dataIn) { return UAVObjSetData($(NAME)Handle(), dataIn); }
|
||||
|
||||
static inline int32_t $(NAME)InstGet(uint16_t instId, $(NAME)Data *dataOut) { return UAVObjGetInstanceData($(NAME)Handle(), instId, dataOut); }
|
||||
|
||||
static inline int32_t $(NAME)InstSet(uint16_t instId, const $(NAME)Data *dataIn) { return UAVObjSetInstanceData($(NAME)Handle(), instId, dataIn); }
|
||||
|
||||
static inline int32_t $(NAME)ConnectQueue(xQueueHandle queue) { return UAVObjConnectQueue($(NAME)Handle(), queue, EV_MASK_ALL_UPDATES); }
|
||||
|
||||
static inline int32_t $(NAME)ConnectCallback(UAVObjEventCallback cb) { return UAVObjConnectCallback($(NAME)Handle(), cb, EV_MASK_ALL_UPDATES); }
|
||||
|
||||
static inline uint16_t $(NAME)CreateInstance() { return UAVObjCreateInstance($(NAME)Handle(), &$(NAME)SetDefaults); }
|
||||
|
||||
static inline void $(NAME)RequestUpdate() { UAVObjRequestUpdate($(NAME)Handle()); }
|
||||
|
||||
static inline void $(NAME)RequestInstUpdate(uint16_t instId) { UAVObjRequestInstanceUpdate($(NAME)Handle(), instId); }
|
||||
|
||||
static inline void $(NAME)Updated() { UAVObjUpdated($(NAME)Handle()); }
|
||||
|
||||
static inline void $(NAME)InstUpdated(uint16_t instId) { UAVObjInstanceUpdated($(NAME)Handle(), instId); }
|
||||
|
||||
static inline int32_t $(NAME)GetMetadata(UAVObjMetadata *dataOut) { return UAVObjGetMetadata($(NAME)Handle(), dataOut); }
|
||||
|
||||
static inline int32_t $(NAME)SetMetadata(const UAVObjMetadata *dataIn) { return UAVObjSetMetadata($(NAME)Handle(), dataIn); }
|
||||
|
||||
static inline int8_t $(NAME)ReadOnly() { return UAVObjReadOnly($(NAME)Handle()); }
|
||||
|
||||
// Field information
|
||||
$(DATAFIELDINFO)
|
||||
|
||||
// Generic interface functions
|
||||
int32_t $(NAME)Initialize();
|
||||
UAVObjHandle $(NAME)Handle();
|
||||
void $(NAME)SetDefaults(UAVObjHandle obj, uint16_t instId);
|
||||
|
||||
// set/Get functions
|
||||
$(SETGETFIELDSEXTERN)
|
||||
|
||||
|
@ -41,6 +41,17 @@
|
||||
// Macros
|
||||
#define SET_BITS(var, shift, value, mask) var = (var & ~(mask << shift)) | (value << shift);
|
||||
|
||||
/* Table of UAVO handles registered at compile time */
|
||||
extern struct UAVOData * __start__uavo_handles[] __attribute__((weak));
|
||||
extern struct UAVOData * __stop__uavo_handles[] __attribute__((weak));
|
||||
|
||||
#define UAVO_LIST_ITERATE(_item) \
|
||||
for (struct UAVOData ** _uavo_slot = __start__uavo_handles; \
|
||||
_uavo_slot && _uavo_slot < __stop__uavo_handles; \
|
||||
_uavo_slot++) { \
|
||||
struct UAVOData * _item = *_uavo_slot; \
|
||||
if (_item == NULL) continue;
|
||||
|
||||
/**
|
||||
* List of event queues and the eventmask associated with the queue.
|
||||
*/
|
||||
@ -98,7 +109,6 @@ struct UAVOData {
|
||||
* inside the payload for this UAVO.
|
||||
*/
|
||||
struct UAVOMeta metaObj;
|
||||
struct UAVOData * next;
|
||||
uint16_t instance_size;
|
||||
} __attribute__((packed));
|
||||
|
||||
@ -164,7 +174,6 @@ static void customSPrintf(uint8_t * buffer, uint8_t * format, ...);
|
||||
#endif
|
||||
|
||||
// Private variables
|
||||
static struct UAVOData * uavo_list;
|
||||
static xSemaphoreHandle mutex;
|
||||
static const UAVObjMetadata defMetadata = {
|
||||
.flags = (ACCESS_READWRITE << UAVOBJ_ACCESS_SHIFT |
|
||||
@ -188,9 +197,12 @@ static UAVObjStats stats;
|
||||
int32_t UAVObjInitialize()
|
||||
{
|
||||
// Initialize variables
|
||||
uavo_list = NULL;
|
||||
memset(&stats, 0, sizeof(UAVObjStats));
|
||||
|
||||
// Initialize the uavo handle table
|
||||
memset(__start__uavo_handles, 0,
|
||||
(uintptr_t)__stop__uavo_handles - (uintptr_t)__start__uavo_handles);
|
||||
|
||||
// Create mutex
|
||||
mutex = xSemaphoreCreateRecursiveMutex();
|
||||
if (mutex == NULL)
|
||||
@ -338,9 +350,6 @@ UAVObjHandle UAVObjRegister(uint32_t id,
|
||||
/* Initialize the embedded meta UAVO */
|
||||
UAVObjInitMetaData (&uavo_data->metaObj);
|
||||
|
||||
/* Add the newly created object to the global list of objects */
|
||||
LL_APPEND(uavo_list, uavo_data);
|
||||
|
||||
/* Initialize object fields and metadata to default values */
|
||||
if (initCb)
|
||||
initCb((UAVObjHandle) uavo_data, 0);
|
||||
@ -374,8 +383,7 @@ UAVObjHandle UAVObjGetByID(uint32_t id)
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Look for object
|
||||
struct UAVOData * tmp_obj;
|
||||
LL_FOREACH(uavo_list, tmp_obj) {
|
||||
UAVO_LIST_ITERATE(tmp_obj)
|
||||
if (tmp_obj->id == id) {
|
||||
found_obj = (UAVObjHandle *)tmp_obj;
|
||||
goto unlock_exit;
|
||||
@ -1019,15 +1027,13 @@ int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId)
|
||||
*/
|
||||
int32_t UAVObjSaveSettings()
|
||||
{
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
int32_t rc = -1;
|
||||
|
||||
// Save all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
UAVO_LIST_ITERATE(obj)
|
||||
// Check if this is a settings object
|
||||
if (UAVObjIsSettings(obj)) {
|
||||
// Save object
|
||||
@ -1051,15 +1057,13 @@ unlock_exit:
|
||||
*/
|
||||
int32_t UAVObjLoadSettings()
|
||||
{
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
int32_t rc = -1;
|
||||
|
||||
// Load all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
UAVO_LIST_ITERATE(obj)
|
||||
// Check if this is a settings object
|
||||
if (UAVObjIsSettings(obj)) {
|
||||
// Load object
|
||||
@ -1083,15 +1087,13 @@ unlock_exit:
|
||||
*/
|
||||
int32_t UAVObjDeleteSettings()
|
||||
{
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
int32_t rc = -1;
|
||||
|
||||
// Save all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
UAVO_LIST_ITERATE(obj)
|
||||
// Check if this is a settings object
|
||||
if (UAVObjIsSettings(obj)) {
|
||||
// Save object
|
||||
@ -1115,15 +1117,13 @@ unlock_exit:
|
||||
*/
|
||||
int32_t UAVObjSaveMetaobjects()
|
||||
{
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
int32_t rc = -1;
|
||||
|
||||
// Save all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
UAVO_LIST_ITERATE(obj)
|
||||
// Save object
|
||||
if (UAVObjSave( (UAVObjHandle) MetaObjectPtr(obj), 0) ==
|
||||
-1) {
|
||||
@ -1144,15 +1144,13 @@ unlock_exit:
|
||||
*/
|
||||
int32_t UAVObjLoadMetaobjects()
|
||||
{
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
int32_t rc = -1;
|
||||
|
||||
// Load all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
UAVO_LIST_ITERATE(obj)
|
||||
// Load object
|
||||
if (UAVObjLoad((UAVObjHandle) MetaObjectPtr(obj), 0) ==
|
||||
-1) {
|
||||
@ -1173,15 +1171,13 @@ unlock_exit:
|
||||
*/
|
||||
int32_t UAVObjDeleteMetaobjects()
|
||||
{
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
int32_t rc = -1;
|
||||
|
||||
// Load all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
UAVO_LIST_ITERATE(obj)
|
||||
// Load object
|
||||
if (UAVObjDelete((UAVObjHandle) MetaObjectPtr(obj), 0)
|
||||
== -1) {
|
||||
@ -1787,8 +1783,7 @@ void UAVObjIterate(void (*iterator) (UAVObjHandle obj))
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Iterate through the list and invoke iterator for each object
|
||||
struct UAVOData *obj;
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
UAVO_LIST_ITERATE(obj)
|
||||
(*iterator) ((UAVObjHandle) obj);
|
||||
(*iterator) ((UAVObjHandle) &obj->metaObj);
|
||||
}
|
||||
|
@ -40,7 +40,7 @@
|
||||
#include "$(NAMELC).h"
|
||||
|
||||
// Private variables
|
||||
static UAVObjHandle handle = NULL;
|
||||
static UAVObjHandle handle __attribute__((section("_uavo_handles")));
|
||||
|
||||
/**
|
||||
* Initialize object.
|
||||
|
@ -6,6 +6,7 @@ TEMPLATE = subdirs
|
||||
equals(copydata, 1) {
|
||||
|
||||
# Windows release only, no debug target DLLs ending with 'd'
|
||||
# It is assumed that SDL.dll can be found in the same directory as mingw32-make.exe
|
||||
win32:CONFIG(release, debug|release) {
|
||||
|
||||
# copy Qt DLLs and phonon4
|
||||
@ -29,7 +30,7 @@ equals(copydata, 1) {
|
||||
MINGW_DLLS = libgcc_s_dw2-1.dll \
|
||||
mingwm10.dll
|
||||
for(dll, MINGW_DLLS) {
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../../../../mingw/bin/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline()
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(QTMINGW)/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline()
|
||||
}
|
||||
|
||||
# copy iconengines
|
||||
@ -74,7 +75,7 @@ equals(copydata, 1) {
|
||||
# xcopy /s /e <SDL>\include\SDL\* C:\QtSDK\Desktop\Qt\4.7.3\mingw\include\SDL
|
||||
# xcopy /s /e <SDL>\lib\* C:\QtSDK\Desktop\Qt\4.7.3\mingw\lib
|
||||
SDL_DLL = SDL.dll
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../mingw/bin/$$SDL_DLL\") $$targetPath(\"$$GCS_APP_PATH/$$SDL_DLL\") $$addNewline()
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(QTMINGW)/$$SDL_DLL\") $$targetPath(\"$$GCS_APP_PATH/$$SDL_DLL\") $$addNewline()
|
||||
|
||||
data_copy.target = FORCE
|
||||
QMAKE_EXTRA_TARGETS += data_copy
|
||||
|
@ -9,6 +9,8 @@ include(openpilotgcs.pri)
|
||||
TEMPLATE = subdirs
|
||||
CONFIG += ordered
|
||||
|
||||
DEFINES += USE_PATHPLANNER
|
||||
|
||||
SUBDIRS = src share copydata
|
||||
unix:!macx:!isEmpty(copydata):SUBDIRS += bin
|
||||
|
||||
|
@ -5,8 +5,8 @@
|
||||
<UDPMirror>false</UDPMirror>
|
||||
<Description>Default configuration</Description>
|
||||
<Details>Default configuration built to work on all screen sizes</Details>
|
||||
<ExpertMode>true</ExpertMode>
|
||||
<OverrideLanguage>en_AU</OverrideLanguage>
|
||||
<ExpertMode>false</ExpertMode>
|
||||
<OverrideLanguage>C</OverrideLanguage>
|
||||
<SaveSettingsOnExit>true</SaveSettingsOnExit>
|
||||
<SettingsWindowHeight>700</SettingsWindowHeight>
|
||||
<SettingsWindowWidth>800</SettingsWindowWidth>
|
||||
@ -2538,22 +2538,6 @@
|
||||
</data>
|
||||
</default>
|
||||
</UAVObjectBrowser>
|
||||
<Uploader>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<defaultDataBits>3</defaultDataBits>
|
||||
<defaultFlow>0</defaultFlow>
|
||||
<defaultParity>0</defaultParity>
|
||||
<defaultPort>/dev/ttyS0</defaultPort>
|
||||
<defaultSpeed>14</defaultSpeed>
|
||||
<defaultStopBits>0</defaultStopBits>
|
||||
</data>
|
||||
</default>
|
||||
</Uploader>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>1.2.0</version>
|
||||
@ -2666,27 +2650,18 @@
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>LoggingGadget</classId>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>GpsDisplayGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight GPS</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAcAAAAAIAAAHo)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
<classId>LoggingGadget</classId>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>DebugGadget</classId>
|
||||
<classId>GpsDisplayGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight GPS</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB3wAAAAIAAAEp)</splitterSizes>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAVAAAAAIAAAGu)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
|
@ -8,6 +8,7 @@
|
||||
<SaveSettingsOnExit>true</SaveSettingsOnExit>
|
||||
<SettingsWindowHeight>700</SettingsWindowHeight>
|
||||
<SettingsWindowWidth>800</SettingsWindowWidth>
|
||||
<OverrideLanguage>C</OverrideLanguage>
|
||||
<UDPMirror>false</UDPMirror>
|
||||
<Description>Wide configuration</Description>
|
||||
<Details>Default configuration built for wide screens (17"up)</Details>
|
||||
@ -2505,22 +2506,6 @@
|
||||
</data>
|
||||
</default>
|
||||
</UAVObjectBrowser>
|
||||
<Uploader>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<defaultDataBits>3</defaultDataBits>
|
||||
<defaultFlow>0</defaultFlow>
|
||||
<defaultParity>0</defaultParity>
|
||||
<defaultPort>/dev/ttyS0</defaultPort>
|
||||
<defaultSpeed>14</defaultSpeed>
|
||||
<defaultStopBits>0</defaultStopBits>
|
||||
</data>
|
||||
</default>
|
||||
</Uploader>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>1.2.0</version>
|
||||
@ -2645,27 +2630,18 @@
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>LoggingGadget</classId>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>GpsDisplayGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight GPS</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAcAAAAAIAAAHo)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
<classId>LoggingGadget</classId>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>DebugGadget</classId>
|
||||
<classId>GpsDisplayGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight GPS</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB3wAAAAIAAAEp)</splitterSizes>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAVAAAAAIAAAGu)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
|
@ -1,11 +1,13 @@
|
||||
include(../../openpilotgcs.pri)
|
||||
include(../shared/qtsingleapplication/qtsingleapplication.pri)
|
||||
include(gcsversioninfo.pri)
|
||||
|
||||
TEMPLATE = app
|
||||
TARGET = $$GCS_APP_TARGET
|
||||
DESTDIR = $$GCS_APP_PATH
|
||||
QT += xml
|
||||
SOURCES += main.cpp
|
||||
SOURCES += main.cpp \
|
||||
gcssplashscreen.cpp
|
||||
include(../rpath.pri)
|
||||
include(../libs/utils/utils.pri)
|
||||
|
||||
@ -28,3 +30,9 @@ win32 {
|
||||
}
|
||||
|
||||
OTHER_FILES += openpilotgcs.rc
|
||||
|
||||
RESOURCES += \
|
||||
appresources.qrc
|
||||
|
||||
HEADERS += \
|
||||
gcssplashscreen.h
|
||||
|
5
ground/openpilotgcs/src/app/appresources.qrc
Normal file
5
ground/openpilotgcs/src/app/appresources.qrc
Normal file
@ -0,0 +1,5 @@
|
||||
<RCC>
|
||||
<qresource prefix="/app">
|
||||
<file>splash.png</file>
|
||||
</qresource>
|
||||
</RCC>
|
85
ground/openpilotgcs/src/app/gcssplashscreen.cpp
Normal file
85
ground/openpilotgcs/src/app/gcssplashscreen.cpp
Normal file
@ -0,0 +1,85 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file gcssplashscreen.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup [Group]
|
||||
* @{
|
||||
* @addtogroup GCSSplashScreen
|
||||
* @{
|
||||
* @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 "gcssplashscreen.h"
|
||||
#include <QDebug>
|
||||
|
||||
const QChar CopyrightSymbol(0x00a9);
|
||||
|
||||
GCSSplashScreen::GCSSplashScreen() :
|
||||
QSplashScreen(), m_pixmap(0), m_painter(0)
|
||||
{
|
||||
QString revision;
|
||||
QString year;
|
||||
#ifdef GCS_REVISION
|
||||
revision = GCS_REVISION;
|
||||
#else
|
||||
revision = tr("N/A");
|
||||
#endif
|
||||
|
||||
#ifdef GCS_YEAR
|
||||
year = GCS_YEAR;
|
||||
#else
|
||||
year = "2013";
|
||||
#endif
|
||||
|
||||
setWindowFlags(windowFlags());
|
||||
m_pixmap = new QPixmap(":/app/splash.png");
|
||||
|
||||
m_painter = new QPainter(m_pixmap);
|
||||
m_painter->setPen(Qt::lightGray);
|
||||
QFont font("Tahoma", 8);
|
||||
m_painter->setFont(font);
|
||||
m_painter->drawText(405, 170, QString(CopyrightSymbol) +
|
||||
QString(" 2010-") + year +
|
||||
QString(tr(" The OpenPilot Project - All Rights Reserved")));
|
||||
|
||||
m_painter->drawText(406, 173, 310, 100, Qt::TextWordWrap|Qt::AlignTop|Qt::AlignLeft,
|
||||
QString(tr("GCS Revision - ")) + revision);
|
||||
setPixmap(*m_pixmap);
|
||||
}
|
||||
|
||||
GCSSplashScreen::~GCSSplashScreen()
|
||||
{
|
||||
}
|
||||
|
||||
void GCSSplashScreen::drawMessageText(const QString &message)
|
||||
{
|
||||
QPixmap pix(*m_pixmap);
|
||||
QPainter progressPainter(&pix);
|
||||
progressPainter.setPen(Qt::lightGray);
|
||||
QFont font("Tahoma", 13);
|
||||
progressPainter.setFont(font);
|
||||
progressPainter.drawText(170, 385, message);
|
||||
setPixmap(pix);
|
||||
}
|
||||
|
||||
void GCSSplashScreen::showPluginLoadingProgress(ExtensionSystem::PluginSpec *pluginSpec)
|
||||
{
|
||||
QString message(tr("Loading ") + pluginSpec->name() + " plugin...");
|
||||
drawMessageText(message);
|
||||
}
|
@ -1,49 +1,56 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file waypointeditorgadgetfactory.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup Waypoint Editor GCS Plugins
|
||||
* @{
|
||||
* @addtogroup WaypointEditorGadgetPlugin Waypoint Editor Gadget Plugin
|
||||
* @{
|
||||
* @brief A gadget to edit a list of waypoints
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 WaypointEditorGADGETFACTORY_H_
|
||||
#define WaypointEditorGADGETFACTORY_H_
|
||||
|
||||
#include <coreplugin/iuavgadgetfactory.h>
|
||||
|
||||
namespace Core {
|
||||
class IUAVGadget;
|
||||
class IUAVGadgetFactory;
|
||||
}
|
||||
|
||||
using namespace Core;
|
||||
|
||||
class WaypointEditorGadgetFactory : public IUAVGadgetFactory
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
WaypointEditorGadgetFactory(QObject *parent = 0);
|
||||
~WaypointEditorGadgetFactory();
|
||||
|
||||
IUAVGadget *createGadget(QWidget *parent);
|
||||
};
|
||||
|
||||
#endif // WaypointEditorGADGETFACTORY_H_
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file gcssplashscreen.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup [Group]
|
||||
* @{
|
||||
* @addtogroup GCSSplashScreen
|
||||
* @{
|
||||
* @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
|
||||
*/
|
||||
|
||||
#ifndef GCSSPLASHSCREEN_H
|
||||
#define GCSSPLASHSCREEN_H
|
||||
|
||||
#include <QSplashScreen>
|
||||
#include <QPixmap>
|
||||
#include <QPainter>
|
||||
#include <extensionsystem/pluginspec.h>
|
||||
|
||||
#include "../../../../build/ground/openpilotgcs/gcsversioninfo.h"
|
||||
|
||||
class GCSSplashScreen : public QSplashScreen
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
explicit GCSSplashScreen();
|
||||
~GCSSplashScreen();
|
||||
|
||||
public slots:
|
||||
void showPluginLoadingProgress(ExtensionSystem::PluginSpec *pluginSpec);
|
||||
void showProgressMessage(const QString &message) { drawMessageText(message); }
|
||||
|
||||
private:
|
||||
QPixmap *m_pixmap;
|
||||
QPainter *m_painter;
|
||||
void drawMessageText(const QString &message);
|
||||
|
||||
};
|
||||
|
||||
#endif // GCSSPLASHSCREEN_H
|
@ -28,6 +28,7 @@
|
||||
|
||||
#include "qtsingleapplication.h"
|
||||
#include "utils/xmlconfig.h"
|
||||
#include "gcssplashscreen.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <extensionsystem/pluginspec.h>
|
||||
@ -46,6 +47,8 @@
|
||||
#include <QtGui/QMessageBox>
|
||||
#include <QtGui/QApplication>
|
||||
#include <QtGui/QMainWindow>
|
||||
#include <QtGui/QSplashScreen>
|
||||
#include <QtGui/QPainter>
|
||||
|
||||
enum { OptionIndent = 4, DescriptionIndent = 24 };
|
||||
|
||||
@ -241,10 +244,17 @@ int main(int argc, char **argv)
|
||||
#ifdef Q_OS_LINUX
|
||||
QApplication::setAttribute(Qt::AA_X11InitThreads, true);
|
||||
#endif
|
||||
QApplication::setGraphicsSystem("raster");
|
||||
|
||||
//Set the default locale to EN, if this is not set the system locale will be used
|
||||
//and as of now we dont want that behaviour.
|
||||
QLocale::setDefault(QLocale::English);
|
||||
|
||||
SharedTools::QtSingleApplication app((QLatin1String(appNameC)), argc, argv);
|
||||
|
||||
//Open Splashscreen
|
||||
GCSSplashScreen splash;
|
||||
splash.show();
|
||||
|
||||
QString locale = QLocale::system().name();
|
||||
|
||||
// Must be done before any QSettings class is created
|
||||
@ -275,6 +285,8 @@ int main(int argc, char **argv)
|
||||
}
|
||||
app.setProperty("qtc_locale", locale); // Do we need this?
|
||||
|
||||
splash.showProgressMessage(QObject::tr("Application starting..."));
|
||||
|
||||
// Load
|
||||
ExtensionSystem::PluginManager pluginManager;
|
||||
pluginManager.setFileExtension(QLatin1String("pluginspec"));
|
||||
@ -314,7 +326,7 @@ int main(int argc, char **argv)
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (!coreplugin) {
|
||||
if(!coreplugin){
|
||||
QString nativePaths = QDir::toNativeSeparators(pluginPaths.join(QLatin1String(",")));
|
||||
const QString reason = QCoreApplication::translate("Application", "Could not find 'Core.pluginspec' in %1").arg(nativePaths);
|
||||
displayError(msgCoreLoadFailure(reason));
|
||||
@ -342,11 +354,16 @@ int main(int argc, char **argv)
|
||||
if (!isFirstInstance && foundAppOptions.contains(QLatin1String(CLIENT_OPTION)))
|
||||
return sendArguments(app, pluginManager.arguments()) ? 0 : -1;
|
||||
|
||||
QObject::connect(&pluginManager, SIGNAL(pluginAboutToBeLoaded(ExtensionSystem::PluginSpec*)),
|
||||
&splash, SLOT(showPluginLoadingProgress(ExtensionSystem::PluginSpec*)));
|
||||
|
||||
pluginManager.loadPlugins();
|
||||
|
||||
if (coreplugin->hasError()) {
|
||||
displayError(msgCoreLoadFailure(coreplugin->errorString()));
|
||||
return 1;
|
||||
}
|
||||
|
||||
{
|
||||
QStringList errors;
|
||||
foreach (ExtensionSystem::PluginSpec *p, pluginManager.plugins())
|
||||
@ -369,5 +386,10 @@ int main(int argc, char **argv)
|
||||
|
||||
// Do this after the event loop has started
|
||||
QTimer::singleShot(100, &pluginManager, SLOT(startTests()));
|
||||
|
||||
//Update message and postpone closing of splashscreen 3 seconds
|
||||
splash.showProgressMessage(QObject::tr("Application started."));
|
||||
QTimer::singleShot(1500, &splash, SLOT(close()));
|
||||
|
||||
return app.exec();
|
||||
}
|
||||
|
BIN
ground/openpilotgcs/src/app/splash.png
Normal file
BIN
ground/openpilotgcs/src/app/splash.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 274 KiB |
@ -583,7 +583,9 @@ void PluginManagerPrivate::loadPlugins()
|
||||
QListIterator<PluginSpec *> it(queue);
|
||||
it.toBack();
|
||||
while (it.hasPrevious()) {
|
||||
loadPlugin(it.previous(), PluginSpec::Running);
|
||||
PluginSpec* plugin = it.previous();
|
||||
emit q->pluginAboutToBeLoaded(plugin);
|
||||
loadPlugin(plugin, PluginSpec::Running);
|
||||
}
|
||||
emit q->pluginsChanged();
|
||||
q->m_allPluginsLoaded=true;
|
||||
|
@ -114,6 +114,7 @@ signals:
|
||||
void objectAdded(QObject *obj);
|
||||
void aboutToRemoveObject(QObject *obj);
|
||||
|
||||
void pluginAboutToBeLoaded(ExtensionSystem::PluginSpec* pluginSpec);
|
||||
void pluginsChanged();
|
||||
void pluginsLoadEnded();
|
||||
private slots:
|
||||
|
@ -150,6 +150,7 @@ namespace mapcontrol
|
||||
QString uavoInfoStrLine3, uavoInfoStrLine4;
|
||||
QString uavoInfoStrLine5;
|
||||
|
||||
uavoInfoStrLine1.append(QString("CAS: %1 kph").arg(CAS_mps * 3.6));
|
||||
uavoInfoStrLine2.append(QString("Groundspeed: %1 kph").arg(groundspeed_kph, 0, 'f',1));
|
||||
uavoInfoStrLine3.append(QString("Lat-Lon: %1, %2").arg(coord.Lat(), 0, 'f',7).arg(coord.Lng(), 0, 'f',7));
|
||||
uavoInfoStrLine4.append(QString("North-East: %1 m, %2 m").arg(NED[0], 0, 'f',1).arg(NED[1], 0, 'f',1));
|
||||
|
@ -229,7 +229,6 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals
|
||||
}
|
||||
void WayPointItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event)
|
||||
{
|
||||
QGraphicsItem::mouseReleaseEvent(event);
|
||||
if(event->button()==Qt::LeftButton)
|
||||
{
|
||||
if(text)
|
||||
@ -242,15 +241,14 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals
|
||||
delete textBG;
|
||||
textBG=NULL;
|
||||
}
|
||||
coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y());
|
||||
|
||||
isDragging=false;
|
||||
RefreshToolTip();
|
||||
emit manualCoordChange(this);
|
||||
emit localPositionChanged(this->pos(),this);
|
||||
emit WPValuesChanged(this);
|
||||
emit WPDropped(this);
|
||||
}
|
||||
QGraphicsItem::mouseReleaseEvent(event);
|
||||
}
|
||||
void WayPointItem::mouseMoveEvent(QGraphicsSceneMouseEvent *event)
|
||||
{
|
||||
|
@ -234,13 +234,6 @@ signals:
|
||||
* @param waypoint a pointer to this WayPoint
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Fired when the waypoint is dropped somewhere
|
||||
*
|
||||
* @param waypoint a pointer to this WayPoint
|
||||
*/
|
||||
void WPDropped(WayPointItem* waypoint);
|
||||
|
||||
void WPValuesChanged(WayPointItem* waypoint);
|
||||
void waypointdoubleclick(WayPointItem* waypoint);
|
||||
void localPositionChanged(QPointF point,WayPointItem* waypoint);
|
||||
|
@ -1498,7 +1498,7 @@ font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Tricopter Yaw Motor channel</string>
|
||||
<string>Tricopter Yaw Servo channel</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
|
@ -51,9 +51,10 @@
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:20pt; font-weight:600; color:#ff0000;">WARNING:</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:'Lucida Grande'; font-size:13pt;"><br /></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:'Lucida Grande'; font-size:13pt;"></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;"><br /></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:'Lucida Grande'; font-size:13pt;"><br /></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:'Lucida Grande'; font-size:13pt;">This is an experimental plugin for the GCS that is going to make your aircraft shake, etc, so test with lots of space and be </span><span style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:600;">very very wary</span><span style=" font-family:'Lucida Grande'; font-size:13pt;"> for it creating bad tuning values. Basically there is no reason to think this will work at all.<br /><br />To use autotuning, here are the steps:<br /></span></p>
|
||||
<ul style="margin-top: 0px; margin-bottom: 0px; margin-left: 0px; margin-right: 0px; -qt-list-indent: 1;"><li style=" font-family:'Lucida Grande'; font-size:13pt;" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">On the <span style=" font-style:italic;">Input configuration</span> tab, <span style=" font-style:italic;">Flight Mode Switch Settings</span>, set one of your flight modes to &quot;Autotune&quot;.<br /></li>
|
||||
@ -70,7 +71,7 @@ p, li { white-space: pre-wrap; }
|
||||
<property name="title">
|
||||
<string>Module Control</string>
|
||||
</property>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_3">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_4">
|
||||
<item>
|
||||
<widget class="QCheckBox" name="enableAutoTune">
|
||||
<property name="text">
|
||||
@ -82,24 +83,13 @@ p, li { white-space: pre-wrap; }
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
<widget class="QLabel" name="label_13">
|
||||
<property name="text">
|
||||
<string>After enabling the module, you must power cycle before using and configuring.</string>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>454</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
<zorder>horizontalSpacer_5</zorder>
|
||||
<zorder>enableAutoTune</zorder>
|
||||
<zorder>horizontalSpacer_4</zorder>
|
||||
<zorder>enableAutoTune</zorder>
|
||||
<zorder>horizontalSpacer_5</zorder>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
@ -192,8 +182,8 @@ p, li { white-space: pre-wrap; }
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>711</width>
|
||||
<height>596</height>
|
||||
<width>709</width>
|
||||
<height>605</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
|
@ -7,7 +7,7 @@
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>786</width>
|
||||
<height>566</height>
|
||||
<height>791</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
@ -64,8 +64,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>741</width>
|
||||
<height>559</height>
|
||||
<width>762</width>
|
||||
<height>658</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
@ -130,7 +130,7 @@
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>130</height>
|
||||
<height>110</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
@ -285,7 +285,7 @@ have to define channel output range using Output configuration tab.</string>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_43">
|
||||
<property name="text">
|
||||
<string>Output Range</string>
|
||||
<string>Output Range (Angle)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
@ -390,7 +390,7 @@ margin:1px;</string>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>250</height>
|
||||
<height>187</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
@ -403,9 +403,6 @@ margin:1px;</string>
|
||||
<string>Advanced Settings (Control)</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_8">
|
||||
<property name="verticalSpacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<item row="0" column="3">
|
||||
<widget class="QLabel" name="label_32">
|
||||
<property name="minimumSize">
|
||||
@ -653,34 +650,6 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="3">
|
||||
<widget class="QSpinBox" name="yawResponseTime">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Input low-pass filter response time for yaw axis, ms.
|
||||
|
||||
This option smoothes the stick input. Zero value disables LPF.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1000</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>150</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:ResponseTime</string>
|
||||
<string>element:Yaw</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QComboBox" name="pitchStabilizationMode">
|
||||
<property name="focusPolicy">
|
||||
@ -759,34 +728,6 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="2">
|
||||
<widget class="QSpinBox" name="pitchResponseTime">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Input low-pass filter response time for pitch axis, ms.
|
||||
|
||||
This option smoothes the stick input. Zero value disables LPF.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1000</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>150</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:ResponseTime</string>
|
||||
<string>element:Pitch</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="rollStabilizationMode">
|
||||
<property name="focusPolicy">
|
||||
@ -865,59 +806,24 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QSpinBox" name="rollResponseTime">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Input low-pass filter response time for roll axis, ms.
|
||||
|
||||
This option smoothes the stick input. Zero value disables LPF.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1000</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>150</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:ResponseTime</string>
|
||||
<string>element:Roll</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="label_36">
|
||||
<property name="text">
|
||||
<string>MaxAxisLockRate</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="label_37">
|
||||
<property name="text">
|
||||
<string>Response Time</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="label_38">
|
||||
<property name="text">
|
||||
<string>Input Rate</string>
|
||||
<string>Input Rate (Speed)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_39">
|
||||
<property name="text">
|
||||
<string>Input Range</string>
|
||||
<string>Input Range (Angle)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
@ -928,14 +834,14 @@ This option smoothes the stick input. Zero value disables LPF.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2" colspan="2">
|
||||
<item row="5" column="2" colspan="2">
|
||||
<widget class="QLabel" name="label_41">
|
||||
<property name="text">
|
||||
<string>(the same value for Roll, Pitch, Yaw)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<item row="5" column="1">
|
||||
<widget class="QDoubleSpinBox" name="MaxAxisLockRate">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
@ -974,30 +880,471 @@ value.</string>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_4">
|
||||
<widget class="QGroupBox" name="groupBox_3">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>71</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
<height>187</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Messages</string>
|
||||
<string>Expert Settings (Attitude Filter and Feed Forward)</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<item>
|
||||
<widget class="QLabel" name="message">
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label_49">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_50">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QLabel" name="label_51">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string>Attitude Filter RT</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QSpinBox" name="rollResponseTime">
|
||||
<property name="toolTip">
|
||||
<string>Roll axis attitude filter response time
|
||||
|
||||
Range: 0-250ms, 0 disables the filter (default).
|
||||
|
||||
Smoothes estimated airframe attitude used by camera stabilization.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>250</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:ResponseTime</string>
|
||||
<string>element:Roll</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QSpinBox" name="pitchResponseTime">
|
||||
<property name="toolTip">
|
||||
<string>Pitch axis attitude filter response time
|
||||
|
||||
Range: 0-250ms, 0 disables the filter (default).
|
||||
|
||||
Smoothes estimated airframe attitude used by camera stabilization.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>250</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:ResponseTime</string>
|
||||
<string>element:Pitch</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QSpinBox" name="yawResponseTime">
|
||||
<property name="toolTip">
|
||||
<string>Yaw axis attitude filter response time
|
||||
|
||||
Range: 0-250ms, 0 disables the filter (default).
|
||||
|
||||
Smoothes estimated airframe attitude used by camera stabilization.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>250</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:ResponseTime</string>
|
||||
<string>element:Yaw</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="text">
|
||||
<string>FF Servo Acceleration</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QSpinBox" name="rollFeedForward">
|
||||
<property name="toolTip">
|
||||
<string>Roll servo feed forward acceleration
|
||||
|
||||
Range: 0-25, 0 disables feed forward for the axis (default).
|
||||
|
||||
Good starting value is 2-7.
|
||||
Too high value may burn your servo!</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:FeedForward</string>
|
||||
<string>element:Roll</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QSpinBox" name="pitchFeedForward">
|
||||
<property name="toolTip">
|
||||
<string>Pitch servo feed forward acceleration
|
||||
|
||||
Range: 0-25, 0 disables feed forward for the axis (default).
|
||||
|
||||
Good starting value is 2-7.
|
||||
Too high value may burn your servo!</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:FeedForward</string>
|
||||
<string>element:Pitch</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QSpinBox" name="yawFeedForward">
|
||||
<property name="toolTip">
|
||||
<string>Yaw servo feed forward acceleration
|
||||
|
||||
Range: 0-25, 0 disables feed forward for the axis (default).
|
||||
|
||||
Good starting value is 2-7.
|
||||
Too high value may burn your servo!</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:FeedForward</string>
|
||||
<string>element:Yaw</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_48">
|
||||
<property name="text">
|
||||
<string>FF Accel Time Constant</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QSpinBox" name="rollAccelTime">
|
||||
<property name="toolTip">
|
||||
<string>Roll servo feed forward acceleration time constant
|
||||
|
||||
Range: 0-50ms, default is 5.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:AccelTime</string>
|
||||
<string>element:Roll</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QSpinBox" name="pitchAccelTime">
|
||||
<property name="toolTip">
|
||||
<string>Pitch servo feed forward acceleration time constant
|
||||
|
||||
Range: 0-50ms, default is 5.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:AccelTime</string>
|
||||
<string>element:Pitch</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QSpinBox" name="yawAccelTime">
|
||||
<property name="toolTip">
|
||||
<string>Yaw servo feed forward acceleration time constant
|
||||
|
||||
Range: 0-50ms, default is 5.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:AccelTime</string>
|
||||
<string>element:Yaw</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>FF Decel Time Constant</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<widget class="QSpinBox" name="rollDecelTime">
|
||||
<property name="toolTip">
|
||||
<string>Roll servo feed forward deceleration time constant
|
||||
|
||||
Range: 0-50ms, default is 5.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:DecelTime</string>
|
||||
<string>element:Roll</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="2">
|
||||
<widget class="QSpinBox" name="pitchDecelTime">
|
||||
<property name="toolTip">
|
||||
<string>Pitch servo feed forward deceleration time constant
|
||||
|
||||
Range: 0-50ms, default is 5.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:DecelTime</string>
|
||||
<string>element:Pitch</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="3">
|
||||
<widget class="QSpinBox" name="yawDecelTime">
|
||||
<property name="toolTip">
|
||||
<string>Yaw servo feed forward deceleration time constant
|
||||
|
||||
Range: 0-50ms, default is 5.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:DecelTime</string>
|
||||
<string>element:Yaw</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="label_47">
|
||||
<property name="text">
|
||||
<string>Gimbal Type:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QComboBox" name="gimbalType">
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Gimbal type
|
||||
|
||||
Used to limit feed forward acceleration at extreme angles.
|
||||
Generic type provides no limit.</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:GimbalType</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Yaw-Roll-Pitch</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="2">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="text">
|
||||
<string>FF Max Acceleration</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="3">
|
||||
<widget class="QSpinBox" name="maxAccel">
|
||||
<property name="toolTip">
|
||||
<string>Feed forward maximum acceleration
|
||||
|
||||
Range: 0-1000, default is 500.
|
||||
|
||||
The same value is used for all axes.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1000</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>500</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:CameraStabSettings</string>
|
||||
<string>fieldname:MaxAccel</string>
|
||||
<string>buttongroup:1</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
@ -1005,13 +1352,17 @@ value.</string>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_2">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Input configuration also provides smoothing for controls. Look for RT options on the RC Input tab.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Expanding</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
@ -1028,6 +1379,37 @@ value.</string>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_4">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>50</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Messages</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<item>
|
||||
<widget class="QLabel" name="message">
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<property name="horizontalSpacing">
|
||||
@ -1221,7 +1603,44 @@ Apply or Save button afterwards.</string>
|
||||
</layout>
|
||||
</widget>
|
||||
<tabstops>
|
||||
<tabstop>scrollArea</tabstop>
|
||||
<tabstop>enableCameraStabilization</tabstop>
|
||||
<tabstop>rollChannel</tabstop>
|
||||
<tabstop>pitchChannel</tabstop>
|
||||
<tabstop>yawChannel</tabstop>
|
||||
<tabstop>rollOutputRange</tabstop>
|
||||
<tabstop>pitchOutputRange</tabstop>
|
||||
<tabstop>yawOutputRange</tabstop>
|
||||
<tabstop>rollInputChannel</tabstop>
|
||||
<tabstop>pitchInputChannel</tabstop>
|
||||
<tabstop>yawInputChannel</tabstop>
|
||||
<tabstop>rollStabilizationMode</tabstop>
|
||||
<tabstop>pitchStabilizationMode</tabstop>
|
||||
<tabstop>yawStabilizationMode</tabstop>
|
||||
<tabstop>rollInputRange</tabstop>
|
||||
<tabstop>pitchInputRange</tabstop>
|
||||
<tabstop>yawInputRange</tabstop>
|
||||
<tabstop>rollInputRate</tabstop>
|
||||
<tabstop>pitchInputRate</tabstop>
|
||||
<tabstop>yawInputRate</tabstop>
|
||||
<tabstop>MaxAxisLockRate</tabstop>
|
||||
<tabstop>rollResponseTime</tabstop>
|
||||
<tabstop>pitchResponseTime</tabstop>
|
||||
<tabstop>yawResponseTime</tabstop>
|
||||
<tabstop>rollFeedForward</tabstop>
|
||||
<tabstop>pitchFeedForward</tabstop>
|
||||
<tabstop>yawFeedForward</tabstop>
|
||||
<tabstop>rollAccelTime</tabstop>
|
||||
<tabstop>pitchAccelTime</tabstop>
|
||||
<tabstop>yawAccelTime</tabstop>
|
||||
<tabstop>rollDecelTime</tabstop>
|
||||
<tabstop>pitchDecelTime</tabstop>
|
||||
<tabstop>yawDecelTime</tabstop>
|
||||
<tabstop>gimbalType</tabstop>
|
||||
<tabstop>maxAccel</tabstop>
|
||||
<tabstop>camerastabilizationResetToDefaults</tabstop>
|
||||
<tabstop>pushButton</tabstop>
|
||||
<tabstop>camerastabilizationSaveRAM</tabstop>
|
||||
<tabstop>camerastabilizationSaveSD</tabstop>
|
||||
</tabstops>
|
||||
<resources>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
|
@ -111,7 +111,7 @@
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>750</width>
|
||||
<height>466</height>
|
||||
<height>483</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
@ -391,6 +391,86 @@ arming it in that case!</string>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_4">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>AccelTau</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_12">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QDoubleSpinBox" name="accelTauSpinbox">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>60</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Accelerometer filtering.
|
||||
|
||||
Sets the amount of lowpass filtering of accelerometer data
|
||||
for the attitude estimation. Higher values apply a stronger
|
||||
filter, which may help with drifting in attitude mode.
|
||||
|
||||
Range: 0.00 - 0.20, Good starting value: 0.05 - 0.10
|
||||
Start low and raise until drift stops.
|
||||
|
||||
A setting of 0.00 disables the filter.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>2</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>0.200000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_11">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
|
@ -281,6 +281,7 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType)
|
||||
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
resetMotorAndServoMixers(mixer);
|
||||
|
||||
// ... and compute the matrix:
|
||||
// In order to make code a bit nicer, we assume:
|
||||
@ -288,16 +289,8 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType)
|
||||
|
||||
// 1. Assign the servo/motor/none for each channel
|
||||
|
||||
int channel;
|
||||
//disable all
|
||||
for (channel=0; (unsigned int) channel < VehicleConfig::CHANNEL_NUMELEM; channel++)
|
||||
{
|
||||
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
|
||||
resetMixerVector(mixer, channel);
|
||||
}
|
||||
|
||||
//motor
|
||||
channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
|
||||
int channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
|
||||
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_MOTOR);
|
||||
setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
|
||||
|
||||
@ -359,6 +352,7 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType)
|
||||
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
resetMotorAndServoMixers(mixer);
|
||||
|
||||
// Save the curve:
|
||||
// ... and compute the matrix:
|
||||
@ -367,17 +361,10 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType)
|
||||
|
||||
// 1. Assign the servo/motor/none for each channel
|
||||
|
||||
int channel;
|
||||
double value;
|
||||
//disable all
|
||||
for (channel=0; (unsigned int) channel < VehicleConfig::CHANNEL_NUMELEM; channel++)
|
||||
{
|
||||
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
|
||||
resetMixerVector(mixer, channel);
|
||||
}
|
||||
|
||||
//motor
|
||||
channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
|
||||
int channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
|
||||
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_MOTOR);
|
||||
setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
|
||||
|
||||
@ -437,6 +424,7 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType)
|
||||
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
resetMotorAndServoMixers(mixer);
|
||||
|
||||
// Save the curve:
|
||||
// ... and compute the matrix:
|
||||
@ -445,17 +433,10 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType)
|
||||
|
||||
// 1. Assign the servo/motor/none for each channel
|
||||
|
||||
int channel;
|
||||
double value;
|
||||
//disable all
|
||||
for (channel=0; (unsigned int) channel < VehicleConfig::CHANNEL_NUMELEM; channel++)
|
||||
{
|
||||
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
|
||||
resetMixerVector(mixer, channel);
|
||||
}
|
||||
|
||||
//motor
|
||||
channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
|
||||
int channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
|
||||
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_MOTOR);
|
||||
setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
|
||||
|
||||
|
@ -295,16 +295,10 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleMotorcycle(QString airframeTyp
|
||||
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
|
||||
int channel;
|
||||
//disable all
|
||||
for (channel=0; (unsigned int) channel < VehicleConfig::CHANNEL_NUMELEM; channel++) {
|
||||
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
|
||||
resetMixerVector(mixer, channel);
|
||||
}
|
||||
resetMotorAndServoMixers(mixer);
|
||||
|
||||
//motor
|
||||
channel = m_aircraft->gvMotor2ChannelBox->currentIndex()-1;
|
||||
int channel = m_aircraft->gvMotor2ChannelBox->currentIndex()-1;
|
||||
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
|
||||
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
|
||||
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
|
||||
@ -352,16 +346,10 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleDifferential(QString airframeT
|
||||
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
|
||||
int channel;
|
||||
//disable all
|
||||
for (channel=0; (unsigned int) channel < VehicleConfig::CHANNEL_NUMELEM; channel++) {
|
||||
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
|
||||
resetMixerVector(mixer, channel);
|
||||
}
|
||||
resetMotorAndServoMixers(mixer);
|
||||
|
||||
//left motor
|
||||
channel = m_aircraft->gvMotor1ChannelBox->currentIndex()-1;
|
||||
int channel = m_aircraft->gvMotor1ChannelBox->currentIndex()-1;
|
||||
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
|
||||
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
|
||||
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
|
||||
@ -407,15 +395,9 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleCar(QString airframeType)
|
||||
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
resetMotorAndServoMixers(mixer);
|
||||
|
||||
int channel;
|
||||
//disable all
|
||||
for (channel=0; (unsigned int) channel < VehicleConfig::CHANNEL_NUMELEM; channel++) {
|
||||
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
|
||||
resetMixerVector(mixer, channel);
|
||||
}
|
||||
|
||||
channel = m_aircraft->gvSteering1ChannelBox->currentIndex()-1;
|
||||
int channel = m_aircraft->gvSteering1ChannelBox->currentIndex()-1;
|
||||
setMixerType(mixer,channel, VehicleConfig::MIXERTYPE_SERVO);
|
||||
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
|
||||
|
||||
|
@ -1032,13 +1032,7 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3])
|
||||
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
|
||||
//disable all
|
||||
for (int channel=0; channel<(int)VehicleConfig::CHANNEL_NUMELEM; channel++)
|
||||
{
|
||||
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
|
||||
resetMixerVector(mixer, channel);
|
||||
}
|
||||
resetMotorAndServoMixers(mixer);
|
||||
|
||||
// and enable only the relevant channels:
|
||||
double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100;
|
||||
|
@ -181,6 +181,18 @@ void VehicleConfig::resetMixerVector(UAVDataObject* mixer, int channel)
|
||||
}
|
||||
}
|
||||
|
||||
// Disable all servo/motor mixers (but keep camera and accessory ones)
|
||||
void VehicleConfig::resetMotorAndServoMixers(UAVDataObject *mixer)
|
||||
{
|
||||
for (int channel = 0; channel < (int)VehicleConfig::CHANNEL_NUMELEM; channel++) {
|
||||
QString type = getMixerType(mixer, channel);
|
||||
if ((type == "Disabled") || (type == "Motor") || (type == "Servo")) {
|
||||
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_DISABLED);
|
||||
resetMixerVector(mixer, channel);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
double VehicleConfig::getMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName)
|
||||
{
|
||||
Q_ASSERT(mixer);
|
||||
|
@ -127,6 +127,7 @@ class VehicleConfig: public ConfigTaskWidget
|
||||
double getMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName);
|
||||
void setMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName, double value);
|
||||
void resetMixerVector(UAVDataObject* mixer, int channel);
|
||||
void resetMotorAndServoMixers(UAVDataObject* mixer);
|
||||
QString getMixerType(UAVDataObject* mixer, int channel);
|
||||
void setMixerType(UAVDataObject* mixer, int channel, MixerTypeElem mixerType);
|
||||
double getMixerValue(UAVDataObject* mixer, QString elementName);
|
||||
|
@ -56,7 +56,9 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
|
||||
|
||||
// Connect the help button
|
||||
connect(ui->ccAttitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings","ZeroDuringArming",ui->zeroGyroBiasOnArming);
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings", "AccelTau", ui->accelTauSpinbox);
|
||||
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->rollBias,AttitudeSettings::BOARDROTATION_ROLL);
|
||||
addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->pitchBias,AttitudeSettings::BOARDROTATION_PITCH);
|
||||
@ -73,8 +75,8 @@ ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget()
|
||||
void ConfigCCAttitudeWidget::sensorsUpdated(UAVObject * obj) {
|
||||
|
||||
if (!timer.isActive()) {
|
||||
// ignore updates that come in after the timer has expired
|
||||
return;
|
||||
// ignore updates that come in after the timer has expired
|
||||
return;
|
||||
}
|
||||
|
||||
Accels * accels = Accels::GetInstance(getObjectManager());
|
||||
@ -207,16 +209,27 @@ void ConfigCCAttitudeWidget::openHelp()
|
||||
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/44Cf", QUrl::StrictMode) );
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::setAccelFiltering(bool active)
|
||||
{
|
||||
setDirty(true);
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::enableControls(bool enable)
|
||||
{
|
||||
if(ui->zeroBias)
|
||||
if(ui->zeroBias) {
|
||||
ui->zeroBias->setEnabled(enable);
|
||||
}
|
||||
if(ui->zeroGyroBiasOnArming) {
|
||||
ui->zeroGyroBiasOnArming->setEnabled(enable);
|
||||
}
|
||||
if(ui->accelTauSpinbox) {
|
||||
ui->accelTauSpinbox->setEnabled(enable);
|
||||
}
|
||||
ConfigTaskWidget::enableControls(enable);
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::updateObjectsFromWidgets()
|
||||
{
|
||||
ConfigTaskWidget::updateObjectsFromWidgets();
|
||||
|
||||
ui->zeroBiasProgress->setValue(0);
|
||||
}
|
||||
|
@ -52,6 +52,7 @@ private slots:
|
||||
void timeout();
|
||||
void startAccelCalibration();
|
||||
void openHelp();
|
||||
void setAccelFiltering(bool active);
|
||||
|
||||
private:
|
||||
Ui_ccattitude *ui;
|
||||
@ -65,6 +66,7 @@ private:
|
||||
QList<double> x_accum, y_accum, z_accum;
|
||||
QList<double> x_gyro_accum, y_gyro_accum, z_gyro_accum;
|
||||
|
||||
static const float DEFAULT_ENABLED_ACCEL_TAU = 0.1;
|
||||
static const int NUM_SENSOR_UPDATES = 300;
|
||||
static const float ACCEL_SCALE = 0.004f * 9.81f;
|
||||
protected:
|
||||
|
@ -77,6 +77,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
|
||||
//Generate the rows of buttons in the input channel form GUI
|
||||
unsigned int index=0;
|
||||
unsigned int indexRT = 0;
|
||||
foreach (QString name, manualSettingsObj->getField("ChannelNumber")->getElementNames())
|
||||
{
|
||||
Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM);
|
||||
@ -88,6 +89,28 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inpForm->ui->channelMin,index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inpForm->ui->channelNeutral,index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inpForm->ui->channelMax,index);
|
||||
|
||||
// Input filter response time fields supported for some channels only
|
||||
switch (index) {
|
||||
case ManualControlSettings::CHANNELGROUPS_ROLL:
|
||||
case ManualControlSettings::CHANNELGROUPS_PITCH:
|
||||
case ManualControlSettings::CHANNELGROUPS_YAW:
|
||||
case ManualControlSettings::CHANNELGROUPS_ACCESSORY0:
|
||||
case ManualControlSettings::CHANNELGROUPS_ACCESSORY1:
|
||||
case ManualControlSettings::CHANNELGROUPS_ACCESSORY2:
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "ResponseTime", inpForm->ui->channelResponseTime, indexRT);
|
||||
++indexRT;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_THROTTLE:
|
||||
case ManualControlSettings::CHANNELGROUPS_FLIGHTMODE:
|
||||
case ManualControlSettings::CHANNELGROUPS_COLLECTIVE:
|
||||
inpForm->ui->channelResponseTime->setEnabled(false);
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
break;
|
||||
}
|
||||
|
||||
++index;
|
||||
}
|
||||
|
||||
|
@ -54,7 +54,7 @@
|
||||
#define sign(x) ((x < 0) ? -1 : 1)
|
||||
|
||||
// Uncomment this to enable 6 point calibration on the accels
|
||||
//#define SIX_POINT_CAL_ACCEL
|
||||
#define SIX_POINT_CAL_ACCEL
|
||||
|
||||
const double ConfigRevoWidget::maxVarValue = 0.1;
|
||||
|
||||
|
@ -49,9 +49,8 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
|
||||
|
||||
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if(!settings->useExpertMode() || true)
|
||||
if(!settings->useExpertMode())
|
||||
m_stabilization->saveStabilizationToRAM_6->setVisible(false);
|
||||
m_stabilization->saveStabilizationToRAM_6->setVisible(true);
|
||||
|
||||
|
||||
|
||||
|
@ -1368,7 +1368,8 @@ channel value for each flight mode.</string>
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>After the time indicated here, the frame go back to disarmed state.</string>
|
||||
<string>After the time indicated here, the frame go back to disarmed state.
|
||||
Set to 0 to disable (recommended for soaring fixed wings).</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>64</number>
|
||||
@ -1378,7 +1379,7 @@ channel value for each flight mode.</string>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_19">
|
||||
<property name="text">
|
||||
<string>seconds.</string>
|
||||
<string>seconds (0 to disable).</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
|
@ -19,12 +19,14 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) :
|
||||
layout()->removeWidget(ui->legend3);
|
||||
layout()->removeWidget(ui->legend4);
|
||||
layout()->removeWidget(ui->legend5);
|
||||
layout()->removeWidget(ui->legend6);
|
||||
delete ui->legend0;
|
||||
delete ui->legend1;
|
||||
delete ui->legend2;
|
||||
delete ui->legend3;
|
||||
delete ui->legend4;
|
||||
delete ui->legend5;
|
||||
delete ui->legend6;
|
||||
|
||||
}
|
||||
|
||||
|
@ -236,83 +236,6 @@ font:bold;</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="7">
|
||||
<widget class="QLabel" name="legend5">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<italic>false</italic>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
font:bold;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="lineWidth">
|
||||
<number>1</number>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Max</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="8">
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>48</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="9">
|
||||
<spacer name="horizontalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>42</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="channelName">
|
||||
<property name="sizePolicy">
|
||||
@ -483,6 +406,144 @@ font:bold;</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="7">
|
||||
<widget class="QLabel" name="legend5">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<italic>false</italic>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:1px;
|
||||
font:bold;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="lineWidth">
|
||||
<number>1</number>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Max</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="9">
|
||||
<widget class="QCheckBox" name="channelRev">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Rev</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="10">
|
||||
<widget class="QSpinBox" name="channelResponseTime">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>30</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Optional input filter response time.
|
||||
|
||||
Range: 0-999ms, 0 disables filter (default).
|
||||
|
||||
Warning: this is an expert mode feature, mostly used for aerial video
|
||||
camera control (airframe yaw and camera gimbal accessory channels).
|
||||
Too high values for main controls can cause undesirable effects and
|
||||
even lead to crash. Use with caution.</string>
|
||||
</property>
|
||||
<property name="wrapping">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="buttonSymbols">
|
||||
<enum>QAbstractSpinBox::NoButtons</enum>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="10">
|
||||
<widget class="QLabel" name="legend6">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>30</width>
|
||||
<height>26</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<italic>false</italic>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
margin:5px;
|
||||
font:bold;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RT</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="8">
|
||||
<widget class="QLabel" name="neutral">
|
||||
<property name="sizePolicy">
|
||||
@ -508,22 +569,6 @@ font:bold;</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="9">
|
||||
<widget class="QCheckBox" name="channelRev">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Rev</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
<widget class="QSpinBox" name="channelNumber">
|
||||
<property name="enabled">
|
||||
@ -552,7 +597,6 @@ font:bold;</string>
|
||||
<tabstop>channelMin</tabstop>
|
||||
<tabstop>channelNeutral</tabstop>
|
||||
<tabstop>channelMax</tabstop>
|
||||
<tabstop>channelRev</tabstop>
|
||||
</tabstops>
|
||||
<resources/>
|
||||
<connections/>
|
||||
|
@ -4,9 +4,9 @@ Without the work of the people in this file OpenPilot would not be what it is to
|
||||
|
||||
<p>It is sorted alphabetically by name</p>
|
||||
|
||||
<pre>
|
||||
Connor Abbott
|
||||
<pre>Connor Abbott
|
||||
David Ankers
|
||||
Sergiy Anikeyev
|
||||
Pedro Assuncao
|
||||
Fredrik Arvidsson
|
||||
Werner Backes
|
||||
@ -16,6 +16,7 @@ David Carlson
|
||||
James Cotton
|
||||
Steve Doll
|
||||
Piotr Esden-Tempski
|
||||
Richard Flay
|
||||
Peter Farnworth
|
||||
Ed Faulkner
|
||||
Darren Furniss
|
||||
@ -23,6 +24,7 @@ Frederic Goddeeris
|
||||
Daniel Godin
|
||||
Bani Greyling
|
||||
Nuno Guedes
|
||||
Erik Gustavsson
|
||||
Peter Gunnarsson
|
||||
Dean Hall
|
||||
Joe Hlebasko
|
||||
@ -43,6 +45,7 @@ Ken Northup
|
||||
Greg Matthews
|
||||
Guy McCaldin
|
||||
Gary Mortimer
|
||||
Alessio Morale
|
||||
Cathy Moss
|
||||
Angus Peart
|
||||
Dmytro Poplavskiy
|
||||
@ -72,6 +75,7 @@ Brian Webb
|
||||
Justin Welander
|
||||
Mat Wellington
|
||||
Kendal Wells
|
||||
Dmitriy Zaitsev
|
||||
</pre>
|
||||
|
||||
</html>
|
||||
|
@ -35,8 +35,6 @@ namespace Constants {
|
||||
#define GCS_VERSION_MAJOR 1
|
||||
#define GCS_VERSION_MINOR 0
|
||||
#define GCS_VERSION_RELEASE 0
|
||||
const char * const GCS_VERSION_TYPE = "Alpha";
|
||||
const char * const GCS_VERSION_CODENAME = "Pascal";
|
||||
|
||||
#define STRINGIFY_INTERNAL(x) #x
|
||||
#define STRINGIFY(x) STRINGIFY_INTERNAL(x)
|
||||
@ -46,18 +44,34 @@ const char * const GCS_VERSION_CODENAME = "Pascal";
|
||||
"." STRINGIFY(GCS_VERSION_RELEASE)
|
||||
|
||||
const char * const GCS_VERSION_LONG = GCS_VERSION;
|
||||
const char * const GCS_AUTHOR = "OpenPilot Project";
|
||||
const char * const GCS_YEAR = "2012";
|
||||
|
||||
const char * const GCS_HELP = "http://wiki.openpilot.org";
|
||||
#ifdef GCS_REVISION
|
||||
const char * const GCS_REVISION_STR = STRINGIFY(GCS_REVISION);
|
||||
const char * const GCS_REVISION_STR = GCS_REVISION;
|
||||
#else
|
||||
const char * const GCS_REVISION_STR = "N/A";
|
||||
#endif
|
||||
|
||||
#ifdef GCS_YEAR
|
||||
const char * const GCS_YEAR_STR = GCS_YEAR;
|
||||
#else
|
||||
const char * const GCS_YEAR_STR = "2013";
|
||||
#endif
|
||||
|
||||
#ifdef GCS_ORIGIN
|
||||
const char * const GCS_ORIGIN_STR = GCS_ORIGIN;
|
||||
#else
|
||||
const char * const GCS_ORIGIN_STR = "unknown repository";
|
||||
#endif
|
||||
|
||||
#ifdef UAVO_HASH
|
||||
const char * const UAVOSHA1_STR = STRINGIFY(UAVO_HASH);
|
||||
#else
|
||||
const char * const GCS_REVISION_STR = "";
|
||||
const char * const UAVOSHA1_STR = "";
|
||||
#endif
|
||||
|
||||
const char * const GCS_AUTHOR = "The OpenPilot Project";
|
||||
const char * const GCS_HELP = "http://wiki.openpilot.org";
|
||||
|
||||
#undef GCS_VERSION
|
||||
#undef STRINGIFY
|
||||
#undef STRINGIFY_INTERNAL
|
||||
|
@ -142,5 +142,3 @@ unix:!macx {
|
||||
INSTALLS += images
|
||||
}
|
||||
OTHER_FILES += Core.pluginspec
|
||||
|
||||
include(gcsversioninfo.pri)
|
||||
|
@ -10,47 +10,47 @@ importSettings::importSettings(QWidget *parent) :
|
||||
ui(new Ui::importSettings)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
connect(ui->cbConfigs,SIGNAL(currentIndexChanged(int)),this,SLOT(updateDetails(int)));
|
||||
connect(ui->btnLoad,SIGNAL(clicked()),this,SLOT(accept()));
|
||||
QTimer::singleShot(500,this,SLOT(repaint()));
|
||||
connect(ui->cbConfigs, SIGNAL(currentIndexChanged(int)), this, SLOT(updateDetails(int)));
|
||||
connect(ui->btnLoad, SIGNAL(clicked()), this, SLOT(accept()));
|
||||
QTimer::singleShot(500, this, SLOT(repaint()));
|
||||
}
|
||||
|
||||
void importSettings::loadFiles(QString path)
|
||||
{
|
||||
QDir myDir(path);
|
||||
QStringList filters;
|
||||
filters << "*.xml";
|
||||
QStringList list = myDir.entryList(filters,QDir::Files);
|
||||
int x=0;
|
||||
foreach(QString fileStr, list)
|
||||
{
|
||||
fileInfo * info=new fileInfo;
|
||||
QSettings settings(path+QDir::separator()+fileStr, XmlConfig::XmlSettingsFormat);
|
||||
int x = 0;
|
||||
foreach(QString fileStr, list) {
|
||||
fileInfo *info = new fileInfo;
|
||||
QSettings settings(path+QDir::separator() + fileStr, XmlConfig::XmlSettingsFormat);
|
||||
settings.beginGroup("General");
|
||||
info->description=settings.value("Description","None").toString();
|
||||
info->details=settings.value("Details","None").toString();
|
||||
info->description = settings.value("Description", "None").toString();
|
||||
info->details = settings.value("Details", "None").toString();
|
||||
settings.endGroup();
|
||||
info->file=path+QDir::separator()+fileStr;
|
||||
info->file = path + QDir::separator() + fileStr;
|
||||
configList.insert(x,info);
|
||||
ui->cbConfigs->addItem(info->description,x);
|
||||
ui->cbConfigs->addItem(info->description, x);
|
||||
++x;
|
||||
}
|
||||
}
|
||||
|
||||
void importSettings::updateDetails(int index)
|
||||
{
|
||||
fileInfo * info=configList.value(ui->cbConfigs->itemData(index).toInt());
|
||||
fileInfo *info = configList.value(ui->cbConfigs->itemData(index).toInt());
|
||||
ui->lblDetails->setText(info->details);
|
||||
}
|
||||
|
||||
QString importSettings::choosenConfig()
|
||||
{
|
||||
fileInfo * info=configList.value(ui->cbConfigs->itemData(ui->cbConfigs->currentIndex()).toInt());
|
||||
fileInfo *info = configList.value(ui->cbConfigs->itemData(ui->cbConfigs->currentIndex()).toInt());
|
||||
return info->file;
|
||||
}
|
||||
|
||||
importSettings::~importSettings()
|
||||
{
|
||||
foreach(fileInfo * info,configList.values())
|
||||
{
|
||||
foreach(fileInfo * info,configList.values()) {
|
||||
delete info;
|
||||
}
|
||||
delete ui;
|
||||
|
@ -1,3 +1,4 @@
|
||||
|
||||
#ifndef IMPORTSETTINGS_H
|
||||
#define IMPORTSETTINGS_H
|
||||
|
||||
@ -10,8 +11,7 @@ class importSettings;
|
||||
class importSettings : public QDialog
|
||||
{
|
||||
Q_OBJECT
|
||||
struct fileInfo
|
||||
{
|
||||
struct fileInfo {
|
||||
QString file;
|
||||
QString description;
|
||||
QString details;
|
||||
@ -23,9 +23,11 @@ public:
|
||||
|
||||
void loadFiles(QString path);
|
||||
QString choosenConfig();
|
||||
|
||||
private:
|
||||
Ui::importSettings *ui;
|
||||
QMap<int,fileInfo*> configList;
|
||||
|
||||
private slots:
|
||||
void updateDetails(int);
|
||||
};
|
||||
|
@ -37,6 +37,7 @@
|
||||
#include <QtCore/QDebug>
|
||||
#include <QtCore/QSettings>
|
||||
#include <QtGui/QHeaderView>
|
||||
#include <QtGui/QLabel>
|
||||
#include <QtGui/QPushButton>
|
||||
|
||||
namespace {
|
||||
@ -91,10 +92,12 @@ SettingsDialog::SettingsDialog(QWidget *parent, const QString &categoryId,
|
||||
#endif
|
||||
QString initialCategory = categoryId;
|
||||
QString initialPage = pageId;
|
||||
qDebug() << "SettingsDialog constructor initial category: " << initialCategory << ", initial page: " << initialPage;
|
||||
if (initialCategory.isEmpty() && initialPage.isEmpty()) {
|
||||
QSettings *settings = ICore::instance()->settings();
|
||||
initialCategory = settings->value("General/LastPreferenceCategory", QVariant(QString())).toString();
|
||||
initialPage = settings->value("General/LastPreferencePage", QVariant(QString())).toString();
|
||||
qDebug() << "SettingsDialog settings initial category: " << initialCategory << ", initial page: " << initialPage;
|
||||
m_windowWidth = settings->value("General/SettingsWindowWidth", 0).toInt();
|
||||
m_windowHeight = settings->value("General/SettingsWindowHeight", 0).toInt();
|
||||
}
|
||||
@ -125,6 +128,7 @@ SettingsDialog::SettingsDialog(QWidget *parent, const QString &categoryId,
|
||||
|
||||
int index = 0;
|
||||
bool firstUavGadgetOptionsPageFound = false;
|
||||
QTreeWidgetItem *initialItem = 0;
|
||||
foreach (IOptionsPage *page, pages) {
|
||||
PageData pageData;
|
||||
pageData.index = index;
|
||||
@ -165,11 +169,15 @@ SettingsDialog::SettingsDialog(QWidget *parent, const QString &categoryId,
|
||||
categoryItemList->append(item);
|
||||
|
||||
m_pages.append(page);
|
||||
stackedPages->addWidget(page->createPage(stackedPages));
|
||||
|
||||
// creating all option pages upfront is slow, so we create place holder widgets instead
|
||||
// the real option page widget will be created later when the user selects it
|
||||
// the place holder is a QLabel and we assume that no option page will be a QLabel...
|
||||
QLabel * placeholderWidget = new QLabel(stackedPages);
|
||||
stackedPages->addWidget(placeholderWidget);
|
||||
|
||||
if (page->id() == initialPage && currentCategory == initialCategory) {
|
||||
stackedPages->setCurrentIndex(stackedPages->count());
|
||||
pageTree->setCurrentItem(item);
|
||||
initialItem = item;
|
||||
}
|
||||
|
||||
index++;
|
||||
@ -185,6 +193,15 @@ SettingsDialog::SettingsDialog(QWidget *parent, const QString &categoryId,
|
||||
}
|
||||
}
|
||||
|
||||
if (initialItem) {
|
||||
if (!initialItem->parent()) {
|
||||
// item has no parent, meaning it is single child
|
||||
// so select category item instead as single child are not added to the tree
|
||||
initialItem = categories.value(initialCategory);
|
||||
}
|
||||
pageTree->setCurrentItem(initialItem);
|
||||
}
|
||||
|
||||
QList<int> sizes;
|
||||
sizes << 150 << 300;
|
||||
splitter->setSizes(sizes);
|
||||
@ -199,6 +216,13 @@ SettingsDialog::~SettingsDialog()
|
||||
QList<QTreeWidgetItem *> *categoryItemList = m_categoryItemsMap.value(category);
|
||||
delete categoryItemList;
|
||||
}
|
||||
// delete place holders
|
||||
for (int i = 0; i < stackedPages->count(); i++) {
|
||||
QLabel * widget = dynamic_cast<QLabel*>(stackedPages->widget(i));
|
||||
if (widget) {
|
||||
delete widget;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void SettingsDialog::pageSelected()
|
||||
@ -211,6 +235,16 @@ void SettingsDialog::pageSelected()
|
||||
int index = data.index;
|
||||
m_currentCategory = data.category;
|
||||
m_currentPage = data.id;
|
||||
// check if we are looking at a place holder or not
|
||||
QWidget *widget = dynamic_cast<QLabel*>(stackedPages->widget(index));
|
||||
if (widget) {
|
||||
// place holder found, get rid of it...
|
||||
stackedPages->removeWidget(widget);
|
||||
delete widget;
|
||||
// and replace place holder with actual option page
|
||||
IOptionsPage *page = m_pages.at(index);
|
||||
stackedPages->insertWidget(index, page->createPage(stackedPages));
|
||||
}
|
||||
stackedPages->setCurrentIndex(index);
|
||||
// If user selects a toplevel item, select the first child for them
|
||||
// I.e. Top level items are not really selectable
|
||||
@ -297,26 +331,38 @@ void SettingsDialog::disableApplyOk(bool disable)
|
||||
void SettingsDialog::accept()
|
||||
{
|
||||
m_applied = true;
|
||||
foreach (IOptionsPage *page, m_pages) {
|
||||
page->apply();
|
||||
page->finish();
|
||||
for (int i = 0; i < m_pages.size(); i++) {
|
||||
QWidget * widget = dynamic_cast<QLabel*>(stackedPages->widget(i));
|
||||
if (!widget) {
|
||||
IOptionsPage * page = m_pages.at(i);
|
||||
page->apply();
|
||||
page->finish();
|
||||
}
|
||||
}
|
||||
done(QDialog::Accepted);
|
||||
}
|
||||
|
||||
void SettingsDialog::reject()
|
||||
{
|
||||
foreach (IOptionsPage *page, m_pages)
|
||||
page->finish();
|
||||
|
||||
for (int i = 0; i < m_pages.size(); i++) {
|
||||
QWidget * widget = dynamic_cast<QLabel*>(stackedPages->widget(i));
|
||||
if (!widget) {
|
||||
IOptionsPage * page = m_pages.at(i);
|
||||
page->finish();
|
||||
}
|
||||
}
|
||||
done(QDialog::Rejected);
|
||||
}
|
||||
|
||||
void SettingsDialog::apply()
|
||||
{
|
||||
foreach (IOptionsPage *page, m_pages)
|
||||
page->apply();
|
||||
|
||||
for (int i = 0; i < m_pages.size(); i++) {
|
||||
QWidget * widget = dynamic_cast<QLabel*>(stackedPages->widget(i));
|
||||
if (!widget) {
|
||||
IOptionsPage * page = m_pages.at(i);
|
||||
page->apply();
|
||||
}
|
||||
}
|
||||
m_applied = true;
|
||||
}
|
||||
|
||||
|
@ -266,18 +266,15 @@ void MainWindow::modeChanged(Core::IMode */*mode*/)
|
||||
|
||||
void MainWindow::extensionsInitialized()
|
||||
{
|
||||
|
||||
QSettings* qs = m_settings;
|
||||
QSettings * settings;
|
||||
QSettings *qs = m_settings;
|
||||
QSettings *settings;
|
||||
QString commandLine;
|
||||
if ( ! qs->allKeys().count() ){
|
||||
foreach(QString str,qApp->arguments())
|
||||
{
|
||||
if(str.contains("configfile"))
|
||||
{
|
||||
qDebug()<<"ass";
|
||||
commandLine=str.split("=").at(1);
|
||||
qDebug()<<commandLine;
|
||||
if ( ! qs->allKeys().count() ) {
|
||||
foreach(QString str, qApp->arguments()) {
|
||||
if(str.contains("configfile")) {
|
||||
qDebug() << "ass";
|
||||
commandLine = str.split("=").at(1);
|
||||
qDebug() << commandLine;
|
||||
}
|
||||
}
|
||||
QDir directory(QCoreApplication::applicationDirPath());
|
||||
@ -289,37 +286,34 @@ void MainWindow::extensionsInitialized()
|
||||
directory.cd("share");
|
||||
directory.cd("openpilotgcs");
|
||||
#endif
|
||||
directory.cd("default_configurations");
|
||||
directory.cd("default_configurations");
|
||||
|
||||
qDebug() << "Looking for default config files in: " + directory.absolutePath();
|
||||
bool showDialog=true;
|
||||
qDebug() << "Looking for default config files in: " + directory.absolutePath();
|
||||
bool showDialog = true;
|
||||
QString filename;
|
||||
if(!commandLine.isEmpty())
|
||||
{
|
||||
if(QFile::exists(directory.absolutePath()+QDir::separator()+commandLine))
|
||||
{
|
||||
filename=directory.absolutePath()+QDir::separator()+commandLine;
|
||||
qDebug()<<"Load configuration from command line";
|
||||
settings=new QSettings(filename, XmlConfig::XmlSettingsFormat);
|
||||
showDialog=false;
|
||||
if(!commandLine.isEmpty()) {
|
||||
if(QFile::exists(directory.absolutePath() + QDir::separator()+commandLine)) {
|
||||
filename = directory.absolutePath() + QDir::separator()+commandLine;
|
||||
qDebug() << "Load configuration from command line";
|
||||
settings = new QSettings(filename, XmlConfig::XmlSettingsFormat);
|
||||
showDialog = false;
|
||||
}
|
||||
}
|
||||
if(showDialog)
|
||||
{
|
||||
importSettings * dialog=new importSettings(this);
|
||||
if(showDialog) {
|
||||
importSettings *dialog = new importSettings(this);
|
||||
dialog->loadFiles(directory.absolutePath());
|
||||
dialog->exec();
|
||||
filename=dialog->choosenConfig();
|
||||
settings=new QSettings(filename, XmlConfig::XmlSettingsFormat);
|
||||
filename = dialog->choosenConfig();
|
||||
settings = new QSettings(filename, XmlConfig::XmlSettingsFormat);
|
||||
delete dialog;
|
||||
}
|
||||
qs=settings;
|
||||
qDebug() << "Load default config from resource "<<filename;
|
||||
qs = settings;
|
||||
qDebug() << "Load default config from resource " << filename;
|
||||
}
|
||||
qs->beginGroup("General");
|
||||
m_config_description=qs->value("Description","none").toString();
|
||||
m_config_details=qs->value("Details","none").toString();
|
||||
m_config_stylesheet=qs->value("StyleSheet","none").toString();
|
||||
m_config_description=qs->value("Description", "none").toString();
|
||||
m_config_details=qs->value("Details", "none").toString();
|
||||
m_config_stylesheet=qs->value("StyleSheet", "none").toString();
|
||||
loadStyleSheet(m_config_stylesheet);
|
||||
qs->endGroup();
|
||||
m_uavGadgetInstanceManager = new UAVGadgetInstanceManager(this);
|
||||
@ -799,16 +793,6 @@ void MainWindow::registerDefaultActions()
|
||||
mhelp->addAction(cmd, Constants::G_HELP_ABOUT);
|
||||
#endif
|
||||
|
||||
//About Plugins Action
|
||||
tmpaction = new QAction(QIcon(Constants::ICON_PLUGIN), tr("About &Plugins..."), this);
|
||||
cmd = am->registerAction(tmpaction, Constants::ABOUT_PLUGINS, m_globalContext);
|
||||
mhelp->addAction(cmd, Constants::G_HELP_ABOUT);
|
||||
tmpaction->setEnabled(true);
|
||||
#ifdef Q_WS_MAC
|
||||
cmd->action()->setMenuRole(QAction::ApplicationSpecificRole);
|
||||
#endif
|
||||
connect(tmpaction, SIGNAL(triggered()), this, SLOT(aboutPlugins()));
|
||||
|
||||
// About GCS Action
|
||||
#ifdef Q_WS_MAC
|
||||
tmpaction = new QAction(QIcon(Constants::ICON_OPENPILOT), tr("About &OpenPilot GCS"), this); // it's convention not to add dots to the about menu
|
||||
@ -823,6 +807,16 @@ void MainWindow::registerDefaultActions()
|
||||
#endif
|
||||
connect(tmpaction, SIGNAL(triggered()), this, SLOT(aboutOpenPilotGCS()));
|
||||
|
||||
//About Plugins Action
|
||||
tmpaction = new QAction(QIcon(Constants::ICON_PLUGIN), tr("About &Plugins..."), this);
|
||||
cmd = am->registerAction(tmpaction, Constants::ABOUT_PLUGINS, m_globalContext);
|
||||
mhelp->addAction(cmd, Constants::G_HELP_ABOUT);
|
||||
tmpaction->setEnabled(true);
|
||||
#ifdef Q_WS_MAC
|
||||
cmd->action()->setMenuRole(QAction::ApplicationSpecificRole);
|
||||
#endif
|
||||
connect(tmpaction, SIGNAL(triggered()), this, SLOT(aboutPlugins()));
|
||||
|
||||
//Credits Action
|
||||
tmpaction = new QAction(QIcon(Constants::ICON_PLUGIN), tr("About &Authors..."), this);
|
||||
cmd = am->registerAction(tmpaction, Constants::ABOUT_AUTHORS, m_globalContext);
|
||||
|
@ -239,8 +239,9 @@ void UAVGadgetInstanceManager::createOptionsPages()
|
||||
m_pm->removeObject(m_optionsPages.takeLast());
|
||||
}
|
||||
|
||||
foreach (IUAVGadgetConfiguration *config, m_configurations)
|
||||
{
|
||||
QMutableListIterator<IUAVGadgetConfiguration*> ite(m_configurations);
|
||||
while (ite.hasNext()) {
|
||||
IUAVGadgetConfiguration *config = ite.next();
|
||||
IUAVGadgetFactory *f = factory(config->classId());
|
||||
IOptionsPage *p = f->createOptionsPage(config);
|
||||
if (p) {
|
||||
@ -249,6 +250,14 @@ void UAVGadgetInstanceManager::createOptionsPages()
|
||||
m_optionsPages.append(page);
|
||||
m_pm->addObject(page);
|
||||
}
|
||||
else {
|
||||
qWarning()
|
||||
<< "UAVGadgetInstanceManager::createOptionsPages - failed to create options page for configuration "
|
||||
+ config->classId() + ":" + config->name() + ", configuration will be removed.";
|
||||
// The m_optionsPages list and m_configurations list must be in synch otherwise nasty issues happen later
|
||||
// so if we fail to create an options page we must remove the associated configuration
|
||||
ite.remove();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -59,16 +59,7 @@ VersionDialog::VersionDialog(QWidget *parent)
|
||||
QGridLayout *layout = new QGridLayout(this);
|
||||
layout->setSizeConstraint(QLayout::SetFixedSize);
|
||||
|
||||
QString version = QLatin1String(GCS_VERSION_LONG);
|
||||
version += QDate(2007, 25, 10).toString(Qt::SystemLocaleDate);
|
||||
|
||||
QString ideRev;
|
||||
#ifdef GCS_REVISION
|
||||
//: This gets conditionally inserted as argument %8 into the description string.
|
||||
ideRev = tr("From revision %1<br/>").arg(QString::fromLatin1(GCS_REVISION_STR).left(60));
|
||||
#endif
|
||||
QString uavoHashStr;
|
||||
#ifdef UAVO_HASH
|
||||
#ifdef UAVO_HASH
|
||||
//: This gets conditionally inserted as argument %11 into the description string.
|
||||
QByteArray uavoHashArray;
|
||||
QString uavoHash = QString::fromLatin1(Core::Constants::UAVOSHA1_STR);
|
||||
@ -85,31 +76,41 @@ VersionDialog::VersionDialog(QWidget *parent)
|
||||
{
|
||||
gcsUavoHashStr.append(QString::number(i,16).right(2));
|
||||
}
|
||||
uavoHashStr = tr("UAVO hash %1<br/>").arg(gcsUavoHashStr);
|
||||
#endif
|
||||
QString uavoHashStr = gcsUavoHashStr;
|
||||
#else
|
||||
QString uavoHashStr = "N/A";
|
||||
#endif
|
||||
|
||||
const QString description = tr(
|
||||
"<h3>OpenPilot GCS %1 %9 (%10)</h3>"
|
||||
"Based on Qt %2 (%3 bit)<br/>"
|
||||
"<h3>OpenPilot Ground Control Station</h3>"
|
||||
"GCS Revision: <b>%1</b><br/>"
|
||||
"UAVO Hash: %2<br/>"
|
||||
"<br/>"
|
||||
"Built on %4 at %5<br />"
|
||||
"Built from %3<br/>"
|
||||
"Built on %4 at %5<br/>"
|
||||
"Based on Qt %6 (%7 bit)<br/>"
|
||||
"<br/>"
|
||||
"%8"
|
||||
"© %8, 2010-%9. All rights reserved.<br/>"
|
||||
"<br/>"
|
||||
"%11"
|
||||
"<small>This program is free software; you can redistribute it and/or modify<br/>"
|
||||
"it under the terms of the GNU General Public License as published by<br/>"
|
||||
"the Free Software Foundation; either version 3 of the License, or<br/>"
|
||||
"(at your option) any later version.<br/>"
|
||||
"<br/>"
|
||||
"Copyright 2010-%6 %7. All rights reserved.<br/>"
|
||||
"<br/>"
|
||||
"<small>This program is free software; you can redistribute it and/or modify<br/>"
|
||||
"it under the terms of the GNU General Public License as published by<br/>"
|
||||
"the Free Software Foundation; either version 3 of the License, or<br/>"
|
||||
"(at your option) any later version.<br/><br/>"
|
||||
"The program is provided AS IS with NO WARRANTY OF ANY KIND, "
|
||||
"INCLUDING THE WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A "
|
||||
"PARTICULAR PURPOSE.</small><br/>")
|
||||
.arg(version, QLatin1String(QT_VERSION_STR), QString::number(QSysInfo::WordSize),
|
||||
QLatin1String(__DATE__), QLatin1String(__TIME__), QLatin1String(GCS_YEAR),
|
||||
(QLatin1String(GCS_AUTHOR)), ideRev).arg(QLatin1String(GCS_VERSION_TYPE), QLatin1String(GCS_VERSION_CODENAME), uavoHashStr);
|
||||
"PARTICULAR PURPOSE.</small>"
|
||||
).arg(
|
||||
QString::fromLatin1(GCS_REVISION_STR).left(60), // %1
|
||||
uavoHashStr, // %2
|
||||
QLatin1String(GCS_ORIGIN_STR), // $3
|
||||
QLatin1String(__DATE__), // %4
|
||||
QLatin1String(__TIME__), // %5
|
||||
QLatin1String(QT_VERSION_STR), // %6
|
||||
QString::number(QSysInfo::WordSize), // %7
|
||||
QLatin1String(GCS_AUTHOR), // %8
|
||||
QLatin1String(GCS_YEAR_STR) // %9
|
||||
);
|
||||
|
||||
QLabel *copyRightLabel = new QLabel(description);
|
||||
copyRightLabel->setWordWrap(true);
|
||||
|
@ -62,7 +62,7 @@ equals(copydata, 1) {
|
||||
libgcc_s_dw2-1.dll \
|
||||
mingwm10.dll
|
||||
for(dll, MINGW_DLLS) {
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../../../../mingw/bin/$$dll\") $$targetPath(\"$$SIM_DIR/$$dll\") $$addNewline()
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(QTMINGW)/$$dll\") $$targetPath(\"$$SIM_DIR/$$dll\") $$addNewline()
|
||||
}
|
||||
|
||||
data_copy.target = FORCE
|
||||
|
@ -199,8 +199,7 @@ void ImportExportGadgetWidget::importConfiguration(const QString& fileName)
|
||||
|
||||
void ImportExportGadgetWidget::on_helpButton_clicked()
|
||||
{
|
||||
qDebug() << "Show Help";
|
||||
QDesktopServices::openUrl(QUrl("http://wiki.openpilot.org/Import_Export_plugin"));
|
||||
QDesktopServices::openUrl(QUrl("http://wiki.openpilot.org/x/OQBj"));
|
||||
}
|
||||
|
||||
|
||||
|
@ -114,7 +114,7 @@ void ModelViewGadgetWidget::initializeGL()
|
||||
m_Light.setAmbientColor(Qt::lightGray);
|
||||
|
||||
m_GlView.cameraHandle()->setDefaultUpVector(glc::Z_AXIS);
|
||||
m_GlView.cameraHandle()->setFrontView();
|
||||
m_GlView.cameraHandle()->setRearView();
|
||||
m_GlView.setToOrtho(true); // orthogonal view
|
||||
|
||||
glEnable(GL_NORMALIZE);
|
||||
|
@ -1,5 +1,9 @@
|
||||
QT += xml
|
||||
TEMPLATE = lib
|
||||
PATHPLANNER {
|
||||
DEFINES += USE_PATHPLANNER
|
||||
}
|
||||
|
||||
TARGET = OPMapGadget
|
||||
include(../../openpilotgcsplugin.pri)
|
||||
include(../../plugins/coreplugin/coreplugin.pri)
|
||||
|
@ -54,6 +54,7 @@
|
||||
#include "attitudeactual.h"
|
||||
#include "positionactual.h"
|
||||
#include "velocityactual.h"
|
||||
#include "airspeedactual.h"
|
||||
|
||||
#define allow_manual_home_location_move
|
||||
|
||||
@ -587,16 +588,21 @@ void OPMapGadgetWidget::updatePosition()
|
||||
AttitudeActual *attitudeActualObj = AttitudeActual::GetInstance(obm);
|
||||
PositionActual *positionActualObj = PositionActual::GetInstance(obm);
|
||||
VelocityActual *velocityActualObj = VelocityActual::GetInstance(obm);
|
||||
AirspeedActual *airspeedActualObj = AirspeedActual::GetInstance(obm);
|
||||
|
||||
Gyros *gyrosObj = Gyros::GetInstance(obm);
|
||||
|
||||
Q_ASSERT(attitudeActualObj);
|
||||
Q_ASSERT(positionActualObj);
|
||||
Q_ASSERT(velocityActualObj);
|
||||
Q_ASSERT(airspeedActualObj);
|
||||
Q_ASSERT(gyrosObj);
|
||||
|
||||
AttitudeActual::DataFields attitudeActualData = attitudeActualObj->getData();
|
||||
PositionActual::DataFields positionActualData = positionActualObj->getData();
|
||||
VelocityActual::DataFields velocityActualData = velocityActualObj->getData();
|
||||
AirspeedActual::DataFields airspeedActualData = airspeedActualObj->getData();
|
||||
|
||||
Gyros::DataFields gyrosData = gyrosObj->getData();
|
||||
|
||||
double NED[3]={positionActualData.North, positionActualData.East, positionActualData.Down};
|
||||
@ -604,7 +610,7 @@ void OPMapGadgetWidget::updatePosition()
|
||||
|
||||
//Set the position and heading estimates in the painter module
|
||||
m_map->UAV->SetNED(NED);
|
||||
m_map->UAV->SetCAS(-1); //THIS NEEDS TO BECOME AIRSPEED, ONCE WE SETTLE ON A UAVO
|
||||
m_map->UAV->SetCAS(airspeedActualData.CalibratedAirspeed);
|
||||
m_map->UAV->SetGroundspeed(vNED, m_maxUpdateRate);
|
||||
|
||||
//Convert angular velocities into a rotationg rate around the world-frame yaw axis. This is found by simply taking the dot product of the angular Euler-rate matrix with the angular rates.
|
||||
|
@ -265,7 +265,7 @@ void OsgViewerWidget::paintEvent( QPaintEvent* event )
|
||||
double homeLLA[3] = {homeLocation.Latitude / 10.0e6, homeLocation.Longitude / 10.0e6, homeLocation.Altitude};
|
||||
|
||||
double LLA[3];
|
||||
CoordinateConversions().GetLLA(homeLLA, NED, LLA);
|
||||
CoordinateConversions().NED2LLA_HomeLLA(homeLLA, NED, LLA);
|
||||
uavPos->getLocator()->setPosition( osg::Vec3d(LLA[1], LLA[0], LLA[2]) ); // Note this takes longtitude first
|
||||
} else {
|
||||
GPSPosition *gpsPosObj = GPSPosition::GetInstance(objMngr);
|
||||
|
@ -128,11 +128,11 @@ void PFDGadgetWidget::connectNeedles() {
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
|
||||
airspeedObj = dynamic_cast<UAVDataObject*>(objManager->getObject("BaroAirspeed"));
|
||||
airspeedObj = dynamic_cast<UAVDataObject*>(objManager->getObject("AirspeedActual"));
|
||||
if (airspeedObj != NULL ) {
|
||||
connect(airspeedObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateAirspeed(UAVObject*)));
|
||||
connect(airspeedObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateAirspeed(UAVObject*)));
|
||||
} else {
|
||||
qDebug() << "Error: Object is unknown (BaroAirspeed).";
|
||||
qDebug() << "Error: Object is unknown (AirspeedActual).";
|
||||
}
|
||||
|
||||
groundspeedObj = dynamic_cast<UAVDataObject*>(objManager->getObject("VelocityActual"));
|
||||
@ -323,10 +323,10 @@ void PFDGadgetWidget::updateGroundspeed(UAVObject *object) {
|
||||
|
||||
|
||||
/*!
|
||||
\brief Called by updates to @BaroAirspeed
|
||||
\brief Called by updates to @AirspeedActual
|
||||
*/
|
||||
void PFDGadgetWidget::updateAirspeed(UAVObject *object) {
|
||||
UAVObjectField* airspeedField = object->getField("CalibratedAirspeed");
|
||||
UAVObjectField* airspeedField = object->getField("CalibratedAirspeed");
|
||||
if (airspeedField) {
|
||||
airspeedTarget = airspeedField->getDouble();
|
||||
|
||||
@ -1007,31 +1007,31 @@ void PFDGadgetWidget::moveNeedles()
|
||||
//////
|
||||
if (groundspeedValue != groundspeedTarget) {
|
||||
groundspeedValue = groundspeedTarget;
|
||||
// qreal x = m_speedscale->transform().dx();
|
||||
// //opd = QPointF(x,fmod(groundspeedValue,speedScaleHeight/6));
|
||||
// // fmod does rounding errors!! the formula below works better:
|
||||
// QPointF opd = QPointF(x,groundspeedValue-floor(groundspeedValue/speedScaleHeight*6)*speedScaleHeight/6);
|
||||
// m_speedscale->setTransform(QTransform::fromTranslate(opd.x(),opd.y()), false);
|
||||
qreal x = m_speedscale->transform().dx();
|
||||
//opd = QPointF(x,fmod(groundspeedValue,speedScaleHeight/6));
|
||||
// fmod does rounding errors!! the formula below works better:
|
||||
QPointF opd = QPointF(x,groundspeedValue-floor(groundspeedValue/speedScaleHeight*6)*speedScaleHeight/6);
|
||||
m_speedscale->setTransform(QTransform::fromTranslate(opd.x(),opd.y()), false);
|
||||
|
||||
// double speedText = groundspeedValue/speedScaleHeight*30;
|
||||
// QString s = QString().sprintf("%.0f",speedText);
|
||||
// m_speedtext->setPlainText(s);
|
||||
double speedText = groundspeedValue/speedScaleHeight*30;
|
||||
QString s = QString().sprintf("%.0f",speedText);
|
||||
m_speedtext->setPlainText(s);
|
||||
|
||||
// // Now update the text elements inside the scale:
|
||||
// // (Qt documentation states that the list has the same order
|
||||
// // as the item add order in the QGraphicsItemGroup)
|
||||
// QList <QGraphicsItem *> textList = m_speedscale->childItems();
|
||||
// qreal val = 5*floor(groundspeedValue/speedScaleHeight*6)+20;
|
||||
// foreach( QGraphicsItem * item, textList) {
|
||||
// if (QGraphicsTextItem *text = qgraphicsitem_cast<QGraphicsTextItem *>(item)) {
|
||||
// QString s = (val<0) ? QString() : QString().sprintf("%.0f",val);
|
||||
// if (text->toPlainText() == s)
|
||||
// break; // This should happen at element one if is has not changed, indicating
|
||||
// // that it's not necessary to do the rest of the list
|
||||
// text->setPlainText(s);
|
||||
// val -= 5;
|
||||
// }
|
||||
// }
|
||||
// Now update the text elements inside the scale:
|
||||
// (Qt documentation states that the list has the same order
|
||||
// as the item add order in the QGraphicsItemGroup)
|
||||
QList <QGraphicsItem *> textList = m_speedscale->childItems();
|
||||
qreal val = 5*floor(groundspeedValue/speedScaleHeight*6)+20;
|
||||
foreach( QGraphicsItem * item, textList) {
|
||||
if (QGraphicsTextItem *text = qgraphicsitem_cast<QGraphicsTextItem *>(item)) {
|
||||
QString s = (val<0) ? QString() : QString().sprintf("%.0f",val);
|
||||
if (text->toPlainText() == s)
|
||||
break; // This should happen at element one if is has not changed, indicating
|
||||
// that it's not necessary to do the rest of the list
|
||||
text->setPlainText(s);
|
||||
val -= 5;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//////
|
||||
|
@ -150,12 +150,6 @@ plugin_pathactioneditor.depends = plugin_coreplugin
|
||||
plugin_pathactioneditor.depends += plugin_uavobjects
|
||||
SUBDIRS += plugin_pathactioneditor
|
||||
|
||||
# Waypoint Editor gadget
|
||||
plugin_waypointeditor.subdir = waypointeditor
|
||||
plugin_waypointeditor.depends = plugin_coreplugin
|
||||
plugin_waypointeditor.depends += plugin_uavobjects
|
||||
SUBDIRS += plugin_waypointeditor
|
||||
|
||||
# Primary Flight Display (PFD) gadget, QML version
|
||||
plugin_pfdqml.subdir = pfdqml
|
||||
plugin_pfdqml.depends = plugin_coreplugin
|
||||
|
@ -8,13 +8,14 @@
|
||||
|
||||
AutoUpdatePage::AutoUpdatePage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::AutoUpdatePage),m_wiz(wizard)
|
||||
ui(new Ui::AutoUpdatePage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Q_ASSERT(pm);
|
||||
UploaderGadgetFactory *uploader = pm->getObject<UploaderGadgetFactory>();
|
||||
Q_ASSERT(uploader);
|
||||
connect(ui->startUpdate,SIGNAL(clicked()), this, SLOT(disableButtons()));
|
||||
connect(ui->startUpdate,SIGNAL(clicked()),uploader,SIGNAL(autoUpdate()));
|
||||
connect(uploader,SIGNAL(autoUpdateSignal(uploader::AutoUpdateStep,QVariant)),this,SLOT(updateStatus(uploader::AutoUpdateStep,QVariant)));
|
||||
}
|
||||
@ -24,18 +25,30 @@ AutoUpdatePage::~AutoUpdatePage()
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void AutoUpdatePage::enableButtons(bool enable = false)
|
||||
{
|
||||
ui->startUpdate->setEnabled(enable);
|
||||
getWizard()->button(QWizard::NextButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::CancelButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::BackButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::CustomButton1)->setEnabled(enable);
|
||||
QApplication::processEvents();
|
||||
}
|
||||
|
||||
void AutoUpdatePage::updateStatus(uploader::AutoUpdateStep status, QVariant value)
|
||||
{
|
||||
switch(status)
|
||||
{
|
||||
case uploader::WAITING_DISCONNECT:
|
||||
m_wiz->setWindowFlags(m_wiz->windowFlags() & ~Qt::WindowStaysOnTopHint);
|
||||
getWizard()->setWindowFlags(getWizard()->windowFlags() & ~Qt::WindowStaysOnTopHint);
|
||||
disableButtons();
|
||||
ui->statusLabel->setText("Waiting for all OP boards to be disconnected");
|
||||
break;
|
||||
case uploader::WAITING_CONNECT:
|
||||
m_wiz->setWindowFlags(m_wiz->windowFlags() | Qt::WindowStaysOnTopHint);
|
||||
m_wiz->setWindowIcon(qApp->windowIcon());
|
||||
m_wiz->show();
|
||||
getWizard()->setWindowFlags(getWizard()->windowFlags() | Qt::WindowStaysOnTopHint);
|
||||
getWizard()->setWindowIcon(qApp->windowIcon());
|
||||
disableButtons();
|
||||
getWizard()->show();
|
||||
ui->statusLabel->setText("Please connect the board to the USB port (don't use external supply)");
|
||||
ui->levellinProgressBar->setValue(value.toInt());
|
||||
break;
|
||||
@ -57,12 +70,14 @@ void AutoUpdatePage::updateStatus(uploader::AutoUpdateStep status, QVariant valu
|
||||
ui->statusLabel->setText("Booting the board");
|
||||
break;
|
||||
case uploader::SUCCESS:
|
||||
enableButtons(true);
|
||||
ui->statusLabel->setText("Board Updated, please press the 'next' button below");
|
||||
break;
|
||||
case uploader::FAILURE:
|
||||
m_wiz->setWindowFlags(m_wiz->windowFlags() | Qt::WindowStaysOnTopHint);
|
||||
m_wiz->setWindowIcon(qApp->windowIcon());
|
||||
m_wiz->show();
|
||||
getWizard()->setWindowFlags(getWizard()->windowFlags() | Qt::WindowStaysOnTopHint);
|
||||
getWizard()->setWindowIcon(qApp->windowIcon());
|
||||
enableButtons(true);
|
||||
getWizard()->show();
|
||||
ui->statusLabel->setText("Something went wrong, you will have to manualy upgrade the board using the uploader plugin");
|
||||
break;
|
||||
}
|
||||
|
@ -49,10 +49,12 @@ public:
|
||||
|
||||
private slots:
|
||||
void updateStatus(uploader::AutoUpdateStep ,QVariant);
|
||||
void disableButtons(){ enableButtons(false); }
|
||||
void enableButtons(bool enable);
|
||||
|
||||
private:
|
||||
Ui::AutoUpdatePage *ui;
|
||||
SetupWizard * m_wiz;
|
||||
|
||||
};
|
||||
|
||||
#endif // AUTOUPDATEPAGE_H
|
||||
|
@ -57,13 +57,13 @@ p, li { white-space: pre-wrap; }
|
||||
<item>
|
||||
<widget class="QToolButton" name="startUpdate">
|
||||
<property name="toolTip">
|
||||
<string>Calculate gyro and accelerometer bias</string>
|
||||
<string>Upgrade now</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Calculate</string>
|
||||
<string>Upgrade</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
|
@ -123,7 +123,7 @@ void ControllerPage::setupBoardTypes()
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot CopterControl 3D"), SetupWizard::CONTROLLER_CC3D);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot Revolution"), SetupWizard::CONTROLLER_REVO);
|
||||
//ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(ui->boardTypeCombo->count() - 1, 0), v, Qt::UserRole - 1);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot PipX Radio Modem"), SetupWizard::CONTROLLER_PIPX);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot OPLink Radio Modem"), SetupWizard::CONTROLLER_PIPX);
|
||||
//ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(ui->boardTypeCombo->count() - 1, 0), v, Qt::UserRole - 1);
|
||||
}
|
||||
|
||||
|
@ -64,6 +64,7 @@ void LevellingPage::enableButtons(bool enable)
|
||||
getWizard()->button(QWizard::NextButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::CancelButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::BackButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::CustomButton1)->setEnabled(enable);
|
||||
QApplication::processEvents();
|
||||
}
|
||||
|
||||
|
@ -85,6 +85,7 @@ void SavePage::enableButtons(bool enable)
|
||||
getWizard()->button(QWizard::NextButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::CancelButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::BackButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::CustomButton1)->setEnabled(enable);
|
||||
QApplication::processEvents();
|
||||
}
|
||||
|
||||
|
@ -148,7 +148,7 @@ QString SetupWizard::getSummaryText()
|
||||
summary.append(tr("OpenPilot Revolution"));
|
||||
break;
|
||||
case CONTROLLER_PIPX:
|
||||
summary.append(tr("OpenPilot PipX Radio Modem"));
|
||||
summary.append(tr("OpenPilot OPLink Radio Modem"));
|
||||
break;
|
||||
default:
|
||||
summary.append(tr("Unknown"));
|
||||
|
@ -292,12 +292,12 @@ void VehicleConfigurationHelper::applyFlighModeConfiguration()
|
||||
|
||||
void VehicleConfigurationHelper::applyLevellingConfiguration()
|
||||
{
|
||||
AttitudeSettings* attitudeSettings = AttitudeSettings::GetInstance(m_uavoManager);
|
||||
Q_ASSERT(attitudeSettings);
|
||||
AttitudeSettings::DataFields data = attitudeSettings->getData();
|
||||
if(m_configSource->isLevellingPerformed())
|
||||
{
|
||||
accelGyroBias bias = m_configSource->getLevellingBias();
|
||||
AttitudeSettings* attitudeSettings = AttitudeSettings::GetInstance(m_uavoManager);
|
||||
Q_ASSERT(attitudeSettings);
|
||||
AttitudeSettings::DataFields data = attitudeSettings->getData();
|
||||
|
||||
data.AccelBias[0] += bias.m_accelerometerXBias;
|
||||
data.AccelBias[1] += bias.m_accelerometerYBias;
|
||||
@ -305,10 +305,10 @@ void VehicleConfigurationHelper::applyLevellingConfiguration()
|
||||
data.GyroBias[0] = -bias.m_gyroXBias;
|
||||
data.GyroBias[1] = -bias.m_gyroYBias;
|
||||
data.GyroBias[2] = -bias.m_gyroZBias;
|
||||
|
||||
attitudeSettings->setData(data);
|
||||
addModifiedObject(attitudeSettings, tr("Writing gyro and accelerometer bias settings"));
|
||||
}
|
||||
data.AccelTau = DEFAULT_ENABLED_ACCEL_TAU;
|
||||
attitudeSettings->setData(data);
|
||||
addModifiedObject(attitudeSettings, tr("Writing gyro and accelerometer bias settings"));
|
||||
}
|
||||
|
||||
void VehicleConfigurationHelper::applyStabilizationConfiguration()
|
||||
|
@ -68,6 +68,7 @@ private:
|
||||
static const int MIXER_TYPE_DISABLED = 0;
|
||||
static const int MIXER_TYPE_MOTOR = 1;
|
||||
static const int MIXER_TYPE_SERVO = 2;
|
||||
static const float DEFAULT_ENABLED_ACCEL_TAU = 0.1;
|
||||
|
||||
VehicleConfigurationSource *m_configSource;
|
||||
UAVObjectManager *m_uavoManager;
|
||||
|
@ -132,6 +132,7 @@ void UAVObjectBrowserWidget::useScientificNotation(bool scientific)
|
||||
|
||||
void UAVObjectBrowserWidget::sendUpdate()
|
||||
{
|
||||
this->setFocus();
|
||||
ObjectTreeItem *objItem = findCurrentObjectTreeItem();
|
||||
Q_ASSERT(objItem);
|
||||
objItem->apply();
|
||||
@ -165,6 +166,7 @@ ObjectTreeItem *UAVObjectBrowserWidget::findCurrentObjectTreeItem()
|
||||
|
||||
void UAVObjectBrowserWidget::saveObject()
|
||||
{
|
||||
this->setFocus();
|
||||
// Send update so that the latest value is saved
|
||||
sendUpdate();
|
||||
// Save object
|
||||
|
@ -22,7 +22,7 @@ public:
|
||||
return QString("OpenPilot INS");
|
||||
break;
|
||||
case 0x0301://PipX
|
||||
return QString("PipXtreme");
|
||||
return QString("OPLink");
|
||||
break;
|
||||
case 0x0401://Coptercontrol
|
||||
return QString("CopterControl");
|
||||
@ -33,10 +33,11 @@ public:
|
||||
return QString("CopterControl");
|
||||
break;
|
||||
case 0x0901://Revolution
|
||||
// It would be nice to say CC3D here but since currently we use string comparisons
|
||||
// for firmware compatibility and the filename path that would break
|
||||
return QString("Revolution");
|
||||
break;
|
||||
case 0x0903://Revomini
|
||||
return QString("Revomini");
|
||||
break;
|
||||
default:
|
||||
return QString("");
|
||||
break;
|
||||
|
@ -87,25 +87,6 @@ UAVSettingsImportExportFactory::UAVSettingsImportExportFactory(QObject *parent):
|
||||
cmd->action()->setText(tr("Export UAV Data..."));
|
||||
ac->addAction(cmd, Core::Constants::G_HELP_HELP);
|
||||
connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVData()));
|
||||
|
||||
ac = am->actionContainer(Core::Constants::M_FILE);
|
||||
cmd = am->registerAction(new QAction(this),
|
||||
"UAVSettingsImportExportPlugin.UAVWaypointsExport",
|
||||
QList<int>() <<
|
||||
Core::Constants::C_GLOBAL_ID);
|
||||
cmd->action()->setText(tr("Export Waypoints..."));
|
||||
ac->addAction(cmd, Core::Constants::G_FILE_SAVE);
|
||||
connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportWaypoints()));
|
||||
|
||||
ac = am->actionContainer(Core::Constants::M_FILE);
|
||||
cmd = am->registerAction(new QAction(this),
|
||||
"UAVSettingsImportExportPlugin.UAVWaypointsImport",
|
||||
QList<int>() <<
|
||||
Core::Constants::C_GLOBAL_ID);
|
||||
cmd->action()->setText(tr("Import Waypoints..."));
|
||||
ac->addAction(cmd, Core::Constants::G_FILE_SAVE);
|
||||
connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(importWaypoints()));
|
||||
|
||||
}
|
||||
|
||||
// Slot called by the menu manager on user action
|
||||
@ -232,125 +213,6 @@ void UAVSettingsImportExportFactory::importUAVSettings()
|
||||
swui.exec();
|
||||
}
|
||||
|
||||
|
||||
// Slot called by the menu manager on user action
|
||||
void UAVSettingsImportExportFactory::importWaypoints()
|
||||
{
|
||||
// ask for file name
|
||||
QString fileName;
|
||||
QString filters = tr("Waypoint XML files (*.xml)");
|
||||
fileName = QFileDialog::getOpenFileName(0, tr("Import waypoints"), "", filters);
|
||||
if (fileName.isEmpty()) {
|
||||
return;
|
||||
}
|
||||
|
||||
// Now open the file
|
||||
QFile file(fileName);
|
||||
QDomDocument doc("UAVObjects");
|
||||
file.open(QFile::ReadOnly|QFile::Text);
|
||||
if (!doc.setContent(file.readAll())) {
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("File Parsing Failed."));
|
||||
msgBox.setInformativeText(tr("This file is not a correct XML file"));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
return;
|
||||
}
|
||||
file.close();
|
||||
|
||||
// find the root of settings subtree
|
||||
emit importAboutToBegin();
|
||||
qDebug()<<"Import about to begin";
|
||||
|
||||
QDomElement root = doc.documentElement();
|
||||
if (root.tagName() == "uavobjects") {
|
||||
root = root.firstChildElement("waypoints");
|
||||
}
|
||||
if (root.isNull() || (root.tagName() != "waypoints")) {
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Wrong file contents"));
|
||||
msgBox.setInformativeText(tr("This file does not contain waypoints"));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
return;
|
||||
}
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
|
||||
QDomNode node = root.firstChild();
|
||||
while (!node.isNull()) {
|
||||
QDomElement e = node.toElement();
|
||||
if (e.tagName() == "object") {
|
||||
|
||||
// - Read each object
|
||||
QString uavObjectName = e.attribute("name");
|
||||
uint uavObjectID = e.attribute("id").toUInt(NULL,16);
|
||||
uint instId = e.attribute("instId").toUInt(NULL,10);
|
||||
|
||||
// Sanity Check:
|
||||
UAVDataObject * obj = dynamic_cast<UAVDataObject*>(objManager->getObject(uavObjectName));
|
||||
if (obj == NULL) {
|
||||
// This object is unknown!
|
||||
qDebug() << "Object unknown:" << uavObjectName << uavObjectID;
|
||||
} else {
|
||||
|
||||
int numInstances = objManager->getNumInstances(obj->getObjID());
|
||||
if (instId >= numInstances) {
|
||||
obj = obj->clone(instId);
|
||||
objManager->registerObject(obj);
|
||||
qDebug() << "Cloned new object";
|
||||
} else {
|
||||
obj = dynamic_cast<UAVDataObject*>(objManager->getObject(uavObjectName, instId));
|
||||
Q_ASSERT(obj);
|
||||
qDebug() << "Setting existing object";
|
||||
}
|
||||
|
||||
// - Update each field
|
||||
// - Issue and "updated" command
|
||||
bool error = false;
|
||||
bool setError = false;
|
||||
QDomNode field = node.firstChild();
|
||||
while(!field.isNull()) {
|
||||
QDomElement f = field.toElement();
|
||||
if (f.tagName() == "field") {
|
||||
UAVObjectField *uavfield = obj->getField(f.attribute("name"));
|
||||
if (uavfield) {
|
||||
QStringList list = f.attribute("values").split(",");
|
||||
if (list.length() == 1) {
|
||||
if (false == uavfield->checkValue(f.attribute("values"))) {
|
||||
qDebug() << "checkValue returned false on: " << uavObjectName << f.attribute("values");
|
||||
setError = true;
|
||||
} else {
|
||||
uavfield->setValue(f.attribute("values"));
|
||||
}
|
||||
} else {
|
||||
// This is an enum:
|
||||
int i = 0;
|
||||
QStringList list = f.attribute("values").split(",");
|
||||
foreach (QString element, list) {
|
||||
if (false == uavfield->checkValue(element, i)) {
|
||||
qDebug() << "checkValue(list) returned false on: " << uavObjectName << list;
|
||||
setError = true;
|
||||
} else {
|
||||
uavfield->setValue(element,i);
|
||||
}
|
||||
i++;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
error = true;
|
||||
}
|
||||
}
|
||||
field = field.nextSibling();
|
||||
}
|
||||
}
|
||||
}
|
||||
node = node.nextSibling();
|
||||
}
|
||||
qDebug() << "End import";
|
||||
}
|
||||
|
||||
// Create an XML document from UAVObject database
|
||||
QString UAVSettingsImportExportFactory::createXMLDocument(const enum storedData what, const bool fullExport)
|
||||
{
|
||||
@ -396,7 +258,6 @@ QString UAVSettingsImportExportFactory::createXMLDocument(const enum storedData
|
||||
// create settings and/or data elements
|
||||
QDomElement settings = doc.createElement("settings");
|
||||
QDomElement data = doc.createElement("data");
|
||||
QDomElement waypoints = doc.createElement("waypoints");
|
||||
|
||||
switch (what)
|
||||
{
|
||||
@ -410,121 +271,61 @@ QString UAVSettingsImportExportFactory::createXMLDocument(const enum storedData
|
||||
root.appendChild(data);
|
||||
root.appendChild(settings);
|
||||
break;
|
||||
case Waypoints:
|
||||
root.appendChild(waypoints);
|
||||
break;
|
||||
}
|
||||
|
||||
switch (what)
|
||||
{
|
||||
case Settings:
|
||||
case Data:
|
||||
case Both:
|
||||
{
|
||||
// iterate over settings objects
|
||||
QList< QList<UAVDataObject*> > objList = objManager->getDataObjects();
|
||||
foreach (QList<UAVDataObject*> list, objList) {
|
||||
foreach (UAVDataObject *obj, list) {
|
||||
if (((what == Settings) && obj->isSettings()) ||
|
||||
((what == Data) && !obj->isSettings()) ||
|
||||
(what == Both)) {
|
||||
// iterate over settings objects
|
||||
QList< QList<UAVDataObject*> > objList = objManager->getDataObjects();
|
||||
foreach (QList<UAVDataObject*> list, objList) {
|
||||
foreach (UAVDataObject *obj, list) {
|
||||
if (((what == Settings) && obj->isSettings()) ||
|
||||
((what == Data) && !obj->isSettings()) ||
|
||||
(what == Both)) {
|
||||
|
||||
// add each object to the XML
|
||||
QDomElement o = doc.createElement("object");
|
||||
o.setAttribute("name", obj->getName());
|
||||
o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper());
|
||||
if (fullExport) {
|
||||
QDomElement d = doc.createElement("description");
|
||||
QDomText t = doc.createTextNode(obj->getDescription().remove("@Ref ", Qt::CaseInsensitive));
|
||||
d.appendChild(t);
|
||||
o.appendChild(d);
|
||||
}
|
||||
|
||||
// iterate over fields
|
||||
QList<UAVObjectField*> fieldList = obj->getFields();
|
||||
|
||||
foreach (UAVObjectField* field, fieldList) {
|
||||
QDomElement f = doc.createElement("field");
|
||||
|
||||
// iterate over values
|
||||
QString vals;
|
||||
quint32 nelem = field->getNumElements();
|
||||
for (unsigned int n = 0; n < nelem; ++n) {
|
||||
vals.append(QString("%1,").arg(field->getValue(n).toString()));
|
||||
}
|
||||
vals.chop(1);
|
||||
|
||||
f.setAttribute("name", field->getName());
|
||||
f.setAttribute("values", vals);
|
||||
if (fullExport) {
|
||||
f.setAttribute("type", field->getTypeAsString());
|
||||
f.setAttribute("units", field->getUnits());
|
||||
f.setAttribute("elements", nelem);
|
||||
if (field->getType() == UAVObjectField::ENUM) {
|
||||
f.setAttribute("options", field->getOptions().join(","));
|
||||
}
|
||||
}
|
||||
o.appendChild(f);
|
||||
}
|
||||
|
||||
// append to the settings or data element
|
||||
if (obj->isSettings())
|
||||
settings.appendChild(o);
|
||||
else
|
||||
data.appendChild(o);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
case Waypoints:
|
||||
{
|
||||
// iterate over waypoints until the first one that is set to Stop
|
||||
QList<UAVObject*> list = objManager->getObjectInstances("Waypoint");
|
||||
foreach (UAVObject *obj, list) {
|
||||
// add each object to the XML
|
||||
QDomElement o = doc.createElement("object");
|
||||
o.setAttribute("name", obj->getName());
|
||||
o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper());
|
||||
o.setAttribute("instId",QString().setNum(obj->getInstID()));
|
||||
|
||||
// iterate over fields
|
||||
QList<UAVObjectField*> fieldList = obj->getFields();
|
||||
|
||||
foreach (UAVObjectField* field, fieldList) {
|
||||
QDomElement f = doc.createElement("field");
|
||||
|
||||
// iterate over values
|
||||
QString vals;
|
||||
quint32 nelem = field->getNumElements();
|
||||
for (unsigned int n = 0; n < nelem; ++n) {
|
||||
vals.append(QString("%1,").arg(field->getValue(n).toString()));
|
||||
}
|
||||
vals.chop(1);
|
||||
|
||||
f.setAttribute("name", field->getName());
|
||||
f.setAttribute("values", vals);
|
||||
// add each object to the XML
|
||||
QDomElement o = doc.createElement("object");
|
||||
o.setAttribute("name", obj->getName());
|
||||
o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper());
|
||||
if (fullExport) {
|
||||
f.setAttribute("type", field->getTypeAsString());
|
||||
f.setAttribute("units", field->getUnits());
|
||||
f.setAttribute("elements", nelem);
|
||||
if (field->getType() == UAVObjectField::ENUM) {
|
||||
f.setAttribute("options", field->getOptions().join(","));
|
||||
}
|
||||
QDomElement d = doc.createElement("description");
|
||||
QDomText t = doc.createTextNode(obj->getDescription().remove("@Ref ", Qt::CaseInsensitive));
|
||||
d.appendChild(t);
|
||||
o.appendChild(d);
|
||||
}
|
||||
o.appendChild(f);
|
||||
|
||||
// iterate over fields
|
||||
QList<UAVObjectField*> fieldList = obj->getFields();
|
||||
|
||||
foreach (UAVObjectField* field, fieldList) {
|
||||
QDomElement f = doc.createElement("field");
|
||||
|
||||
// iterate over values
|
||||
QString vals;
|
||||
quint32 nelem = field->getNumElements();
|
||||
for (unsigned int n = 0; n < nelem; ++n) {
|
||||
vals.append(QString("%1,").arg(field->getValue(n).toString()));
|
||||
}
|
||||
vals.chop(1);
|
||||
|
||||
f.setAttribute("name", field->getName());
|
||||
f.setAttribute("values", vals);
|
||||
if (fullExport) {
|
||||
f.setAttribute("type", field->getTypeAsString());
|
||||
f.setAttribute("units", field->getUnits());
|
||||
f.setAttribute("elements", nelem);
|
||||
if (field->getType() == UAVObjectField::ENUM) {
|
||||
f.setAttribute("options", field->getOptions().join(","));
|
||||
}
|
||||
}
|
||||
o.appendChild(f);
|
||||
}
|
||||
|
||||
// append to the settings or data element
|
||||
if (obj->isSettings())
|
||||
settings.appendChild(o);
|
||||
else
|
||||
data.appendChild(o);
|
||||
}
|
||||
waypoints.appendChild(o);
|
||||
|
||||
// If this waypoint was stop, then don't add anymore
|
||||
UAVObjectField *field = obj->getField("Action");
|
||||
Q_ASSERT(field);
|
||||
if(field && field->getValue().toString().compare("Stop") == 0)
|
||||
break;
|
||||
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return doc.toString(4);
|
||||
@ -622,40 +423,3 @@ void UAVSettingsImportExportFactory::exportUAVData()
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
}
|
||||
|
||||
/**
|
||||
* Slot called by the menu manager on user action
|
||||
*/
|
||||
void UAVSettingsImportExportFactory::exportWaypoints()
|
||||
{
|
||||
|
||||
// ask for file name
|
||||
QString fileName;
|
||||
QString filters = tr("UAVObjects XML files (*.xml)");
|
||||
|
||||
fileName = QFileDialog::getSaveFileName(0, tr("Save waypoint File As"), "", filters);
|
||||
if (fileName.isEmpty()) {
|
||||
return;
|
||||
}
|
||||
|
||||
// generate an XML first (used for all export formats as a formatted data source)
|
||||
QString xml = createXMLDocument(Waypoints, false);
|
||||
|
||||
// save file
|
||||
QFile file(fileName);
|
||||
if (file.open(QIODevice::WriteOnly) &&
|
||||
(file.write(xml.toAscii()) != -1)) {
|
||||
file.close();
|
||||
} else {
|
||||
QMessageBox::critical(0,
|
||||
tr("UAV Data Export"),
|
||||
tr("Unable to save data: ") + fileName,
|
||||
QMessageBox::Ok);
|
||||
return;
|
||||
}
|
||||
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Data saved."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
}
|
||||
|
@ -38,16 +38,13 @@ public:
|
||||
~UAVSettingsImportExportFactory();
|
||||
|
||||
private:
|
||||
enum storedData { Settings, Data, Waypoints, Both };
|
||||
enum storedData { Settings, Data, Both };
|
||||
QString createXMLDocument(const enum storedData, const bool fullExport);
|
||||
|
||||
private slots:
|
||||
void importUAVSettings();
|
||||
void exportUAVSettings();
|
||||
void exportUAVData();
|
||||
|
||||
void exportWaypoints();
|
||||
void importWaypoints();
|
||||
signals:
|
||||
void importAboutToBegin();
|
||||
void importEnded();
|
||||
|
@ -158,9 +158,9 @@ bool deviceWidget::populateBoardStructuredDescription(QByteArray desc)
|
||||
{
|
||||
myDevice->lblGitTag->setText(onBoardDescription.gitHash);
|
||||
myDevice->lblBuildDate->setText(onBoardDescription.gitDate.insert(4,"-").insert(7,"-"));
|
||||
if (onBoardDescription.gitTag.compare("master") == 0)
|
||||
if(onBoardDescription.gitTag.startsWith("RELEASE",Qt::CaseSensitive))
|
||||
{
|
||||
myDevice->lblDescription->setText(QString("Firmware tag: ")+onBoardDescription.gitTag);
|
||||
myDevice->lblDescription->setText(onBoardDescription.gitTag);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg"));
|
||||
myDevice->lblCertified->setPixmap(pix);
|
||||
myDevice->lblCertified->setToolTip(tr("Tagged officially released firmware build"));
|
||||
@ -188,7 +188,7 @@ bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc)
|
||||
{
|
||||
myDevice->lblGitTagL->setText(LoadedDescription.gitHash);
|
||||
myDevice->lblBuildDateL->setText( LoadedDescription.gitDate.insert(4,"-").insert(7,"-"));
|
||||
if (LoadedDescription.gitTag.compare("master") == 0)
|
||||
if(LoadedDescription.gitTag.startsWith("RELEASE",Qt::CaseSensitive))
|
||||
{
|
||||
myDevice->lblDescritpionL->setText(LoadedDescription.gitTag);
|
||||
myDevice->description->setText(LoadedDescription.gitTag);
|
||||
@ -302,7 +302,7 @@ void deviceWidget::loadFirmware()
|
||||
myDevice->statusLabel->setText(tr("The board has newer firmware than loaded. Are you sure you want to update?"));
|
||||
px.load(QString(":/uploader/images/warning.svg"));
|
||||
}
|
||||
else if (LoadedDescription.gitTag.compare("master"))
|
||||
else if(!LoadedDescription.gitTag.startsWith("RELEASE",Qt::CaseSensitive))
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware is untagged or custom build. Update only if it was received from a trusted source (official website or your own build)"));
|
||||
px.load(QString(":/uploader/images/warning.svg"));
|
||||
|
@ -103,7 +103,7 @@ void runningDeviceWidget::populate()
|
||||
deviceDescriptorStruct devDesc;
|
||||
if(UAVObjectUtilManager::descriptionToStructure(description,devDesc))
|
||||
{
|
||||
if (devDesc.gitTag.compare("master") == 0)
|
||||
if(devDesc.gitTag.startsWith("RELEASE",Qt::CaseSensitive))
|
||||
{
|
||||
myDevice->lblFWTag->setText(QString("Firmware tag: ")+devDesc.gitTag);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg"));
|
||||
|
@ -28,6 +28,7 @@
|
||||
#include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h"
|
||||
#include <coreplugin/coreconstants.h>
|
||||
#include <QDebug>
|
||||
#include "flightstatus.h"
|
||||
|
||||
#define DFU_DEBUG true
|
||||
|
||||
@ -49,7 +50,7 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
|
||||
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()));
|
||||
|
||||
connect(m_config->haltButton, SIGNAL(clicked()), this, SLOT(goToBootloader()));
|
||||
connect(m_config->haltButton, SIGNAL(clicked()), this, SLOT(systemHalt()));
|
||||
connect(m_config->resetButton, SIGNAL(clicked()), this, SLOT(systemReset()));
|
||||
connect(m_config->bootButton, SIGNAL(clicked()), this, SLOT(systemBoot()));
|
||||
connect(m_config->safeBootButton, SIGNAL(clicked()), this, SLOT(systemSafeBoot()));
|
||||
@ -120,6 +121,18 @@ void UploaderGadgetWidget::connectSignalSlot(QWidget *widget)
|
||||
connect(qobject_cast<deviceWidget *>(widget),SIGNAL(uploadStarted()),this,SLOT(uploadStarted()));
|
||||
connect(qobject_cast<deviceWidget *>(widget),SIGNAL(uploadEnded(bool)),this,SLOT(uploadEnded(bool)));
|
||||
}
|
||||
|
||||
FlightStatus *UploaderGadgetWidget::getFlightStatus()
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Q_ASSERT(pm);
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(objManager);
|
||||
FlightStatus *status = dynamic_cast<FlightStatus*>(objManager->getObject(QString("FlightStatus")));
|
||||
Q_ASSERT(status);
|
||||
return status;
|
||||
}
|
||||
|
||||
void UploaderGadgetWidget::onPhisicalHWConnect()
|
||||
{
|
||||
m_config->bootButton->setEnabled(false);
|
||||
@ -348,6 +361,26 @@ void UploaderGadgetWidget::goToBootloader(UAVObject* callerObj, bool success)
|
||||
|
||||
}
|
||||
|
||||
void UploaderGadgetWidget::systemHalt()
|
||||
{
|
||||
FlightStatus* status = getFlightStatus();
|
||||
|
||||
// The board can not be halted when in armed state.
|
||||
// If board is armed, or arming. Show message with notice.
|
||||
if (status->getArmed() == FlightStatus::ARMED_DISARMED) {
|
||||
goToBootloader();
|
||||
}
|
||||
else {
|
||||
QMessageBox mbox(this);
|
||||
mbox.setText(QString(tr("The controller board is armed and can not be halted.\n\n"
|
||||
"Please make sure the board is not armed and then press halt again to proceed\n"
|
||||
"or use the rescue option to force a firmware upgrade.")));
|
||||
mbox.setStandardButtons(QMessageBox::Ok);
|
||||
mbox.setIcon(QMessageBox::Warning);
|
||||
mbox.exec();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
Tell the mainboard to reset:
|
||||
- Send the relevant IAP commands
|
||||
@ -355,14 +388,29 @@ void UploaderGadgetWidget::goToBootloader(UAVObject* callerObj, bool success)
|
||||
*/
|
||||
void UploaderGadgetWidget::systemReset()
|
||||
{
|
||||
resetOnly = true;
|
||||
if (dfu) {
|
||||
delete dfu;
|
||||
dfu = NULL;
|
||||
FlightStatus* status = getFlightStatus();
|
||||
|
||||
// The board can not be reset when in armed state.
|
||||
// If board is armed, or arming. Show message with notice.
|
||||
if (status->getArmed() == FlightStatus::ARMED_DISARMED) {
|
||||
resetOnly = true;
|
||||
if (dfu) {
|
||||
delete dfu;
|
||||
dfu = NULL;
|
||||
}
|
||||
m_config->textBrowser->clear();
|
||||
log("Board Reset initiated.");
|
||||
goToBootloader();
|
||||
}
|
||||
else {
|
||||
QMessageBox mbox(this);
|
||||
mbox.setText(QString(tr("The controller board is armed and can not be reset.\n\n"
|
||||
"Please make sure the board is not armed and then press reset again to proceed\n"
|
||||
"or power cycle to force a board reset.")));
|
||||
mbox.setStandardButtons(QMessageBox::Ok);
|
||||
mbox.setIcon(QMessageBox::Warning);
|
||||
mbox.exec();
|
||||
}
|
||||
m_config->textBrowser->clear();
|
||||
log("Board Reset initiated.");
|
||||
goToBootloader();
|
||||
}
|
||||
|
||||
void UploaderGadgetWidget::systemBoot()
|
||||
@ -381,7 +429,6 @@ void UploaderGadgetWidget::systemSafeBoot()
|
||||
*/
|
||||
void UploaderGadgetWidget::commonSystemBoot(bool safeboot)
|
||||
{
|
||||
|
||||
clearLog();
|
||||
m_config->bootButton->setEnabled(false);
|
||||
m_config->safeBootButton->setEnabled(false);
|
||||
@ -828,6 +875,5 @@ void UploaderGadgetWidget::versionMatchCheck()
|
||||
|
||||
void UploaderGadgetWidget::openHelp()
|
||||
{
|
||||
|
||||
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/AoBZ", QUrl::StrictMode) );
|
||||
}
|
||||
|
@ -61,6 +61,8 @@
|
||||
using namespace OP_DFU;
|
||||
using namespace uploader;
|
||||
|
||||
class FlightStatus;
|
||||
|
||||
class UPLOADER_EXPORT UploaderGadgetWidget : public QWidget
|
||||
{
|
||||
Q_OBJECT
|
||||
@ -94,12 +96,14 @@ private:
|
||||
QErrorMessage * msg;
|
||||
void connectSignalSlot(QWidget * widget);
|
||||
int autoUpdateConnectTimeout;
|
||||
FlightStatus * getFlightStatus();
|
||||
private slots:
|
||||
void onPhisicalHWConnect();
|
||||
void versionMatchCheck();
|
||||
void error(QString errorString,int errorNumber);
|
||||
void info(QString infoString,int infoNumber);
|
||||
void goToBootloader(UAVObject* = NULL, bool = false);
|
||||
void systemHalt();
|
||||
void systemReset();
|
||||
void systemBoot();
|
||||
void systemSafeBoot();
|
||||
|
@ -1,11 +0,0 @@
|
||||
<plugin name="WaypointEditor" version="0.0.1" compatVersion="1.0.0">
|
||||
<vendor>The OpenPilot Project</vendor>
|
||||
<copyright>(C) 2012 OpenPilot Project</copyright>
|
||||
<license>The GNU Public License (GPL) Version 3</license>
|
||||
<description>Allows editing a list of waypoints</description>
|
||||
<url>http://www.openpilot.org</url>
|
||||
<dependencyList>
|
||||
<dependency name="Core" version="1.0.0"/>
|
||||
</dependencyList>
|
||||
</plugin>
|
||||
|
@ -1,26 +0,0 @@
|
||||
TEMPLATE = lib
|
||||
TARGET = WaypointEditor
|
||||
|
||||
include(../../openpilotgcsplugin.pri)
|
||||
include(../../plugins/coreplugin/coreplugin.pri)
|
||||
include(../../plugins/uavobjects/uavobjects.pri)
|
||||
|
||||
HEADERS += waypointeditorgadget.h \
|
||||
waypointtable.h
|
||||
HEADERS += waypointeditorgadgetwidget.h
|
||||
HEADERS += waypointeditorgadgetfactory.h
|
||||
HEADERS += waypointeditorplugin.h
|
||||
|
||||
SOURCES += waypointeditorgadget.cpp \
|
||||
waypointtable.cpp
|
||||
SOURCES += waypointeditorgadgetwidget.cpp
|
||||
SOURCES += waypointeditorgadgetfactory.cpp
|
||||
SOURCES += waypointeditorplugin.cpp
|
||||
|
||||
OTHER_FILES += waypointeditor.pluginspec
|
||||
|
||||
FORMS += waypointeditor.ui
|
||||
|
||||
RESOURCES += waypointeditor.qrc
|
||||
|
||||
|
@ -1,3 +0,0 @@
|
||||
<RCC>
|
||||
<qresource prefix="/waypointeditor"/>
|
||||
</RCC>
|
@ -1,55 +0,0 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>WaypointEditor</class>
|
||||
<widget class="QWidget" name="WaypointEditor">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>653</width>
|
||||
<height>296</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<widget class="QTableView" name="waypoints">
|
||||
<attribute name="horizontalHeaderCascadingSectionResizes">
|
||||
<bool>false</bool>
|
||||
</attribute>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="buttonNewWaypoint">
|
||||
<property name="text">
|
||||
<string>New Waypoint</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="buttonSaveFile">
|
||||
<property name="text">
|
||||
<string>Save to File</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="buttonLoadFile">
|
||||
<property name="text">
|
||||
<string>Load from File</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -1,48 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file waypointeditorgadget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup Waypoint Editor GCS Plugins
|
||||
* @{
|
||||
* @addtogroup WaypointEditorGadgetPlugin Waypoint Editor Gadget Plugin
|
||||
* @{
|
||||
* @brief A gadget to edit a list of waypoints
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "waypointeditorgadget.h"
|
||||
#include "waypointeditorgadgetwidget.h"
|
||||
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavobject.h"
|
||||
#include <QDebug>
|
||||
|
||||
WaypointEditorGadget::WaypointEditorGadget(QString classId, WaypointEditorGadgetWidget *widget, QWidget *parent) :
|
||||
IUAVGadget(classId, parent),
|
||||
m_widget(widget)
|
||||
{
|
||||
}
|
||||
|
||||
WaypointEditorGadget::~WaypointEditorGadget()
|
||||
{
|
||||
delete m_widget;
|
||||
}
|
||||
|
||||
void WaypointEditorGadget::loadConfiguration(IUAVGadgetConfiguration* config)
|
||||
{
|
||||
Q_UNUSED(config);
|
||||
}
|
@ -1,59 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file waypointeditorgadget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup Waypoint Editor GCS Plugins
|
||||
* @{
|
||||
* @addtogroup WaypointEditorGadgetPlugin Waypoint Editor Gadget Plugin
|
||||
* @{
|
||||
* @brief A gadget to edit a list of waypoints
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 WaypointEditorGADGET_H_
|
||||
#define WaypointEditorGADGET_H_
|
||||
|
||||
#include <coreplugin/iuavgadget.h>
|
||||
|
||||
namespace Core {
|
||||
class IUAVGadget;
|
||||
}
|
||||
//class QWidget;
|
||||
//class QString;
|
||||
class WaypointEditorGadgetWidget;
|
||||
|
||||
using namespace Core;
|
||||
|
||||
class WaypointEditorGadget : public Core::IUAVGadget
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
WaypointEditorGadget(QString classId, WaypointEditorGadgetWidget *widget, QWidget *parent = 0);
|
||||
~WaypointEditorGadget();
|
||||
|
||||
QList<int> context() const { return m_context; }
|
||||
QWidget *widget() { return m_widget; }
|
||||
QString contextHelpId() const { return QString(); }
|
||||
|
||||
void loadConfiguration(IUAVGadgetConfiguration* config);
|
||||
private:
|
||||
QWidget *m_widget;
|
||||
QList<int> m_context;
|
||||
};
|
||||
|
||||
|
||||
#endif // WaypointEditorGADGET_H_
|
@ -1,47 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file waypointeditorgadgetfactor.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup Waypoint Editor GCS Plugins
|
||||
* @{
|
||||
* @addtogroup WaypointEditorGadgetPlugin Waypoint Editor Gadget Plugin
|
||||
* @{
|
||||
* @brief A gadget to edit a list of waypoints
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "waypointeditorgadgetfactory.h"
|
||||
#include "waypointeditorgadgetwidget.h"
|
||||
#include "waypointeditorgadget.h"
|
||||
#include <coreplugin/iuavgadget.h>
|
||||
#include <QDebug>
|
||||
|
||||
WaypointEditorGadgetFactory::WaypointEditorGadgetFactory(QObject *parent) :
|
||||
IUAVGadgetFactory(QString("WaypointEditorGadget"),
|
||||
tr("Waypoint Editor"),
|
||||
parent)
|
||||
{
|
||||
}
|
||||
|
||||
WaypointEditorGadgetFactory::~WaypointEditorGadgetFactory()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
IUAVGadget* WaypointEditorGadgetFactory::createGadget(QWidget *parent) {
|
||||
WaypointEditorGadgetWidget* gadgetWidget = new WaypointEditorGadgetWidget(parent);
|
||||
return new WaypointEditorGadget(QString("WaypointEditorGadget"), gadgetWidget, parent);
|
||||
}
|
@ -1,90 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file waypointeditorgadgetwidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup Waypoint Editor GCS Plugins
|
||||
* @{
|
||||
* @addtogroup WaypointEditorGadgetPlugin Waypoint Editor Gadget Plugin
|
||||
* @{
|
||||
* @brief A gadget to edit a list of waypoints
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "waypointeditorgadgetwidget.h"
|
||||
#include "ui_waypointeditor.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QString>
|
||||
#include <QStringList>
|
||||
#include <QtGui/QWidget>
|
||||
#include <QtGui/QTextEdit>
|
||||
#include <QtGui/QVBoxLayout>
|
||||
#include <QtGui/QPushButton>
|
||||
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
|
||||
WaypointEditorGadgetWidget::WaypointEditorGadgetWidget(QWidget *parent) : QLabel(parent)
|
||||
{
|
||||
m_waypointeditor = new Ui_WaypointEditor();
|
||||
m_waypointeditor->setupUi(this);
|
||||
|
||||
waypointTable = new WaypointTable(this);
|
||||
m_waypointeditor->waypoints->setModel(waypointTable);
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Q_ASSERT(pm != NULL);
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(objManager != NULL);
|
||||
waypointObj = Waypoint::GetInstance(objManager);
|
||||
Q_ASSERT(waypointObj != NULL);
|
||||
|
||||
// Connect the signals
|
||||
connect(m_waypointeditor->buttonNewWaypoint, SIGNAL(clicked()),
|
||||
this, SLOT(addInstance()));
|
||||
}
|
||||
|
||||
WaypointEditorGadgetWidget::~WaypointEditorGadgetWidget()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void WaypointEditorGadgetWidget::waypointChanged(UAVObject *)
|
||||
{
|
||||
}
|
||||
|
||||
void WaypointEditorGadgetWidget::waypointActiveChanged(UAVObject *)
|
||||
{
|
||||
}
|
||||
|
||||
void WaypointEditorGadgetWidget::addInstance()
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Q_ASSERT(pm != NULL);
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(objManager != NULL);
|
||||
|
||||
qDebug() << "Instances before: " << objManager->getNumInstances(waypointObj->getObjID());
|
||||
Waypoint *obj = new Waypoint();
|
||||
quint32 newInstId = objManager->getNumInstances(waypointObj->getObjID());
|
||||
obj->initialize(newInstId,obj->getMetaObject());
|
||||
objManager->registerObject(obj);
|
||||
qDebug() << "Instances after: " << objManager->getNumInstances(waypointObj->getObjID());
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -1,57 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file waypointeditorgadgetwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup Waypoint Editor GCS Plugins
|
||||
* @{
|
||||
* @addtogroup WaypointEditorGadgetPlugin Waypoint Editor Gadget Plugin
|
||||
* @{
|
||||
* @brief A gadget to edit a list of waypoints
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 WaypointEditorGADGETWIDGET_H_
|
||||
#define WaypointEditorGADGETWIDGET_H_
|
||||
|
||||
#include <QtGui/QLabel>
|
||||
#include <waypointtable.h>
|
||||
#include <waypointactive.h>
|
||||
|
||||
class Ui_WaypointEditor;
|
||||
|
||||
class WaypointEditorGadgetWidget : public QLabel
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
WaypointEditorGadgetWidget(QWidget *parent = 0);
|
||||
~WaypointEditorGadgetWidget();
|
||||
|
||||
signals:
|
||||
|
||||
protected slots:
|
||||
void waypointChanged(UAVObject *);
|
||||
void waypointActiveChanged(UAVObject *);
|
||||
void addInstance();
|
||||
|
||||
private:
|
||||
Ui_WaypointEditor * m_waypointeditor;
|
||||
WaypointTable *waypointTable;
|
||||
Waypoint *waypointObj;
|
||||
};
|
||||
|
||||
#endif /* WaypointEditorGADGETWIDGET_H_ */
|
@ -1,68 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file waypointeditorplugin.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup Waypoint Editor GCS Plugins
|
||||
* @{
|
||||
* @addtogroup WaypointEditorGadgetPlugin Waypoint Editor Gadget Plugin
|
||||
* @{
|
||||
* @brief A gadget to edit a list of waypoints
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "waypointeditorplugin.h"
|
||||
#include "waypointeditorgadgetfactory.h"
|
||||
#include <QDebug>
|
||||
#include <QtPlugin>
|
||||
#include <QStringList>
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
|
||||
|
||||
WaypointEditorPlugin::WaypointEditorPlugin()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
WaypointEditorPlugin::~WaypointEditorPlugin()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
bool WaypointEditorPlugin::initialize(const QStringList& args, QString *errMsg)
|
||||
{
|
||||
Q_UNUSED(args);
|
||||
Q_UNUSED(errMsg);
|
||||
mf = new WaypointEditorGadgetFactory(this);
|
||||
addAutoReleasedObject(mf);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void WaypointEditorPlugin::extensionsInitialized()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void WaypointEditorPlugin::shutdown()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
Q_EXPORT_PLUGIN(WaypointEditorPlugin)
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -1,191 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file waypointtable.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup Waypoint Editor GCS Plugins
|
||||
* @{
|
||||
* @addtogroup WaypointEditorGadgetPlugin Waypoint Editor Gadget Plugin
|
||||
* @{
|
||||
* @brief Table model for listing waypoint
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 <QDebug>
|
||||
#include <QBrush>
|
||||
#include "waypointtable.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
|
||||
WaypointTable::WaypointTable(QObject *parent) :
|
||||
QAbstractTableModel(parent)
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Q_ASSERT(pm != NULL);
|
||||
objManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(objManager != NULL);
|
||||
waypointObj = Waypoint::GetInstance(objManager);
|
||||
Q_ASSERT(waypointObj != NULL);
|
||||
waypointActiveObj = WaypointActive::GetInstance(objManager);
|
||||
Q_ASSERT(waypointActiveObj != NULL);
|
||||
|
||||
elements = 0;
|
||||
|
||||
// Unfortunately there is no per object new instance signal yet
|
||||
connect(objManager, SIGNAL(newInstance(UAVObject*)),
|
||||
this, SLOT(doNewInstance(UAVObject*)));
|
||||
connect(waypointActiveObj, SIGNAL(objectUpdated(UAVObject*)),
|
||||
this, SLOT(waypointsUpdated(UAVObject*)));
|
||||
|
||||
int numWaypoints = objManager->getNumInstances(Waypoint::OBJID);
|
||||
for (int i = 0; i < numWaypoints; i++) {
|
||||
Waypoint *waypoint = Waypoint::GetInstance(objManager, i);
|
||||
Q_ASSERT(waypoint);
|
||||
if(waypoint)
|
||||
connect(waypoint, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(waypointsUpdated(UAVObject*)));
|
||||
}
|
||||
|
||||
headers.clear();
|
||||
headers.append(QString("North"));
|
||||
headers.append(QString("East"));
|
||||
headers.append(QString("Down"));
|
||||
}
|
||||
|
||||
int WaypointTable::rowCount(const QModelIndex & /*parent*/) const
|
||||
{
|
||||
return elements;
|
||||
}
|
||||
|
||||
int WaypointTable::columnCount(const QModelIndex &parent) const
|
||||
{
|
||||
if (parent.isValid())
|
||||
return 0;
|
||||
|
||||
return headers.length();
|
||||
}
|
||||
|
||||
QVariant WaypointTable::data(const QModelIndex &index, int role) const
|
||||
{
|
||||
if(role == Qt::DisplayRole) {
|
||||
Waypoint *obj = Waypoint::GetInstance(objManager, index.row());
|
||||
Q_ASSERT(obj);
|
||||
Waypoint::DataFields waypoint = obj->getData();
|
||||
|
||||
switch(index.column()) {
|
||||
case 0:
|
||||
return waypoint.Position[Waypoint::POSITION_NORTH];
|
||||
case 1:
|
||||
return waypoint.Position[Waypoint::POSITION_EAST];
|
||||
case 2:
|
||||
return waypoint.Position[Waypoint::POSITION_DOWN];
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
return 0;
|
||||
}
|
||||
} else if (role == Qt::BackgroundRole) {
|
||||
WaypointActive::DataFields waypointActive = waypointActiveObj->getData();
|
||||
|
||||
if(index.row() == waypointActive.Index) {
|
||||
return QBrush(Qt::lightGray);
|
||||
} else
|
||||
return QVariant::Invalid;
|
||||
}
|
||||
else {
|
||||
return QVariant::Invalid;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
QVariant WaypointTable::headerData(int section, Qt::Orientation orientation, int role) const
|
||||
{
|
||||
if(role == Qt::DisplayRole && orientation == Qt::Horizontal) {
|
||||
if(section < headers.length())
|
||||
return headers[section];
|
||||
return QVariant::Invalid;
|
||||
} else
|
||||
return QAbstractTableModel::headerData(section, orientation, role);
|
||||
}
|
||||
|
||||
/**
|
||||
* Called for any new UAVO instance and when that is a Waypoint register
|
||||
* to update the table
|
||||
*/
|
||||
void WaypointTable::doNewInstance(UAVObject*obj)
|
||||
{
|
||||
Q_ASSERT(obj);
|
||||
if (!obj)
|
||||
return;
|
||||
|
||||
if (obj->getObjID() == Waypoint::OBJID)
|
||||
connect(obj, SIGNAL(objectUpdated(UAVObject*)),this,SLOT(waypointsUpdated(UAVObject*)));
|
||||
}
|
||||
|
||||
/**
|
||||
* Called whenever the waypoints are updated to inform
|
||||
* the view
|
||||
*/
|
||||
void WaypointTable::waypointsUpdated(UAVObject *)
|
||||
{
|
||||
int elementsNow = objManager->getNumInstances(waypointObj->getObjID());
|
||||
|
||||
// Currently only support adding instances which is all the UAVO manager
|
||||
// supports
|
||||
if (elementsNow > elements) {
|
||||
beginInsertRows(QModelIndex(), elements, elementsNow-1);
|
||||
elements = elementsNow;
|
||||
endInsertRows();
|
||||
}
|
||||
|
||||
QModelIndex i1 = index(0,0);
|
||||
QModelIndex i2 = index(elements-1, columnCount(QModelIndex()));
|
||||
emit dataChanged(i1, i2);
|
||||
}
|
||||
|
||||
Qt::ItemFlags WaypointTable::flags(const QModelIndex &index) const
|
||||
{
|
||||
return QAbstractTableModel::flags(index) | Qt::ItemIsEditable;
|
||||
}
|
||||
|
||||
bool WaypointTable::setData ( const QModelIndex & index, const QVariant & value, int role = Qt::EditRole )
|
||||
{
|
||||
Q_UNUSED(role);
|
||||
|
||||
double val = value.toDouble();
|
||||
qDebug() << "New value " << val << " for column " << index.column();
|
||||
|
||||
Waypoint *obj = Waypoint::GetInstance(objManager, index.row());
|
||||
Q_ASSERT(obj);
|
||||
Waypoint::DataFields waypoint = obj->getData();
|
||||
|
||||
switch(index.column()) {
|
||||
case 0:
|
||||
waypoint.Position[Waypoint::POSITION_NORTH] = val;
|
||||
break;
|
||||
case 1:
|
||||
waypoint.Position[Waypoint::POSITION_EAST] = val;
|
||||
break;
|
||||
case 2:
|
||||
waypoint.Position[Waypoint::POSITION_DOWN] = val;
|
||||
break;
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
||||
obj->setData(waypoint);
|
||||
obj->updated();
|
||||
qDebug() << "Set data for instance " << obj->getInstID();
|
||||
|
||||
return true;
|
||||
}
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user