mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-29 14:52:12 +01:00
Merge branch 'next' into GCS_ChangesToUI-RuntimeCFG
Conflicts: flight/CopterControl/Makefile flight/OpenPilot/System/pios_board.c flight/OpenPilot/UAVObjects.inc flight/PiOS/STM32F10x/pios_spektrum.c ground/openpilotgcs/src/plugins/config/config.pro ground/openpilotgcs/src/plugins/config/configgadget.qrc ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro shared/uavobjectdefinition/hwsettings.xml
This commit is contained in:
commit
dc340596f5
13
HISTORY.txt
13
HISTORY.txt
@ -1,5 +1,18 @@
|
||||
Short summary of changes. For a complete list see the git log.
|
||||
|
||||
2011-08-10
|
||||
Added Camera Stabilization and a gui to configure this. This is a software
|
||||
selectable module from the GUI. However, a restart is required to make it
|
||||
active. The GUI does not currently expose the configuration for using the
|
||||
transmitter to change the view angle but this is supported by the hardware.
|
||||
|
||||
2011-08-10
|
||||
By default a lot of diagnostic objects that were enabled by default are now
|
||||
disabled in the build. This include TaskInfo (and all the FreeRTOS options
|
||||
that provide that debugging information). Also MixerStatus, I2CStatus,
|
||||
WatchdogStatus and RateDesired. These can be reenabled for debugging with
|
||||
-DDIAGNOSTICS.
|
||||
|
||||
2011-08-04
|
||||
Fixed packaging aesthetic issues. Also avoid runtime issues on OSX Lion by
|
||||
disabling the ModelView and Notify plugins for now (sorry).
|
||||
|
@ -137,6 +137,16 @@ C: Mat Wellington
|
||||
D: July 2011
|
||||
V: http://www.youtube.com/watch?v=YE4Fd9vdg1I
|
||||
|
||||
M: First CopterControl Flybared Heli inverted flight (2:33)
|
||||
C: Maxim Izergin (Maximus43)
|
||||
D: August 2011
|
||||
V: http://www.youtube.com/watch?v=8SrfIS7OkB4
|
||||
|
||||
M: First CopterControl Flybared Heli funnel (4:18), loop (5:35)
|
||||
C: Sergey Solodennikov (alconaft43)
|
||||
D: August 2011
|
||||
V: http://www.youtube.com/watch?v=8SrfIS7OkB4
|
||||
|
||||
M: First Altitude Hold using Sonar
|
||||
C:
|
||||
D:
|
||||
|
@ -37,6 +37,9 @@ OUTDIR := $(TOP)/build/$(TARGET)
|
||||
# Set to YES to compile for debugging
|
||||
DEBUG ?= NO
|
||||
|
||||
# Include objects that are just nice information to show
|
||||
DIAGNOSTICS ?= NO
|
||||
|
||||
# Set to YES to build a FW version that will erase all flash memory
|
||||
ERASE_FLASH ?= NO
|
||||
# Set to YES to use the Servo output pins for debugging via scope or logic analyser
|
||||
@ -62,7 +65,9 @@ endif
|
||||
FLASH_TOOL = OPENOCD
|
||||
|
||||
# List of modules to include
|
||||
MODULES = Telemetry Attitude Stabilization Actuator ManualControl FirmwareIAP
|
||||
MODULES = Attitude Stabilization Actuator ManualControl FirmwareIAP CameraStab
|
||||
# Telemetry must be last to grab the optional modules
|
||||
MODULES += Telemetry
|
||||
|
||||
# Paths
|
||||
OPSYSTEM = ./System
|
||||
@ -125,7 +130,6 @@ SRC += $(OPSYSTEM)/taskmonitor.c
|
||||
SRC += $(OPUAVTALK)/uavtalk.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectsinit_linker.c
|
||||
SRC += $(OPSYSTEM)/pios_usb_hid_desc.c
|
||||
else
|
||||
## TESTCODE
|
||||
@ -153,23 +157,22 @@ SRC += $(OPUAVSYNTHDIR)/actuatorsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/attituderaw.c
|
||||
SRC += $(OPUAVSYNTHDIR)/attitudeactual.c
|
||||
SRC += $(OPUAVSYNTHDIR)/manualcontrolcommand.c
|
||||
SRC += $(OPUAVSYNTHDIR)/taskinfo.c
|
||||
SRC += $(OPUAVSYNTHDIR)/i2cstats.c
|
||||
SRC += $(OPUAVSYNTHDIR)/watchdogstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/telemetrysettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/ratedesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/manualcontrolsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/mixersettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/mixerstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/firmwareiapobj.c
|
||||
SRC += $(OPUAVSYNTHDIR)/attitudesettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/camerastabsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/cameradesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/hwsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c
|
||||
SRC += $(OPUAVSYNTHDIR)/receiveractivity.c
|
||||
#${wildcard ${OBJ}/$(shell echo $(VAR) | tr A-Z a-z)/*.c}
|
||||
#SRC += ${foreach OBJ, ${UAVOBJECTS}, $(UAVOBJECTS)/$(OBJ).c}
|
||||
# Cant use until i can automatically generate list of UAVObjects
|
||||
#SRC += ${OUTDIR}/InitObjects.c
|
||||
SRC += $(OPUAVSYNTHDIR)/taskinfo.c
|
||||
SRC += $(OPUAVSYNTHDIR)/mixerstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/ratedesired.c
|
||||
|
||||
endif
|
||||
|
||||
## PIOS Hardware (STM32F10x)
|
||||
@ -420,6 +423,10 @@ ifeq ($(DEBUG),YES)
|
||||
CFLAGS = -DDEBUG
|
||||
endif
|
||||
|
||||
ifeq ($(DIAGNOSTICS),YES)
|
||||
CFLAGS = -DDIAGNOSTICS
|
||||
endif
|
||||
|
||||
CFLAGS += -g$(DEBUGF)
|
||||
CFLAGS += -O$(OPT)
|
||||
CFLAGS += -mcpu=$(MCU)
|
||||
@ -428,7 +435,7 @@ CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I.
|
||||
|
||||
#CFLAGS += -fno-cprop-registers -fno-defer-pop -fno-guess-branch-probability -fno-section-anchors
|
||||
#CFLAGS += -fno-if-conversion -fno-if-conversion2 -fno-ipa-pure-const -fno-ipa-reference -fno-merge-constants
|
||||
#CFLAGS += -fno-split-wide-types -fno-tree-ccp -fno-tree-ch -fno-tree-copy-prop -fno-tree-copyrename
|
||||
#CFLAGS += -fno-split-wide-types -fno-tree-ccp -fno-tree-ch -fno-tree-copy-prop -fno-tree-copyrename
|
||||
#CFLAGS += -fno-tree-dce -fno-tree-dominator-opts -fno-tree-dse -fno-tree-fre -fno-tree-sink -fno-tree-sra
|
||||
#CFLAGS += -fno-tree-ter
|
||||
#CFLAGS += -g$(DEBUGF) -DDEBUG
|
||||
@ -507,7 +514,7 @@ endif
|
||||
endif
|
||||
|
||||
# Generate code for PyMite
|
||||
#$(OUTDIR)/pmlib_img.c $(OUTDIR)/pmlib_nat.c $(OUTDIR)/pmlibusr_img.c $(OUTDIR)/pmlibusr_nat.c $(OUTDIR)/pmfeatures.h: $(wildcard $(PYMITELIB)/*.py) $(wildcard $(PYMITEPLAT)/*.py) $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(FLIGHTPLANS)/*.py)
|
||||
#$(OUTDIR)/pmlib_img.c $(OUTDIR)/pmlib_nat.c $(OUTDIR)/pmlibusr_img.c $(OUTDIR)/pmlibusr_nat.c $(OUTDIR)/pmfeatures.h: $(wildcard $(PYMITELIB)/*.py) $(wildcard $(PYMITEPLAT)/*.py) $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(FLIGHTPLANS)/*.py)
|
||||
# @echo $(MSG_PYMITEINIT) $(call toprel, $@)
|
||||
# @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py)
|
||||
# @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h
|
||||
|
@ -41,10 +41,12 @@ static xSemaphoreHandle lock;
|
||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
||||
|
||||
/**
|
||||
* Initialize the alarms library
|
||||
* Initialize the alarms library
|
||||
*/
|
||||
int32_t AlarmsInitialize(void)
|
||||
{
|
||||
SystemAlarmsInitialize();
|
||||
|
||||
lock = xSemaphoreCreateRecursiveMutex();
|
||||
//do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that
|
||||
//AlarmsClearAll();
|
||||
@ -56,7 +58,7 @@ int32_t AlarmsInitialize(void)
|
||||
* Set an alarm
|
||||
* @param alarm The system alarm to be modified
|
||||
* @param severity The alarm severity
|
||||
* @return 0 if success, -1 if an error
|
||||
* @return 0 if success, -1 if an error
|
||||
*/
|
||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
||||
{
|
||||
@ -151,7 +153,7 @@ void AlarmsClearAll()
|
||||
|
||||
/**
|
||||
* Check if there are any alarms with the given or higher severity
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
*/
|
||||
int32_t AlarmsHasWarnings()
|
||||
{
|
||||
@ -208,5 +210,5 @@ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
*/
|
||||
|
||||
|
@ -1,97 +1,107 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @brief These files are the core system files of OpenPilot.
|
||||
* They are the ground layer just above PiOS. In practice, OpenPilot actually starts
|
||||
* in the main() function of openpilot.c
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @brief This is where the OP firmware starts. Those files also define the compile-time
|
||||
* options of the firmware.
|
||||
* @{
|
||||
* @file openpilot.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Sets up and runs main OpenPilot tasks.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
/* OpenPilot Includes */
|
||||
#include "openpilot.h"
|
||||
#include "uavobjectsinit.h"
|
||||
#include "systemmod.h"
|
||||
|
||||
/* Task Priorities */
|
||||
#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3)
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void Stack_Change(void);
|
||||
|
||||
/**
|
||||
* OpenPilot Main function:
|
||||
*
|
||||
* Initialize PiOS<BR>
|
||||
* Create the "System" task (SystemModInitializein Modules/System/systemmod.c) <BR>
|
||||
* Start FreeRTOS Scheduler (vTaskStartScheduler) (Now handled by caller)
|
||||
* If something goes wrong, blink LED1 and LED2 every 100ms
|
||||
*
|
||||
*/
|
||||
int main()
|
||||
{
|
||||
/* NOTE: Do NOT modify the following start-up sequence */
|
||||
/* Any new initialization functions should be added in OpenPilotInit() */
|
||||
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
|
||||
/* Architecture dependant Hardware and
|
||||
* core subsystem initialisation
|
||||
* (see pios_board.c for your arch)
|
||||
* */
|
||||
PIOS_Board_Init();
|
||||
|
||||
/* Initialize modules */
|
||||
MODULE_INITIALISE_ALL
|
||||
|
||||
/* swap the stack to use the IRQ stack */
|
||||
Stack_Change();
|
||||
|
||||
/* Start the FreeRTOS scheduler which should never returns.*/
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
PIOS_LED_Off(LED1); \
|
||||
for(;;) { \
|
||||
PIOS_LED_Toggle(LED1); \
|
||||
PIOS_DELAY_WaitmS(100); \
|
||||
};
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @brief These files are the core system files of OpenPilot.
|
||||
* They are the ground layer just above PiOS. In practice, OpenPilot actually starts
|
||||
* in the main() function of openpilot.c
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @brief This is where the OP firmware starts. Those files also define the compile-time
|
||||
* options of the firmware.
|
||||
* @{
|
||||
* @file openpilot.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Sets up and runs main OpenPilot tasks.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
/* OpenPilot Includes */
|
||||
#include "openpilot.h"
|
||||
#include "uavobjectsinit.h"
|
||||
#include "hwsettings.h"
|
||||
#include "camerastab.h"
|
||||
#include "systemmod.h"
|
||||
|
||||
/* Task Priorities */
|
||||
#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3)
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void Stack_Change(void);
|
||||
|
||||
/**
|
||||
* OpenPilot Main function:
|
||||
*
|
||||
* Initialize PiOS<BR>
|
||||
* Create the "System" task (SystemModInitializein Modules/System/systemmod.c) <BR>
|
||||
* Start FreeRTOS Scheduler (vTaskStartScheduler) (Now handled by caller)
|
||||
* If something goes wrong, blink LED1 and LED2 every 100ms
|
||||
*
|
||||
*/
|
||||
int main()
|
||||
{
|
||||
/* NOTE: Do NOT modify the following start-up sequence */
|
||||
/* Any new initialization functions should be added in OpenPilotInit() */
|
||||
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
|
||||
/* Architecture dependant Hardware and
|
||||
* core subsystem initialisation
|
||||
* (see pios_board.c for your arch)
|
||||
* */
|
||||
PIOS_Board_Init();
|
||||
|
||||
/* Initialize modules */
|
||||
MODULE_INITIALISE_ALL
|
||||
|
||||
/* Optional module initialization. This code might want to go somewhere else as
|
||||
* it grows */
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
if(optionalModules[HWSETTINGS_OPTIONALMODULES_CAMERASTABILIZATION] == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
CameraStabInitialize();
|
||||
}
|
||||
|
||||
/* swap the stack to use the IRQ stack */
|
||||
Stack_Change();
|
||||
|
||||
/* Start the FreeRTOS scheduler which should never returns.*/
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
PIOS_LED_Off(LED1); \
|
||||
for(;;) { \
|
||||
PIOS_LED_Toggle(LED1); \
|
||||
PIOS_DELAY_WaitmS(100); \
|
||||
};
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
@ -26,6 +26,7 @@
|
||||
#define configUSE_PREEMPTION 1
|
||||
#define configUSE_IDLE_HOOK 1
|
||||
#define configUSE_TICK_HOOK 0
|
||||
#define configUSE_MALLOC_FAILED_HOOK 1
|
||||
#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 )
|
||||
#define configTICK_RATE_HZ ( ( portTickType ) 1000 )
|
||||
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )
|
||||
@ -39,7 +40,6 @@
|
||||
#define configUSE_RECURSIVE_MUTEXES 1
|
||||
#define configUSE_COUNTING_SEMAPHORES 0
|
||||
#define configUSE_ALTERNATIVE_API 0
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
#define configQUEUE_REGISTRY_SIZE 10
|
||||
|
||||
/* Co-routine definitions. */
|
||||
@ -76,7 +76,9 @@ NVIC value of 255. */
|
||||
#endif
|
||||
|
||||
/* Enable run time stats collection */
|
||||
//#if defined(DEBUG)
|
||||
#if defined(DIAGNOSTICS)
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
|
||||
#define configGENERATE_RUN_TIME_STATS 1
|
||||
#define INCLUDE_uxTaskGetRunTime 1
|
||||
#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS()\
|
||||
@ -85,7 +87,9 @@ do {\
|
||||
(*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */\
|
||||
} while(0)
|
||||
#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004)/* DWT_CYCCNT */
|
||||
//#endif
|
||||
#else
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 1
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
|
@ -915,8 +915,10 @@ void PIOS_Board_Init(void) {
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
UAVObjectsInitializeAll();
|
||||
|
||||
HwSettingsInitialize();
|
||||
ManualControlSettingsInitialize();
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/* Initialize the real-time clock and its associated tick */
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
@ -929,6 +931,8 @@ void PIOS_Board_Init(void) {
|
||||
TaskMonitorInitialize();
|
||||
|
||||
/* Configure the main IO port */
|
||||
uint8_t hwsettings_DSMxBind;
|
||||
HwSettingsDSMxBindGet(&hwsettings_DSMxBind);
|
||||
uint8_t hwsettings_cc_mainport;
|
||||
HwSettingsCC_MainPortGet(&hwsettings_cc_mainport);
|
||||
|
||||
@ -998,7 +1002,7 @@ void PIOS_Board_Init(void) {
|
||||
}
|
||||
|
||||
uint32_t pios_spektrum_id;
|
||||
if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_main_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, false)) {
|
||||
if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_main_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
@ -1071,7 +1075,7 @@ void PIOS_Board_Init(void) {
|
||||
}
|
||||
|
||||
uint32_t pios_spektrum_id;
|
||||
if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_flexi_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, false)) {
|
||||
if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_flexi_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, hwsettings_DSMxBind)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
|
@ -42,7 +42,6 @@ void PIOS_Board_Init(void) {
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
UAVObjectsInitializeAll();
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
@ -46,7 +46,10 @@ int32_t TaskMonitorInitialize(void)
|
||||
{
|
||||
lock = xSemaphoreCreateRecursiveMutex();
|
||||
memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM);
|
||||
lastMonitorTime = 0;
|
||||
#if defined(DIAGNOSTICS)
|
||||
lastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE();
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -73,6 +76,7 @@ int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle)
|
||||
*/
|
||||
void TaskMonitorUpdateAll(void)
|
||||
{
|
||||
#if defined(DIAGNOSTICS)
|
||||
TaskInfoData data;
|
||||
int n;
|
||||
|
||||
@ -123,4 +127,5 @@ void TaskMonitorUpdateAll(void)
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
#endif
|
||||
}
|
||||
|
@ -79,6 +79,7 @@ CREATEHANDLE(10, FirmwareIAPObj);
|
||||
static void ObjectUpdatedCb(UAVObjEvent * ev);
|
||||
|
||||
#define ADDHANDLE(idx,obj) {\
|
||||
obj##Initialize();\
|
||||
int n = idx;\
|
||||
objectHandles[n].data = &obj;\
|
||||
objectHandles[n].uavHandle = obj##Handle();\
|
||||
|
@ -52,6 +52,8 @@
|
||||
|
||||
#include "ahrs_comms.h"
|
||||
#include "ahrs_spi_comm.h"
|
||||
#include "ahrsstatus.h"
|
||||
#include "ahrscalibration.h"
|
||||
|
||||
// Private constants
|
||||
#define STACK_SIZE configMINIMAL_STACK_SIZE-128
|
||||
@ -71,7 +73,7 @@ static void ahrscommsTask(void *parameters);
|
||||
*/
|
||||
int32_t AHRSCommsStart(void)
|
||||
{
|
||||
// Start main task
|
||||
// Start main task
|
||||
xTaskCreate(ahrscommsTask, (signed char *)"AHRSComms", STACK_SIZE, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_AHRSCOMMS, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_AHRS);
|
||||
@ -85,6 +87,11 @@ int32_t AHRSCommsStart(void)
|
||||
*/
|
||||
int32_t AHRSCommsInitialize(void)
|
||||
{
|
||||
AhrsStatusInitialize();
|
||||
AHRSCalibrationInitialize();
|
||||
AttitudeRawInitialize();
|
||||
VelocityActualInitialize();
|
||||
PositionActualInitialize();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -41,6 +41,7 @@
|
||||
#include "flightstatus.h"
|
||||
#include "mixersettings.h"
|
||||
#include "mixerstatus.h"
|
||||
#include "cameradesired.h"
|
||||
|
||||
|
||||
// Private constants
|
||||
@ -108,9 +109,17 @@ int32_t ActuatorInitialize()
|
||||
// Create object queue
|
||||
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
|
||||
ActuatorSettingsInitialize();
|
||||
ActuatorDesiredInitialize();
|
||||
MixerSettingsInitialize();
|
||||
ActuatorCommandInitialize();
|
||||
#if defined(DIAGNOSTICS)
|
||||
MixerStatusInitialize();
|
||||
#endif
|
||||
|
||||
// Listen for ExampleObject1 updates
|
||||
ActuatorDesiredConnectQueue(queue);
|
||||
|
||||
|
||||
// If settings change, update the output rate
|
||||
ActuatorSettingsConnectCallback(actuator_update_rate);
|
||||
|
||||
@ -160,7 +169,7 @@ static void actuatorTask(void* parameters)
|
||||
// Main task loop
|
||||
lastSysTime = xTaskGetTickCount();
|
||||
while (1)
|
||||
{
|
||||
{
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_ACTUATOR);
|
||||
|
||||
// Wait until the ActuatorDesired object is updated, if a timeout then go to failsafe
|
||||
@ -177,11 +186,13 @@ static void actuatorTask(void* parameters)
|
||||
lastSysTime = thisSysTime;
|
||||
|
||||
FlightStatusGet(&flightStatus);
|
||||
MixerStatusGet(&mixerStatus);
|
||||
MixerSettingsGet (&mixerSettings);
|
||||
ActuatorDesiredGet(&desired);
|
||||
ActuatorCommandGet(&command);
|
||||
|
||||
#if defined(DIAGNOSTICS)
|
||||
MixerStatusGet(&mixerStatus);
|
||||
#endif
|
||||
ActuatorSettingsMotorsSpinWhileArmedGet(&MotorsSpinWhileArmed);
|
||||
ActuatorSettingsChannelMaxGet(ChannelMax);
|
||||
ActuatorSettingsChannelMinGet(ChannelMin);
|
||||
@ -196,7 +207,7 @@ static void actuatorTask(void* parameters)
|
||||
nMixers ++;
|
||||
}
|
||||
}
|
||||
if((nMixers < 2) && !ActuatorCommandReadOnly(dummy)) //Nothing can fly with less than two mixers.
|
||||
if((nMixers < 2) && !ActuatorCommandReadOnly(dummy)) //Nothing can fly with less than two mixers.
|
||||
{
|
||||
setFailsafe(); // So that channels like PWM buzzer keep working
|
||||
continue;
|
||||
@ -207,7 +218,7 @@ static void actuatorTask(void* parameters)
|
||||
bool armed = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED;
|
||||
bool positiveThrottle = desired.Throttle >= 0.00;
|
||||
bool spinWhileArmed = MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE;
|
||||
|
||||
|
||||
float curve1 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve1);
|
||||
//The source for the secondary curve is selectable
|
||||
float curve2 = 0;
|
||||
@ -233,11 +244,11 @@ static void actuatorTask(void* parameters)
|
||||
case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY5:
|
||||
if(AccessoryDesiredInstGet(mixerSettings.Curve2Source - MIXERSETTINGS_CURVE2SOURCE_ACCESSORY0,&accessory) == 0)
|
||||
curve2 = MixerCurve(accessory.AccessoryVal,mixerSettings.ThrottleCurve2);
|
||||
else
|
||||
curve2 = 0;
|
||||
else
|
||||
curve2 = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++)
|
||||
{
|
||||
if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_DISABLED) {
|
||||
@ -246,53 +257,82 @@ static void actuatorTask(void* parameters)
|
||||
command.Channel[ct] = 0;
|
||||
continue;
|
||||
}
|
||||
|
||||
status[ct] = ProcessMixer(ct, curve1, curve2, &mixerSettings, &desired, dT);
|
||||
|
||||
|
||||
if((mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) || (mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_SERVO))
|
||||
status[ct] = ProcessMixer(ct, curve1, curve2, &mixerSettings, &desired, dT);
|
||||
else
|
||||
status[ct] = -1;
|
||||
|
||||
|
||||
|
||||
// Motors have additional protection for when to be on
|
||||
if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) {
|
||||
if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) {
|
||||
|
||||
// If not armed or motors aren't meant to spin all the time
|
||||
if( !armed ||
|
||||
(!spinWhileArmed && !positiveThrottle))
|
||||
{
|
||||
filterAccumulator[ct] = 0;
|
||||
lastResult[ct] = 0;
|
||||
lastResult[ct] = 0;
|
||||
status[ct] = -1; //force min throttle
|
||||
}
|
||||
// If armed meant to keep spinning,
|
||||
}
|
||||
// If armed meant to keep spinning,
|
||||
else if ((spinWhileArmed && !positiveThrottle) ||
|
||||
(status[ct] < 0) )
|
||||
status[ct] = 0;
|
||||
status[ct] = 0;
|
||||
}
|
||||
|
||||
|
||||
// If an accessory channel is selected for direct bypass mode
|
||||
// In this configuration the accessory channel is scaled and mapped
|
||||
// directly to output. Note: THERE IS NO SAFETY CHECK HERE FOR ARMING
|
||||
// these also will not be updated in failsafe mode. I'm not sure what
|
||||
// these also will not be updated in failsafe mode. I'm not sure what
|
||||
// the correct behavior is since it seems domain specific. I don't love
|
||||
// this code
|
||||
if( (mixers[ct].type >= MIXERSETTINGS_MIXER1TYPE_ACCESSORY0) &&
|
||||
(mixers[ct].type <= MIXERSETTINGS_MIXER1TYPE_ACCESSORY2))
|
||||
if( (mixers[ct].type >= MIXERSETTINGS_MIXER1TYPE_ACCESSORY0) &&
|
||||
(mixers[ct].type <= MIXERSETTINGS_MIXER1TYPE_ACCESSORY5))
|
||||
{
|
||||
if(AccessoryDesiredInstGet(mixers[ct].type - MIXERSETTINGS_MIXER1TYPE_ACCESSORY0,&accessory) == 0)
|
||||
status[ct] = accessory.AccessoryVal;
|
||||
else
|
||||
status[ct] = -1;
|
||||
}
|
||||
|
||||
if( (mixers[ct].type >= MIXERSETTINGS_MIXER1TYPE_CAMERAROLL) &&
|
||||
(mixers[ct].type <= MIXERSETTINGS_MIXER1TYPE_CAMERAYAW))
|
||||
{
|
||||
CameraDesiredData cameraDesired;
|
||||
if( CameraDesiredGet(&cameraDesired) == 0 ) {
|
||||
switch(mixers[ct].type) {
|
||||
case MIXERSETTINGS_MIXER1TYPE_CAMERAROLL:
|
||||
status[ct] = cameraDesired.Roll;
|
||||
break;
|
||||
case MIXERSETTINGS_MIXER1TYPE_CAMERAPITCH:
|
||||
status[ct] = cameraDesired.Pitch;
|
||||
break;
|
||||
case MIXERSETTINGS_MIXER1TYPE_CAMERAYAW:
|
||||
status[ct] = cameraDesired.Yaw;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
else
|
||||
status[ct] = -1;
|
||||
}
|
||||
|
||||
command.Channel[ct] = scaleChannel(status[ct],
|
||||
ChannelMax[ct],
|
||||
ChannelMin[ct],
|
||||
ChannelNeutral[ct]);
|
||||
}
|
||||
#if defined(DIAGNOSTICS)
|
||||
MixerStatusSet(&mixerStatus);
|
||||
#endif
|
||||
|
||||
// Store update time
|
||||
command.UpdateTime = 1000*dT;
|
||||
if(1000*dT > command.MaxUpdateTime)
|
||||
command.MaxUpdateTime = 1000*dT;
|
||||
|
||||
|
||||
// Update output object
|
||||
ActuatorCommandSet(&command);
|
||||
// Update in case read only (eg. during servo configuration)
|
||||
@ -300,7 +340,7 @@ static void actuatorTask(void* parameters)
|
||||
|
||||
// Update servo outputs
|
||||
bool success = true;
|
||||
|
||||
|
||||
for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n)
|
||||
{
|
||||
success &= set_channel(n, command.Channel[n]);
|
||||
@ -309,7 +349,7 @@ static void actuatorTask(void* parameters)
|
||||
if(!success) {
|
||||
command.NumFailedUpdates++;
|
||||
ActuatorCommandSet(&command);
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ACTUATOR, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ACTUATOR, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
}
|
||||
|
||||
}
|
||||
@ -463,7 +503,7 @@ static void setFailsafe()
|
||||
// Reset ActuatorCommand to safe values
|
||||
for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n)
|
||||
{
|
||||
|
||||
|
||||
if(mixers[n].type == MIXERSETTINGS_MIXER1TYPE_MOTOR)
|
||||
{
|
||||
Channel[n] = ChannelMin[n];
|
||||
@ -510,10 +550,10 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) {
|
||||
}
|
||||
#else
|
||||
static bool set_channel(uint8_t mixer_channel, uint16_t value) {
|
||||
|
||||
|
||||
ActuatorSettingsData settings;
|
||||
ActuatorSettingsGet(&settings);
|
||||
|
||||
|
||||
switch(settings.ChannelType[mixer_channel]) {
|
||||
case ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER: {
|
||||
// This is for buzzers that take a PWM input
|
||||
@ -565,7 +605,7 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) {
|
||||
PIOS_Servo_Set(settings.ChannelAddr[mixer_channel], value);
|
||||
return true;
|
||||
#if defined(PIOS_INCLUDE_I2C_ESC)
|
||||
case ACTUATORSETTINGS_CHANNELTYPE_MK:
|
||||
case ACTUATORSETTINGS_CHANNELTYPE_MK:
|
||||
return PIOS_SetMKSpeed(settings.ChannelAddr[mixer_channel],value);
|
||||
case ACTUATORSETTINGS_CHANNELTYPE_ASTEC4:
|
||||
return PIOS_SetAstec4Speed(settings.ChannelAddr[mixer_channel],value);
|
||||
@ -573,10 +613,10 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) {
|
||||
#endif
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return false;
|
||||
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -69,6 +69,12 @@ static void altitudeTask(void *parameters);
|
||||
*/
|
||||
int32_t AltitudeStart()
|
||||
{
|
||||
|
||||
BaroAltitudeInitialize();
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
SonarAltitudeInitialze();
|
||||
#endif
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle);
|
||||
|
@ -112,6 +112,10 @@ int32_t AttitudeStart(void)
|
||||
*/
|
||||
int32_t AttitudeInitialize(void)
|
||||
{
|
||||
AttitudeActualInitialize();
|
||||
AttitudeRawInitialize();
|
||||
AttitudeSettingsInitialize();
|
||||
|
||||
// Initialize quaternion
|
||||
AttitudeActualData attitude;
|
||||
AttitudeActualGet(&attitude);
|
||||
|
@ -79,6 +79,9 @@ MODULE_INITCALL(BatteryInitialize, 0)
|
||||
|
||||
int32_t BatteryInitialize(void)
|
||||
{
|
||||
BatteryStateInitialze();
|
||||
BatterySettingsInitialize();
|
||||
|
||||
static UAVObjEvent ev;
|
||||
|
||||
memset(&ev,0,sizeof(UAVObjEvent));
|
||||
|
141
flight/Modules/CameraStab/camerastab.c
Normal file
141
flight/Modules/CameraStab/camerastab.c
Normal file
@ -0,0 +1,141 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup CameraStab Camera Stabilization Module
|
||||
* @brief Camera stabilization module
|
||||
* Updates accessory outputs with values appropriate for camera stabilization
|
||||
* @{
|
||||
*
|
||||
* @file camerastab.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Stabilize camera against the roll pitch and yaw of aircraft
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/**
|
||||
* Output object: Accessory
|
||||
*
|
||||
* This module will periodically calculate the output values for stabilizing the camera
|
||||
*
|
||||
* UAVObjects are automatically generated by the UAVObjectGenerator from
|
||||
* the object definition XML file.
|
||||
*
|
||||
* Modules have no API, all communication to other modules is done through UAVObjects.
|
||||
* However modules may use the API exposed by shared libraries.
|
||||
* See the OpenPilot wiki for more details.
|
||||
* http://www.openpilot.org/OpenPilot_Application_Architecture
|
||||
*
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
|
||||
#include "accessorydesired.h"
|
||||
#include "attitudeactual.h"
|
||||
#include "camerastabsettings.h"
|
||||
#include "cameradesired.h"
|
||||
|
||||
//
|
||||
// Configuration
|
||||
//
|
||||
#define SAMPLE_PERIOD_MS 10
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
|
||||
// Private functions
|
||||
static void attitudeUpdated(UAVObjEvent* ev);
|
||||
static float bound(float val);
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t CameraStabInitialize(void)
|
||||
{
|
||||
static UAVObjEvent ev;
|
||||
ev.obj = AttitudeActualHandle();
|
||||
ev.instId = 0;
|
||||
ev.event = 0;
|
||||
|
||||
CameraStabSettingsInitialize();
|
||||
CameraDesiredInitialize();
|
||||
|
||||
EventPeriodicCallbackCreate(&ev, attitudeUpdated, SAMPLE_PERIOD_MS / portTICK_RATE_MS);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void attitudeUpdated(UAVObjEvent* ev)
|
||||
{
|
||||
if (ev->obj != AttitudeActualHandle())
|
||||
return;
|
||||
|
||||
float attitude;
|
||||
float output;
|
||||
AccessoryDesiredData accessory;
|
||||
|
||||
CameraStabSettingsData cameraStab;
|
||||
CameraStabSettingsGet(&cameraStab);
|
||||
|
||||
// Read any input channels
|
||||
float inputs[3] = {0,0,0};
|
||||
if(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_ROLL] != CAMERASTABSETTINGS_INPUTS_NONE) {
|
||||
if(AccessoryDesiredInstGet(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_ROLL] - CAMERASTABSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0)
|
||||
inputs[0] = accessory.AccessoryVal * cameraStab.InputRange[CAMERASTABSETTINGS_INPUTRANGE_ROLL];
|
||||
}
|
||||
if(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_PITCH] != CAMERASTABSETTINGS_INPUTS_NONE) {
|
||||
if(AccessoryDesiredInstGet(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_PITCH] - CAMERASTABSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0)
|
||||
inputs[1] = accessory.AccessoryVal * cameraStab.InputRange[CAMERASTABSETTINGS_INPUTRANGE_PITCH];
|
||||
}
|
||||
if(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_YAW] != CAMERASTABSETTINGS_INPUTS_NONE) {
|
||||
if(AccessoryDesiredInstGet(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_YAW] - CAMERASTABSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0)
|
||||
inputs[2] = accessory.AccessoryVal * cameraStab.InputRange[CAMERASTABSETTINGS_INPUTRANGE_YAW];
|
||||
}
|
||||
|
||||
// Set output channels
|
||||
AttitudeActualRollGet(&attitude);
|
||||
output = bound((attitude + inputs[0]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_ROLL]);
|
||||
CameraDesiredRollSet(&output);
|
||||
|
||||
AttitudeActualPitchGet(&attitude);
|
||||
output = bound((attitude + inputs[1]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_PITCH]);
|
||||
CameraDesiredPitchSet(&output);
|
||||
|
||||
AttitudeActualYawGet(&attitude);
|
||||
output = bound((attitude + inputs[2]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_YAW]);
|
||||
CameraDesiredYawSet(&output);
|
||||
|
||||
}
|
||||
|
||||
float bound(float val)
|
||||
{
|
||||
return (val > 1) ? 1 :
|
||||
(val < -1) ? -1 :
|
||||
val;
|
||||
}
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
@ -1,45 +1,42 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file uavobjectsinit.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Initialize all objects.
|
||||
* Automatically generated by the UAVObjectGenerator.
|
||||
*
|
||||
* @note This is an automatically generated file.
|
||||
* DO NOT modify manually.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
|
||||
/**
|
||||
* Function used to initialize the first instance of each object.
|
||||
* This file is automatically updated by the UAVObjectGenerator.
|
||||
*/
|
||||
extern initcall_t __uavobj_initcall_start[], __uavobj_initcall_end[];
|
||||
|
||||
void UAVObjectsInitializeAll()
|
||||
{
|
||||
initcall_t *fn;
|
||||
int32_t ret;
|
||||
|
||||
for (fn = __uavobj_initcall_start; fn < __uavobj_initcall_end; fn++)
|
||||
ret = (*fn)();
|
||||
}
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup BatteryModule Battery Module
|
||||
* @{
|
||||
*
|
||||
* @file battery.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Module to read the battery Voltage and Current periodically and set alarms appropriately.
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef BATTERY_H
|
||||
#define BATTERY_H
|
||||
|
||||
#include "openpilot.h"
|
||||
|
||||
int32_t CameraStabInitialize(void);
|
||||
|
||||
#endif // BATTERY_H
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -91,6 +91,9 @@ static void resetTask(UAVObjEvent *);
|
||||
MODULE_INITCALL(FirmwareIAPInitialize, 0)
|
||||
int32_t FirmwareIAPInitialize()
|
||||
{
|
||||
|
||||
FirmwareIAPObjInitialize();
|
||||
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
|
||||
data.BoardType= bdinfo->board_type;
|
||||
|
@ -74,7 +74,11 @@ int32_t FlightPlanStart()
|
||||
int32_t FlightPlanInitialize()
|
||||
{
|
||||
taskHandle = NULL;
|
||||
|
||||
|
||||
FlightPlanStatusInitialize();
|
||||
FlightPlanControlInitialize();
|
||||
FlightPlanSettingsInitialize();
|
||||
|
||||
// Listen for object updates
|
||||
FlightPlanControlConnectCallback(&objectUpdatedCb);
|
||||
|
||||
|
@ -46,6 +46,7 @@
|
||||
#include "gpsposition.h"
|
||||
#include "homelocation.h"
|
||||
#include "gpstime.h"
|
||||
#include "gpssatellites.h"
|
||||
#include "WorldMagModel.h"
|
||||
#include "CoordinateConversions.h"
|
||||
|
||||
@ -124,6 +125,13 @@ int32_t GPSStart(void)
|
||||
*/
|
||||
int32_t GPSInitialize(void)
|
||||
{
|
||||
GPSPositionInitialize();
|
||||
GPSTimeInitialize();
|
||||
GPSSatellitesInitialize();
|
||||
#ifdef PIOS_GPS_SETS_HOMELOCATION
|
||||
HomeLocationInitialize();
|
||||
#endif
|
||||
|
||||
// TODO: Get gps settings object
|
||||
gpsPort = PIOS_COM_GPS;
|
||||
|
||||
@ -191,14 +199,12 @@ static void gpsTask(void *parameters)
|
||||
// Loop forever
|
||||
while (1)
|
||||
{
|
||||
uint8_t c;
|
||||
#ifdef ENABLE_GPS_BINARY_GTOP
|
||||
// GTOP BINARY GPS mode
|
||||
|
||||
while (PIOS_COM_ReceiveBufferUsed(gpsPort) > 0)
|
||||
while (PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, xDelay) > 0)
|
||||
{
|
||||
uint8_t c;
|
||||
PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, 0);
|
||||
|
||||
if (GTOP_BIN_update_position(c, &numChecksumErrors, &numParsingErrors) >= 0)
|
||||
{
|
||||
numUpdates++;
|
||||
@ -213,10 +219,8 @@ static void gpsTask(void *parameters)
|
||||
// NMEA or SINGLE-SENTENCE GPS mode
|
||||
|
||||
// This blocks the task until there is something on the buffer
|
||||
while (PIOS_COM_ReceiveBufferUsed(gpsPort) > 0)
|
||||
while (PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, xDelay) > 0)
|
||||
{
|
||||
uint8_t c;
|
||||
PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, 0);
|
||||
|
||||
// detect start while acquiring stream
|
||||
if (!start_flag && (c == '$'))
|
||||
@ -354,8 +358,6 @@ static void gpsTask(void *parameters)
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
}
|
||||
|
||||
// Block task until next update
|
||||
vTaskDelay(xDelay);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -97,6 +97,12 @@ int32_t GuidanceStart()
|
||||
*/
|
||||
int32_t GuidanceInitialize()
|
||||
{
|
||||
|
||||
GuidanceSettingsInitialize();
|
||||
PositionDesiredInitialize();
|
||||
NedAccelInitialize();
|
||||
VelocityDesiredInitialize();
|
||||
|
||||
// Create object queue
|
||||
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
|
||||
|
@ -103,17 +103,15 @@ static bool updateRcvrActivity(struct rcvr_activity_fsm * fsm);
|
||||
#define assumptions (assumptions1 && assumptions3 && assumptions5 && assumptions7 && assumptions8 && assumptions_flightmode)
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
* Module starting
|
||||
*/
|
||||
int32_t ManualControlStart()
|
||||
{
|
||||
/* Check the assumptions about uavobject enum's are correct */
|
||||
if(!assumptions)
|
||||
return -1;
|
||||
// Start main task
|
||||
xTaskCreate(manualControlTask, (signed char *)"ManualControl", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_MANUALCONTROL, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -123,6 +121,17 @@ int32_t ManualControlStart()
|
||||
int32_t ManualControlInitialize()
|
||||
{
|
||||
|
||||
/* Check the assumptions about uavobject enum's are correct */
|
||||
if(!assumptions)
|
||||
return -1;
|
||||
|
||||
AccessoryDesiredInitialize();
|
||||
ManualControlCommandInitialize();
|
||||
FlightStatusInitialize();
|
||||
StabilizationDesiredInitialize();
|
||||
|
||||
ManualControlSettingsInitialize();
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(ManualControlInitialize, ManualControlStart)
|
||||
@ -737,4 +746,3 @@ bool validInputRange(int16_t min, int16_t max, uint16_t value)
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
@ -40,8 +40,6 @@
|
||||
#include "attitudeactual.h"
|
||||
#include "attituderaw.h"
|
||||
#include "flightstatus.h"
|
||||
#include "systemsettings.h"
|
||||
#include "ahrssettings.h"
|
||||
#include "manualcontrol.h" // Just to get a macro
|
||||
#include "CoordinateConversions.h"
|
||||
|
||||
@ -115,6 +113,11 @@ int32_t StabilizationStart()
|
||||
int32_t StabilizationInitialize()
|
||||
{
|
||||
// Initialize variables
|
||||
StabilizationSettingsInitialize();
|
||||
ActuatorDesiredInitialize();
|
||||
#if defined(DIAGNOSTICS)
|
||||
RateDesiredInitialize();
|
||||
#endif
|
||||
|
||||
// Create object queue
|
||||
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
@ -147,7 +150,6 @@ static void stabilizationTask(void* parameters)
|
||||
RateDesiredData rateDesired;
|
||||
AttitudeActualData attitudeActual;
|
||||
AttitudeRawData attitudeRaw;
|
||||
SystemSettingsData systemSettings;
|
||||
FlightStatusData flightStatus;
|
||||
|
||||
SettingsUpdatedCb((UAVObjEvent *) NULL);
|
||||
@ -175,8 +177,10 @@ static void stabilizationTask(void* parameters)
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
AttitudeActualGet(&attitudeActual);
|
||||
AttitudeRawGet(&attitudeRaw);
|
||||
|
||||
#if defined(DIAGNOSTICS)
|
||||
RateDesiredGet(&rateDesired);
|
||||
SystemSettingsGet(&systemSettings);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_QUATERNION_STABILIZATION)
|
||||
// Quaternion calculation of error in each axis. Uses more memory.
|
||||
@ -273,7 +277,9 @@ static void stabilizationTask(void* parameters)
|
||||
}
|
||||
|
||||
uint8_t shouldUpdate = 1;
|
||||
#if defined(DIAGNOSTICS)
|
||||
RateDesiredSet(&rateDesired);
|
||||
#endif
|
||||
ActuatorDesiredGet(&actuatorDesired);
|
||||
//Calculate desired command
|
||||
for(int8_t ct=0; ct< MAX_AXES; ct++)
|
||||
|
@ -43,7 +43,9 @@
|
||||
#include "objectpersistence.h"
|
||||
#include "flightstatus.h"
|
||||
#include "systemstats.h"
|
||||
#include "systemsettings.h"
|
||||
#include "i2cstats.h"
|
||||
#include "taskinfo.h"
|
||||
#include "watchdogstatus.h"
|
||||
#include "taskmonitor.h"
|
||||
#include "pios_config.h"
|
||||
@ -73,16 +75,18 @@
|
||||
static uint32_t idleCounter;
|
||||
static uint32_t idleCounterClear;
|
||||
static xTaskHandle systemTaskHandle;
|
||||
static int32_t stackOverflow;
|
||||
static bool stackOverflow;
|
||||
static bool mallocFailed;
|
||||
|
||||
// Private functions
|
||||
static void objectUpdatedCb(UAVObjEvent * ev);
|
||||
static void updateStats();
|
||||
static void updateI2Cstats();
|
||||
static void updateWDGstats();
|
||||
static void updateSystemAlarms();
|
||||
static void systemTask(void *parameters);
|
||||
|
||||
#if defined(DIAGNOSTICS)
|
||||
static void updateI2Cstats();
|
||||
static void updateWDGstats();
|
||||
#endif
|
||||
/**
|
||||
* Create the module task.
|
||||
* \returns 0 on success or -1 if initialization failed
|
||||
@ -90,7 +94,8 @@ static void systemTask(void *parameters);
|
||||
int32_t SystemModStart(void)
|
||||
{
|
||||
// Initialize vars
|
||||
stackOverflow = 0;
|
||||
stackOverflow = false;
|
||||
mallocFailed = false;
|
||||
// Create system task
|
||||
xTaskCreate(systemTask, (signed char *)"System", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &systemTaskHandle);
|
||||
// Register task
|
||||
@ -106,6 +111,16 @@ int32_t SystemModStart(void)
|
||||
int32_t SystemModInitialize(void)
|
||||
{
|
||||
|
||||
// Must registers objects here for system thread because ObjectManager started in OpenPilotInit
|
||||
SystemSettingsInitialize();
|
||||
SystemStatsInitialize();
|
||||
ObjectPersistenceInitialize();
|
||||
#if defined(DIAGNOSTICS)
|
||||
TaskInfoInitialize();
|
||||
I2CStatsInitialize();
|
||||
WatchdogStatusInitialize();
|
||||
#endif
|
||||
|
||||
SystemModStart();
|
||||
|
||||
return 0;
|
||||
@ -137,9 +152,10 @@ static void systemTask(void *parameters)
|
||||
|
||||
// Update the system alarms
|
||||
updateSystemAlarms();
|
||||
#if defined(DIAGNOSTICS)
|
||||
updateI2Cstats();
|
||||
updateWDGstats();
|
||||
|
||||
#endif
|
||||
// Update the task status object
|
||||
TaskMonitorUpdateAll();
|
||||
|
||||
@ -230,6 +246,11 @@ static void objectUpdatedCb(UAVObjEvent * ev)
|
||||
|| objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) {
|
||||
retval = UAVObjDeleteMetaobjects();
|
||||
}
|
||||
} else if (objper.Operation == OBJECTPERSISTENCE_OPERATION_FULLERASE) {
|
||||
retval = -1;
|
||||
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
|
||||
retval = PIOS_FLASHFS_Format();
|
||||
#endif
|
||||
}
|
||||
if(retval == 0) {
|
||||
objper.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED;
|
||||
@ -241,9 +262,7 @@ static void objectUpdatedCb(UAVObjEvent * ev)
|
||||
/**
|
||||
* Called periodically to update the I2C statistics
|
||||
*/
|
||||
#if defined(ARCH_POSIX) || defined(ARCH_WIN32)
|
||||
static void updateI2Cstats() {} //Posix and win32 don't have I2C
|
||||
#else
|
||||
#if defined(DIAGNOSTICS)
|
||||
static void updateI2Cstats()
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
@ -263,7 +282,6 @@ static void updateI2Cstats()
|
||||
I2CStatsSet(&i2cStats);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
static void updateWDGstats()
|
||||
{
|
||||
@ -272,6 +290,8 @@ static void updateWDGstats()
|
||||
watchdogStatus.ActiveFlags = PIOS_WDG_GetActiveFlags();
|
||||
WatchdogStatusSet(&watchdogStatus);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* Called periodically to update the system stats
|
||||
@ -399,12 +419,19 @@ static void updateSystemAlarms()
|
||||
}
|
||||
|
||||
// Check for stack overflow
|
||||
if (stackOverflow == 1) {
|
||||
if (stackOverflow) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_STACKOVERFLOW, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_STACKOVERFLOW);
|
||||
}
|
||||
|
||||
// Check for malloc failures
|
||||
if (mallocFailed) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_SDCARD)
|
||||
// Check for SD card
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
@ -443,9 +470,29 @@ void vApplicationIdleHook(void)
|
||||
/**
|
||||
* Called by the RTOS when a stack overflow is detected.
|
||||
*/
|
||||
#define DEBUG_STACK_OVERFLOW 0
|
||||
void vApplicationStackOverflowHook(xTaskHandle * pxTask, signed portCHAR * pcTaskName)
|
||||
{
|
||||
stackOverflow = 1;
|
||||
stackOverflow = true;
|
||||
#if DEBUG_STACK_OVERFLOW
|
||||
static volatile bool wait_here = true;
|
||||
while(wait_here);
|
||||
wait_here = true;
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* Called by the RTOS when a malloc call fails.
|
||||
*/
|
||||
#define DEBUG_MALLOC_FAILURES 0
|
||||
void vApplicationMallocFailedHook(void)
|
||||
{
|
||||
mallocFailed = true;
|
||||
#if DEBUG_MALLOC_FAILURES
|
||||
static volatile bool wait_here = true;
|
||||
while(wait_here);
|
||||
wait_here = true;
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -67,6 +67,7 @@ static uint32_t txErrors;
|
||||
static uint32_t txRetries;
|
||||
static TelemetrySettingsData settings;
|
||||
static uint32_t timeOfLastObjectUpdate;
|
||||
static UAVTalkConnection uavTalkCon;
|
||||
|
||||
// Private functions
|
||||
static void telemetryTxTask(void *parameters);
|
||||
@ -88,7 +89,13 @@ static void updateSettings();
|
||||
*/
|
||||
int32_t TelemetryStart(void)
|
||||
{
|
||||
|
||||
// Process all registered objects and connect queue for updates
|
||||
UAVObjIterate(®isterObject);
|
||||
|
||||
// Listen to objects of interest
|
||||
GCSTelemetryStatsConnectQueue(priorityQueue);
|
||||
TelemetrySettingsConnectQueue(priorityQueue);
|
||||
|
||||
// Start telemetry tasks
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
|
||||
xTaskCreate(telemetryRxTask, (signed char *)"TelRx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
|
||||
@ -111,6 +118,10 @@ int32_t TelemetryStart(void)
|
||||
int32_t TelemetryInitialize(void)
|
||||
{
|
||||
UAVObjEvent ev;
|
||||
|
||||
FlightTelemetryStatsInitialize();
|
||||
GCSTelemetryStatsInitialize();
|
||||
TelemetrySettingsInitialize();
|
||||
|
||||
// Initialize vars
|
||||
timeOfLastObjectUpdate = 0;
|
||||
@ -120,25 +131,19 @@ int32_t TelemetryInitialize(void)
|
||||
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
|
||||
priorityQueue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
#endif
|
||||
|
||||
// Get telemetry settings object
|
||||
|
||||
// Get telemetry settings object
|
||||
updateSettings();
|
||||
|
||||
|
||||
// Initialise UAVTalk
|
||||
UAVTalkInitialize(&transmitData);
|
||||
|
||||
// Process all registered objects and connect queue for updates
|
||||
UAVObjIterate(®isterObject);
|
||||
|
||||
uavTalkCon = UAVTalkInitialize(&transmitData,256);
|
||||
|
||||
// Create periodic event that will be used to update the telemetry stats
|
||||
txErrors = 0;
|
||||
txRetries = 0;
|
||||
memset(&ev, 0, sizeof(UAVObjEvent));
|
||||
EventPeriodicQueueCreate(&ev, priorityQueue, STATS_UPDATE_PERIOD_MS);
|
||||
|
||||
// Listen to objects of interest
|
||||
GCSTelemetryStatsConnectQueue(priorityQueue);
|
||||
TelemetrySettingsConnectQueue(priorityQueue);
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
@ -235,7 +240,7 @@ static void processObjEvent(UAVObjEvent * ev)
|
||||
if (ev->event == EV_UPDATED || ev->event == EV_UPDATED_MANUAL) {
|
||||
// Send update to GCS (with retries)
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendObject(ev->obj, ev->instId, metadata.telemetryAcked, REQ_TIMEOUT_MS); // call blocks until ack is received or timeout
|
||||
success = UAVTalkSendObject(uavTalkCon, ev->obj, ev->instId, metadata.telemetryAcked, REQ_TIMEOUT_MS); // call blocks until ack is received or timeout
|
||||
++retries;
|
||||
}
|
||||
// Update stats
|
||||
@ -246,7 +251,7 @@ static void processObjEvent(UAVObjEvent * ev)
|
||||
} else if (ev->event == EV_UPDATE_REQ) {
|
||||
// Request object update from GCS (with retries)
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendObjectRequest(ev->obj, ev->instId, REQ_TIMEOUT_MS); // call blocks until update is received or timeout
|
||||
success = UAVTalkSendObjectRequest(uavTalkCon, ev->obj, ev->instId, REQ_TIMEOUT_MS); // call blocks until update is received or timeout
|
||||
++retries;
|
||||
}
|
||||
// Update stats
|
||||
@ -326,7 +331,7 @@ static void telemetryRxTask(void *parameters)
|
||||
bytes_to_process = PIOS_COM_ReceiveBuffer(inputPort, serial_data, sizeof(serial_data), 500);
|
||||
if (bytes_to_process > 0) {
|
||||
for (uint8_t i = 0; i < bytes_to_process; i++) {
|
||||
UAVTalkProcessInputStream(serial_data[i]);
|
||||
UAVTalkProcessInputStream(uavTalkCon,serial_data[i]);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
@ -426,8 +431,8 @@ static void updateTelemetryStats()
|
||||
uint32_t timeNow;
|
||||
|
||||
// Get stats
|
||||
UAVTalkGetStats(&utalkStats);
|
||||
UAVTalkResetStats();
|
||||
UAVTalkGetStats(uavTalkCon, &utalkStats);
|
||||
UAVTalkResetStats(uavTalkCon);
|
||||
|
||||
// Get object data
|
||||
FlightTelemetryStatsGet(&flightStats);
|
||||
|
@ -135,7 +135,6 @@ SRC += $(OPSYSTEM)/taskmonitor.c
|
||||
SRC += $(OPUAVTALK)/uavtalk.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectsinit_linker.c
|
||||
else
|
||||
## TESTCODE
|
||||
SRC += $(OPTESTS)/test_common.c
|
||||
@ -388,6 +387,9 @@ ifeq ($(DEBUG),YES)
|
||||
CFLAGS = -g$(DEBUGF) -DDEBUG
|
||||
endif
|
||||
|
||||
# OP has enough memory to always enable optional objects
|
||||
CFLAGS += -DDIAGNOSTICS
|
||||
|
||||
CFLAGS += -O$(OPT)
|
||||
CFLAGS += -mcpu=$(MCU)
|
||||
CFLAGS += $(CDEFS)
|
||||
|
@ -41,14 +41,12 @@ static xSemaphoreHandle lock;
|
||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
||||
|
||||
/**
|
||||
* Initialize the alarms library
|
||||
* Initialize the alarms library
|
||||
*/
|
||||
int32_t AlarmsInitialize(void)
|
||||
{
|
||||
SystemAlarmsInitialize();
|
||||
lock = xSemaphoreCreateRecursiveMutex();
|
||||
//do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that
|
||||
//AlarmsClearAll();
|
||||
//AlarmsDefaultAll();
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -56,7 +54,7 @@ int32_t AlarmsInitialize(void)
|
||||
* Set an alarm
|
||||
* @param alarm The system alarm to be modified
|
||||
* @param severity The alarm severity
|
||||
* @return 0 if success, -1 if an error
|
||||
* @return 0 if success, -1 if an error
|
||||
*/
|
||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
||||
{
|
||||
@ -151,7 +149,7 @@ void AlarmsClearAll()
|
||||
|
||||
/**
|
||||
* Check if there are any alarms with the given or higher severity
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
*/
|
||||
int32_t AlarmsHasWarnings()
|
||||
{
|
||||
@ -208,5 +206,5 @@ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
*/
|
||||
|
||||
|
@ -26,6 +26,7 @@
|
||||
#define configUSE_PREEMPTION 1
|
||||
#define configUSE_IDLE_HOOK 1
|
||||
#define configUSE_TICK_HOOK 0
|
||||
#define configUSE_MALLOC_FAILED_HOOK 1
|
||||
#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 )
|
||||
#define configTICK_RATE_HZ ( ( portTickType ) 1000 )
|
||||
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )
|
||||
@ -39,7 +40,7 @@
|
||||
#define configUSE_RECURSIVE_MUTEXES 1
|
||||
#define configUSE_COUNTING_SEMAPHORES 0
|
||||
#define configUSE_ALTERNATIVE_API 0
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
//#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
#define configQUEUE_REGISTRY_SIZE 10
|
||||
|
||||
/* Co-routine definitions. */
|
||||
@ -72,7 +73,9 @@ NVIC value of 255. */
|
||||
#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15
|
||||
|
||||
/* Enable run time stats collection */
|
||||
#if defined(DEBUG)
|
||||
#if defined(DIAGNOSTICS)
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
|
||||
#define configGENERATE_RUN_TIME_STATS 1
|
||||
#define INCLUDE_uxTaskGetRunTime 1
|
||||
#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS()\
|
||||
@ -81,6 +84,8 @@ do {\
|
||||
(*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */\
|
||||
} while(0)
|
||||
#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004)/* DWT_CYCCNT */
|
||||
#else
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 1
|
||||
#endif
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32)
|
||||
|
@ -60,6 +60,7 @@
|
||||
//#define PIOS_INCLUDE_HCSR04
|
||||
#define PIOS_INCLUDE_OPAHRS
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_GPS
|
||||
#define PIOS_INCLUDE_SDCARD
|
||||
#define PIOS_INCLUDE_SETTINGS
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
|
@ -36,6 +36,7 @@
|
||||
#define PIOS_INCLUDE_SDCARD
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_GPS
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_TELEMETRY_RF
|
||||
#define PIOS_INCLUDE_UDP
|
||||
|
@ -525,6 +525,7 @@ static const struct pios_spektrum_cfg pios_spektrum_cfg = {
|
||||
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192
|
||||
|
||||
#define PIOS_COM_GPS_RX_BUF_LEN 96
|
||||
#define PIOS_COM_GPS_TX_BUF_LEN 96
|
||||
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
|
||||
@ -1027,7 +1028,6 @@ void PIOS_Board_Init(void) {
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
UAVObjectsInitializeAll();
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/* Initialize the real-time clock and its associated tick */
|
||||
@ -1089,18 +1089,19 @@ void PIOS_Board_Init(void) {
|
||||
break;
|
||||
case HWSETTINGS_OP_FLEXIPORT_GPS:
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
{
|
||||
uint32_t pios_usart_gps_id;
|
||||
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id,
|
||||
rx_buffer, PIOS_COM_GPS_RX_BUF_LEN,
|
||||
NULL, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
{
|
||||
uint32_t pios_usart_gps_id;
|
||||
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id,
|
||||
rx_buffer, PIOS_COM_GPS_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_GPS_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
break;
|
||||
|
@ -29,6 +29,11 @@
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
|
||||
#include "attituderaw.h"
|
||||
#include "attitudeactual.h"
|
||||
#include "positionactual.h"
|
||||
#include "velocityactual.h"
|
||||
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS];
|
||||
@ -66,6 +71,7 @@ const struct pios_udp_cfg pios_udp_aux_cfg = {
|
||||
|
||||
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192
|
||||
#define PIOS_COM_GPS_RX_BUF_LEN 192
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
@ -154,20 +160,27 @@ void PIOS_Board_Init(void) {
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
{
|
||||
uint32_t pios_udp_gps_id;
|
||||
if (PIOS_USART_Init(&pios_udp_gps_id, &pios_udp_gps_cfg)) {
|
||||
if (PIOS_UDP_Init(&pios_udp_gps_id, &pios_udp_gps_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_udp_com_driver, pios_udp_gps_id,
|
||||
rx_buffer, PIOS_COM_GPS_RX_BUF_LEN,
|
||||
NULL, 0)) {
|
||||
tx_buffer, PIOS_COM_GPS_RX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
#endif
|
||||
|
||||
// Initialize these here as posix has no AHRSComms
|
||||
AttitudeRawInitialize();
|
||||
AttitudeActualInitialize();
|
||||
VelocityActualInitialize();
|
||||
PositionActualInitialize();
|
||||
|
||||
}
|
||||
|
||||
|
@ -46,7 +46,10 @@ int32_t TaskMonitorInitialize(void)
|
||||
{
|
||||
lock = xSemaphoreCreateRecursiveMutex();
|
||||
memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM);
|
||||
lastMonitorTime = 0;
|
||||
#if defined(DIAGNOSTICS)
|
||||
lastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE();
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -91,6 +94,7 @@ int32_t TaskMonitorRemove(TaskInfoRunningElem task)
|
||||
*/
|
||||
void TaskMonitorUpdateAll(void)
|
||||
{
|
||||
#if defined(DIAGNOSTICS)
|
||||
TaskInfoData data;
|
||||
int n;
|
||||
|
||||
@ -142,4 +146,5 @@ void TaskMonitorUpdateAll(void)
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
#endif
|
||||
}
|
||||
|
@ -71,6 +71,8 @@ UAVOBJSRCFILENAMES += watchdogstatus
|
||||
UAVOBJSRCFILENAMES += flightstatus
|
||||
UAVOBJSRCFILENAMES += hwsettings
|
||||
UAVOBJSRCFILENAMES += receiveractivity
|
||||
UAVOBJSRCFILENAMES += cameradesired
|
||||
UAVOBJSRCFILENAMES += camerastabsettings
|
||||
|
||||
UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c )
|
||||
UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) )
|
||||
|
@ -51,7 +51,6 @@ extern initmodule_t __module_initcall_start[], __module_initcall_end[];
|
||||
extern void InitModules();
|
||||
extern void StartModules();
|
||||
|
||||
#define UAVOBJ_INITCALL(fn)
|
||||
#define MODULE_INITCALL(ifn, sfn)
|
||||
|
||||
#define MODULE_TASKCREATE_ALL { \
|
||||
|
@ -79,8 +79,15 @@ void PIOS_DEBUG_Panic(const char *msg)
|
||||
PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, "\r%s @0x%x\r", msg, lr);
|
||||
#endif
|
||||
|
||||
// Stay put
|
||||
while (1) ;
|
||||
// tell the user whats going on on commandline too
|
||||
fprintf(stderr,"CRITICAL ERROR: %s\n",msg);
|
||||
|
||||
// this helps debugging: causing a div by zero allows a backtrace
|
||||
// and/or ends execution
|
||||
int b = 0;
|
||||
int a = (2/b);
|
||||
b=a;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -64,6 +64,7 @@ static pios_udp_dev * find_udp_dev_by_id (uint8_t udp)
|
||||
{
|
||||
if (udp >= pios_udp_num_devices) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
PIOS_Assert(0);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
@ -154,6 +155,8 @@ int32_t PIOS_UDP_Init(uint32_t * udp_id, const struct pios_udp_cfg * cfg)
|
||||
|
||||
printf("udp dev %i - socket %i opened - result %i\n",pios_udp_num_devices-1,udp_dev->socket,res);
|
||||
|
||||
*udp_id = pios_udp_num_devices-1;
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
|
@ -38,7 +38,6 @@
|
||||
* and we cannot define a linker script for each of them atm
|
||||
*/
|
||||
|
||||
#define UAVOBJ_INITCALL(fn)
|
||||
#define MODULE_INITCALL(ifn, iparam, sfn, sparam, flags)
|
||||
|
||||
#define MODULE_TASKCREATE_ALL
|
||||
|
@ -116,6 +116,19 @@ int32_t PIOS_FLASHFS_Init()
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Erase the whole flash chip and create the file system
|
||||
* @return 0 if successful, -1 if not
|
||||
*/
|
||||
int32_t PIOS_FLASHFS_Format()
|
||||
{
|
||||
if(PIOS_Flash_W25X_EraseChip() != 0)
|
||||
return -1;
|
||||
if(PIOS_FLASHFS_ClearObjectTableHeader() != 0)
|
||||
return -1;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Erase the headers for all objects in the flash chip
|
||||
* @return 0 if successful, -1 if not
|
||||
|
@ -18,16 +18,6 @@ SECTIONS
|
||||
*(.rodata .rodata* .gnu.linkonce.r.*)
|
||||
} > BL_FLASH
|
||||
|
||||
/* init sections */
|
||||
.initcalluavobj.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_start = .;
|
||||
KEEP(*(.initcalluavobj.init))
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_end = .;
|
||||
} > BL_FLASH
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
|
@ -22,16 +22,6 @@ SECTIONS
|
||||
*(.rodata .rodata* .gnu.linkonce.r.*)
|
||||
} > FLASH
|
||||
|
||||
/* init sections */
|
||||
.initcalluavobj.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_start = .;
|
||||
KEEP(*(.initcalluavobj.init))
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
/* module sections */
|
||||
.initcallmodule.init :
|
||||
{
|
||||
|
@ -207,16 +207,6 @@ SECTIONS
|
||||
} > BL_FLASH
|
||||
|
||||
|
||||
/* init sections */
|
||||
.initcalluavobj.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_start = .;
|
||||
KEEP(*(.initcalluavobj.init))
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_end = .;
|
||||
} > BL_FLASH
|
||||
|
||||
/* the program code is stored in the .text section, which goes to Flash */
|
||||
.text :
|
||||
{
|
||||
|
@ -206,16 +206,6 @@ SECTIONS
|
||||
. = ALIGN(4);
|
||||
} > FLASH
|
||||
|
||||
|
||||
/* init sections */
|
||||
.initcalluavobj.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_start = .;
|
||||
KEEP(*(.initcalluavobj.init))
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_end = .;
|
||||
} > FLASH
|
||||
|
||||
/* the program code is stored in the .text section, which goes to Flash */
|
||||
.text :
|
||||
|
@ -179,17 +179,6 @@ SECTIONS
|
||||
. = ALIGN(4);
|
||||
} > BL_FLASH
|
||||
|
||||
|
||||
/* init sections */
|
||||
.initcalluavobj.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_start = .;
|
||||
KEEP(*(.initcalluavobj.init))
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_end = .;
|
||||
} > BL_FLASH
|
||||
|
||||
/* the program code is stored in the .text section, which goes to Flash */
|
||||
.text :
|
||||
{
|
||||
|
@ -181,17 +181,6 @@ SECTIONS
|
||||
*(.flashtext) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
|
||||
/* init sections */
|
||||
.initcalluavobj.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_start = .;
|
||||
KEEP(*(.initcalluavobj.init))
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
/* module sections */
|
||||
.initcallmodule.init :
|
||||
|
@ -8,7 +8,6 @@
|
||||
*
|
||||
* @file pios_spektrum.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org)
|
||||
* @brief USART commands. Inits USARTs, controls USARTs & Interrupt handlers. (STM32 dependent)
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
@ -113,7 +112,7 @@ static struct pios_spektrum_dev * PIOS_SPEKTRUM_alloc(void)
|
||||
#endif
|
||||
|
||||
static void PIOS_SPEKTRUM_Supervisor(uint32_t spektrum_id);
|
||||
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg);
|
||||
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg, uint8_t bind);
|
||||
static int32_t PIOS_SPEKTRUM_UpdateFSM(struct pios_spektrum_fsm * fsm, uint8_t b);
|
||||
|
||||
static uint16_t PIOS_SPEKTRUM_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
|
||||
@ -221,7 +220,7 @@ static int32_t PIOS_SPEKTRUM_UpdateFSM(struct pios_spektrum_fsm * fsm, uint8_t b
|
||||
/**
|
||||
* Bind and Initialise Spektrum satellite receiver
|
||||
*/
|
||||
int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, bool bind)
|
||||
int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t bind)
|
||||
{
|
||||
PIOS_DEBUG_Assert(spektrum_id);
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
@ -236,7 +235,7 @@ int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cf
|
||||
spektrum_dev->cfg = cfg;
|
||||
|
||||
if (bind) {
|
||||
PIOS_SPEKTRUM_Bind(cfg);
|
||||
PIOS_SPEKTRUM_Bind(cfg,bind);
|
||||
}
|
||||
|
||||
PIOS_SPEKTRUM_ResetFSM(&(spektrum_dev->fsm));
|
||||
@ -280,9 +279,15 @@ static int32_t PIOS_SPEKTRUM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
* \output true Successful bind
|
||||
* \output false Bind failed
|
||||
*/
|
||||
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg)
|
||||
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg, uint8_t bind)
|
||||
{
|
||||
#define BIND_PULSES 5
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Pin = cfg->bind.init.GPIO_Pin;
|
||||
GPIO_InitStructure.GPIO_Speed = cfg->bind.init.GPIO_Speed;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
|
||||
|
||||
/* just to limit bind pulses */
|
||||
bind=(bind<=10)?bind:10;
|
||||
|
||||
GPIO_Init(cfg->bind.gpio, &cfg->bind.init);
|
||||
/* RX line, set high */
|
||||
@ -291,7 +296,7 @@ static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg)
|
||||
/* on CC works upto 140ms, I guess bind window is around 20-140ms after powerup */
|
||||
PIOS_DELAY_WaitmS(60);
|
||||
|
||||
for (int i = 0; i < BIND_PULSES ; i++) {
|
||||
for (int i = 0; i < bind ; i++) {
|
||||
/* RX line, drive low for 120us */
|
||||
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
@ -300,6 +305,7 @@ static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg)
|
||||
PIOS_DELAY_WaituS(120);
|
||||
}
|
||||
/* RX line, set input and wait for data, PIOS_SPEKTRUM_Init */
|
||||
GPIO_Init(cfg->bind.gpio, &GPIO_InitStructure);
|
||||
|
||||
return true;
|
||||
}
|
||||
@ -328,6 +334,7 @@ static void PIOS_SPEKTRUM_Supervisor(uint32_t spektrum_id)
|
||||
fsm->sync_of++;
|
||||
/* watchdog activated after 100ms silence */
|
||||
if (fsm->sync_of > 12) {
|
||||
|
||||
/* signal lost */
|
||||
fsm->sync_of = 0;
|
||||
for (int i = 0; i < PIOS_SPEKTRUM_NUM_INPUTS; i++) {
|
||||
|
@ -32,6 +32,7 @@
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
int32_t PIOS_FLASHFS_Init();
|
||||
int32_t PIOS_FLASHFS_Format();
|
||||
int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data);
|
||||
int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data);
|
||||
int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId);
|
||||
int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId);
|
||||
|
@ -67,7 +67,6 @@ extern initmodule_t __module_initcall_start[], __module_initcall_end[];
|
||||
static initmodule_t __initcall_##fn __attribute__((__used__)) \
|
||||
__attribute__((__section__(".initcall" level ".init"))) = { .fn_minit = ifn, .fn_tinit = sfn };
|
||||
|
||||
#define UAVOBJ_INITCALL(fn) __define_initcall("uavobj",fn,1)
|
||||
#define MODULE_INITCALL(ifn, sfn) __define_module_initcall("module", ifn, sfn)
|
||||
|
||||
#define MODULE_INITIALISE_ALL { for (initmodule_t *fn = __module_initcall_start; fn < __module_initcall_end; fn++) \
|
||||
|
@ -42,7 +42,7 @@ struct pios_spektrum_cfg {
|
||||
|
||||
extern const struct pios_rcvr_driver pios_spektrum_rcvr_driver;
|
||||
|
||||
extern int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, bool bind);
|
||||
extern int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t bind);
|
||||
|
||||
#endif /* PIOS_SPEKTRUM_PRIV_H */
|
||||
|
||||
|
@ -85,6 +85,7 @@
|
||||
6549E0D21279B3C800C5476F /* fifo_buffer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = fifo_buffer.c; sourceTree = "<group>"; };
|
||||
6549E0D31279B3CF00C5476F /* fifo_buffer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fifo_buffer.h; sourceTree = "<group>"; };
|
||||
655268BC121FBD2900410C6E /* ahrscalibration.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrscalibration.xml; sourceTree = "<group>"; };
|
||||
655B1A8E13B2FC0900B0E48D /* camerastabsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = camerastabsettings.xml; sourceTree = "<group>"; };
|
||||
656268C612DC1923007B0A0F /* nedaccel.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = nedaccel.xml; sourceTree = "<group>"; };
|
||||
6562BE1713CCAD0600C823E8 /* pios_rcvr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rcvr.c; sourceTree = "<group>"; };
|
||||
65632DF51251650300469B77 /* pios_board.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_board.h; sourceTree = "<group>"; };
|
||||
@ -2680,7 +2681,6 @@
|
||||
65C35E7912EFB2F3004811C2 /* watchdogstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = watchdogstatus.xml; sourceTree = "<group>"; };
|
||||
65C35E9E12F0A834004811C2 /* uavobjecttemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjecttemplate.c; sourceTree = "<group>"; };
|
||||
65C35E9F12F0A834004811C2 /* uavobjectsinittemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectsinittemplate.c; sourceTree = "<group>"; };
|
||||
65C35EA012F0A834004811C2 /* uavobjectsinit_cc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectsinit_cc.c; sourceTree = "<group>"; };
|
||||
65C35EA112F0A834004811C2 /* uavobjectmanager.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectmanager.c; sourceTree = "<group>"; };
|
||||
65C35EA312F0A834004811C2 /* eventdispatcher.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = eventdispatcher.h; sourceTree = "<group>"; };
|
||||
65C35EA412F0A834004811C2 /* uavobjectmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectmanager.h; sourceTree = "<group>"; };
|
||||
@ -2690,9 +2690,13 @@
|
||||
65C35EA812F0A834004811C2 /* eventdispatcher.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = eventdispatcher.c; sourceTree = "<group>"; };
|
||||
65C35F6612F0DC2D004811C2 /* attitude.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = attitude.c; sourceTree = "<group>"; };
|
||||
65C35F6812F0DC2D004811C2 /* attitude.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = attitude.h; sourceTree = "<group>"; };
|
||||
65C9903C13A871B90082BD60 /* camerastab.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = camerastab.c; sourceTree = "<group>"; };
|
||||
65C9903E13A871B90082BD60 /* camerastab.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = camerastab.h; sourceTree = "<group>"; };
|
||||
65D2CA841248F9A400B1E7D6 /* mixersettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixersettings.xml; sourceTree = "<group>"; };
|
||||
65D2CA851248F9A400B1E7D6 /* mixerstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixerstatus.xml; sourceTree = "<group>"; };
|
||||
65DEA79113F2143B00095B06 /* cameradesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = cameradesired.xml; sourceTree = "<group>"; };
|
||||
65E410AE12F65AEA00725888 /* attitudesettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitudesettings.xml; sourceTree = "<group>"; };
|
||||
65E6D80713E3A4D0002A557A /* hwsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = hwsettings.xml; sourceTree = "<group>"; };
|
||||
65E6DF7112E02E8E00058553 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||
65E6DF7312E02E8E00058553 /* alarms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = alarms.c; sourceTree = "<group>"; };
|
||||
65E6DF7412E02E8E00058553 /* coptercontrol.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = coptercontrol.c; sourceTree = "<group>"; };
|
||||
@ -3208,6 +3212,7 @@
|
||||
650D8E2812DFE16400D05CC9 /* Altitude */,
|
||||
65C35F6512F0DC2D004811C2 /* Attitude */,
|
||||
650D8E2E12DFE16400D05CC9 /* Battery */,
|
||||
65C9903B13A871B90082BD60 /* CameraStab */,
|
||||
650D8E3212DFE16400D05CC9 /* Example */,
|
||||
650D8E3B12DFE16400D05CC9 /* FirmwareIAP */,
|
||||
650D8E3F12DFE16400D05CC9 /* FlightPlan */,
|
||||
@ -3517,7 +3522,6 @@
|
||||
children = (
|
||||
65C35E9E12F0A834004811C2 /* uavobjecttemplate.c */,
|
||||
65C35E9F12F0A834004811C2 /* uavobjectsinittemplate.c */,
|
||||
65C35EA012F0A834004811C2 /* uavobjectsinit_cc.c */,
|
||||
65C35EA112F0A834004811C2 /* uavobjectmanager.c */,
|
||||
65C35EA212F0A834004811C2 /* inc */,
|
||||
65C35EA812F0A834004811C2 /* eventdispatcher.c */,
|
||||
@ -7422,6 +7426,7 @@
|
||||
65C35E4F12EFB2F3004811C2 /* uavobjectdefinition */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65E6D80713E3A4D0002A557A /* hwsettings.xml */,
|
||||
65E8C788139AA2A800E1F979 /* accessorydesired.xml */,
|
||||
65C35E5012EFB2F3004811C2 /* actuatorcommand.xml */,
|
||||
65C35E5112EFB2F3004811C2 /* actuatordesired.xml */,
|
||||
@ -7434,6 +7439,7 @@
|
||||
65E410AE12F65AEA00725888 /* attitudesettings.xml */,
|
||||
65C35E5912EFB2F3004811C2 /* baroaltitude.xml */,
|
||||
65C35E5A12EFB2F3004811C2 /* batterysettings.xml */,
|
||||
655B1A8E13B2FC0900B0E48D /* camerastabsettings.xml */,
|
||||
652C8568132B632A00BFCC70 /* firmwareiapobj.xml */,
|
||||
65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */,
|
||||
65C35E5D12EFB2F3004811C2 /* flightplancontrol.xml */,
|
||||
@ -7468,6 +7474,7 @@
|
||||
65C35E7712EFB2F3004811C2 /* velocityactual.xml */,
|
||||
65C35E7812EFB2F3004811C2 /* velocitydesired.xml */,
|
||||
65C35E7912EFB2F3004811C2 /* watchdogstatus.xml */,
|
||||
65DEA79113F2143B00095B06 /* cameradesired.xml */,
|
||||
);
|
||||
path = uavobjectdefinition;
|
||||
sourceTree = "<group>";
|
||||
@ -7501,6 +7508,23 @@
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65C9903B13A871B90082BD60 /* CameraStab */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65C9903C13A871B90082BD60 /* camerastab.c */,
|
||||
65C9903D13A871B90082BD60 /* inc */,
|
||||
);
|
||||
path = CameraStab;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65C9903D13A871B90082BD60 /* inc */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
65C9903E13A871B90082BD60 /* camerastab.h */,
|
||||
);
|
||||
path = inc;
|
||||
sourceTree = "<group>";
|
||||
};
|
||||
65E6DF7012E02E8E00058553 /* CopterControl */ = {
|
||||
isa = PBXGroup;
|
||||
children = (
|
||||
|
@ -29,4 +29,6 @@
|
||||
|
||||
void UAVObjectsInitializeAll();
|
||||
|
||||
#define UAVOBJECTS_LARGEST $(SIZECALCULATION)
|
||||
|
||||
#endif // UAVOBJECTSINIT_H
|
@ -36,5 +36,7 @@ $(OBJINC)
|
||||
*/
|
||||
void UAVObjectsInitializeAll()
|
||||
{
|
||||
return;
|
||||
// This function is no longer used anyway
|
||||
$(OBJINIT)
|
||||
}
|
||||
|
@ -40,15 +40,19 @@
|
||||
#include "$(NAMELC).h"
|
||||
|
||||
// Private variables
|
||||
static UAVObjHandle handle;
|
||||
static UAVObjHandle handle = NULL;
|
||||
|
||||
/**
|
||||
* Initialize object.
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
* \return -1 Failure to initialize or -2 for already initialized
|
||||
*/
|
||||
int32_t $(NAME)Initialize(void)
|
||||
{
|
||||
// Don't set the handle to null if already registered
|
||||
if(UAVObjGetByID($(NAMEUC)_OBJID) != NULL)
|
||||
return -2;
|
||||
|
||||
// Register object with the object manager
|
||||
handle = UAVObjRegister($(NAMEUC)_OBJID, $(NAMEUC)_NAME, $(NAMEUC)_METANAME, 0,
|
||||
$(NAMEUC)_ISSINGLEINST, $(NAMEUC)_ISSETTINGS, $(NAMEUC)_NUMBYTES, &$(NAME)SetDefaults);
|
||||
@ -64,8 +68,6 @@ int32_t $(NAME)Initialize(void)
|
||||
}
|
||||
}
|
||||
|
||||
UAVOBJ_INITCALL($(NAME)Initialize);
|
||||
|
||||
/**
|
||||
* Initialize object fields and metadata with the default values.
|
||||
* If a default value is not specified the object fields
|
||||
|
@ -29,10 +29,6 @@
|
||||
#ifndef UAVTALK_H
|
||||
#define UAVTALK_H
|
||||
|
||||
// Public constants
|
||||
#define UAVTALK_WAITFOREVER -1
|
||||
#define UAVTALK_NOWAIT 0
|
||||
|
||||
// Public types
|
||||
typedef int32_t (*UAVTalkOutputStream)(uint8_t* data, int32_t length);
|
||||
|
||||
@ -47,14 +43,17 @@ typedef struct {
|
||||
uint32_t rxErrors;
|
||||
} UAVTalkStats;
|
||||
|
||||
typedef void* UAVTalkConnection;
|
||||
|
||||
// Public functions
|
||||
int32_t UAVTalkInitialize(UAVTalkOutputStream outputStream);
|
||||
int32_t UAVTalkSetOutputStream(UAVTalkOutputStream outputStream);
|
||||
int32_t UAVTalkSendObject(UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs);
|
||||
int32_t UAVTalkSendObjectRequest(UAVObjHandle obj, uint16_t instId, int32_t timeoutMs);
|
||||
int32_t UAVTalkProcessInputStream(uint8_t rxbyte);
|
||||
void UAVTalkGetStats(UAVTalkStats* stats);
|
||||
void UAVTalkResetStats();
|
||||
UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream, uint32_t maxPacketSize);
|
||||
int32_t UAVTalkSetOutputStream(UAVTalkConnection connection, UAVTalkOutputStream outputStream);
|
||||
UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connection);
|
||||
int32_t UAVTalkSendObject(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs);
|
||||
int32_t UAVTalkSendObjectRequest(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, int32_t timeoutMs);
|
||||
int32_t UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte);
|
||||
void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats);
|
||||
void UAVTalkResetStats(UAVTalkConnection connection);
|
||||
|
||||
#endif // UAVTALK_H
|
||||
/**
|
||||
|
111
flight/UAVTalk/inc/uavtalk_priv.h
Normal file
111
flight/UAVTalk/inc/uavtalk_priv.h
Normal file
@ -0,0 +1,111 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
||||
* @{
|
||||
* @file uavtalk.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Private include file of the UAVTalk library
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef UAVTALK_PRIV_H
|
||||
#define UAVTALK_PRIV_H
|
||||
|
||||
#include "uavobjectsinit.h"
|
||||
|
||||
// Private types and constants
|
||||
typedef struct {
|
||||
uint8_t sync;
|
||||
uint8_t type;
|
||||
uint16_t size;
|
||||
uint32_t objId;
|
||||
} uavtalk_min_header;
|
||||
#define UAVTALK_MIN_HEADER_LENGTH sizeof(uavtalk_min_header)
|
||||
|
||||
typedef struct {
|
||||
uint8_t sync;
|
||||
uint8_t type;
|
||||
uint16_t size;
|
||||
uint32_t objId;
|
||||
uint16_t instId;
|
||||
} uavtalk_max_header;
|
||||
#define UAVTALK_MAX_HEADER_LENGTH sizeof(uavtalk_max_header)
|
||||
|
||||
typedef uint8_t uavtalk_checksum;
|
||||
#define UAVTALK_CHECKSUM_LENGTH sizeof(uavtalk_checksum)
|
||||
#define UAVTALK_MAX_PAYLOAD_LENGTH (UAVOBJECTS_LARGEST + 1)
|
||||
#define UAVTALK_MIN_PACKET_LENGTH UAVTALK_MAX_HEADER_LENGTH + UAVTALK_CHECKSUM_LENGTH
|
||||
#define UAVTALK_MAX_PACKET_LENGTH UAVTALK_MIN_PACKET_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH
|
||||
|
||||
typedef enum {UAVTALK_STATE_SYNC, UAVTALK_STATE_TYPE, UAVTALK_STATE_SIZE, UAVTALK_STATE_OBJID, UAVTALK_STATE_INSTID, UAVTALK_STATE_DATA, UAVTALK_STATE_CS} UAVTalkRxState;
|
||||
|
||||
typedef struct {
|
||||
UAVObjHandle obj;
|
||||
uint8_t type;
|
||||
uint16_t packet_size;
|
||||
uint32_t objId;
|
||||
uint16_t instId;
|
||||
uint32_t length;
|
||||
uint8_t cs;
|
||||
int32_t rxCount;
|
||||
UAVTalkRxState state;
|
||||
uint16_t rxPacketLength;
|
||||
} UAVTalkInputProcessor;
|
||||
|
||||
typedef struct {
|
||||
uint8_t canari;
|
||||
UAVTalkOutputStream outStream;
|
||||
xSemaphoreHandle lock;
|
||||
xSemaphoreHandle transLock;
|
||||
xSemaphoreHandle respSema;
|
||||
UAVObjHandle respObj;
|
||||
uint16_t respInstId;
|
||||
UAVTalkStats stats;
|
||||
UAVTalkInputProcessor iproc;
|
||||
uint8_t *rxBuffer;
|
||||
uint32_t txSize;
|
||||
uint8_t *txBuffer;
|
||||
} UAVTalkConnectionData;
|
||||
|
||||
#define UAVTALK_CANARI 0xCA
|
||||
#define UAVTALK_WAITFOREVER -1
|
||||
#define UAVTALK_NOWAIT 0
|
||||
#define UAVTALK_SYNC_VAL 0x3C
|
||||
#define UAVTALK_TYPE_MASK 0xF8
|
||||
#define UAVTALK_TYPE_VER 0x20
|
||||
#define UAVTALK_TYPE_OBJ (UAVTALK_TYPE_VER | 0x00)
|
||||
#define UAVTALK_TYPE_OBJ_REQ (UAVTALK_TYPE_VER | 0x01)
|
||||
#define UAVTALK_TYPE_OBJ_ACK (UAVTALK_TYPE_VER | 0x02)
|
||||
#define UAVTALK_TYPE_ACK (UAVTALK_TYPE_VER | 0x03)
|
||||
#define UAVTALK_TYPE_NACK (UAVTALK_TYPE_VER | 0x04)
|
||||
|
||||
//macros
|
||||
#define CHECKCONHANDLE(handle,variable,failcommand) \
|
||||
variable = (UAVTalkConnectionData*) handle; \
|
||||
if (variable == NULL || variable->canari != UAVTALK_CANARI) { \
|
||||
failcommand; \
|
||||
}
|
||||
|
||||
#endif // UAVTALK__PRIV_H
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -30,113 +30,145 @@
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "uavtalk_priv.h"
|
||||
|
||||
// Private constants
|
||||
#define SYNC_VAL 0x3C
|
||||
#define TYPE_MASK 0xF8
|
||||
#define TYPE_VER 0x20
|
||||
#define TYPE_OBJ (TYPE_VER | 0x00)
|
||||
#define TYPE_OBJ_REQ (TYPE_VER | 0x01)
|
||||
#define TYPE_OBJ_ACK (TYPE_VER | 0x02)
|
||||
#define TYPE_ACK (TYPE_VER | 0x03)
|
||||
#define TYPE_NACK (TYPE_VER | 0x04)
|
||||
|
||||
#define MIN_HEADER_LENGTH 8 // sync(1), type (1), size (2), object ID (4)
|
||||
#define MAX_HEADER_LENGTH 10 // sync(1), type (1), size (2), object ID (4), instance ID (2, not used in single objects)
|
||||
|
||||
#define CHECKSUM_LENGTH 1
|
||||
|
||||
#define MAX_PAYLOAD_LENGTH 256
|
||||
|
||||
#define MAX_PACKET_LENGTH (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH)
|
||||
|
||||
|
||||
// Private types
|
||||
typedef enum {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS} RxState;
|
||||
|
||||
// Private variables
|
||||
static UAVTalkOutputStream outStream;
|
||||
static xSemaphoreHandle lock;
|
||||
static xSemaphoreHandle transLock;
|
||||
static xSemaphoreHandle respSema;
|
||||
static UAVObjHandle respObj;
|
||||
static uint16_t respInstId;
|
||||
static uint8_t rxBuffer[MAX_PACKET_LENGTH];
|
||||
static uint8_t txBuffer[MAX_PACKET_LENGTH];
|
||||
static UAVTalkStats stats;
|
||||
|
||||
// Private functions
|
||||
static int32_t objectTransaction(UAVObjHandle objectId, uint16_t instId, uint8_t type, int32_t timeout);
|
||||
static int32_t sendObject(UAVObjHandle obj, uint16_t instId, uint8_t type);
|
||||
static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type);
|
||||
static int32_t sendNack(uint32_t objId);
|
||||
static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length);
|
||||
static void updateAck(UAVObjHandle obj, uint16_t instId);
|
||||
static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle objectId, uint16_t instId, uint8_t type, int32_t timeout);
|
||||
static int32_t sendObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type);
|
||||
static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type);
|
||||
static int32_t sendNack(UAVTalkConnectionData *connection, uint32_t objId);
|
||||
static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length);
|
||||
static void updateAck(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId);
|
||||
|
||||
/**
|
||||
* Initialize the UAVTalk library
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] outputStream Function pointer that is called to send a data buffer
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
int32_t UAVTalkInitialize(UAVTalkOutputStream outputStream)
|
||||
UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream, uint32_t maxPacketSize)
|
||||
{
|
||||
outStream = outputStream;
|
||||
lock = xSemaphoreCreateRecursiveMutex();
|
||||
transLock = xSemaphoreCreateRecursiveMutex();
|
||||
vSemaphoreCreateBinary(respSema);
|
||||
xSemaphoreTake(respSema, 0); // reset to zero
|
||||
UAVTalkResetStats();
|
||||
if (maxPacketSize<1) return 0;
|
||||
// allocate object
|
||||
UAVTalkConnectionData * connection = pvPortMalloc(sizeof(UAVTalkConnectionData));
|
||||
if (!connection) return 0;
|
||||
connection->canari = UAVTALK_CANARI;
|
||||
connection->iproc.rxPacketLength = 0;
|
||||
connection->iproc.state = UAVTALK_STATE_SYNC;
|
||||
connection->outStream = outputStream;
|
||||
connection->lock = xSemaphoreCreateRecursiveMutex();
|
||||
connection->transLock = xSemaphoreCreateRecursiveMutex();
|
||||
connection->txSize = maxPacketSize;
|
||||
// allocate buffers
|
||||
connection->rxBuffer = pvPortMalloc(UAVTALK_MAX_PACKET_LENGTH);
|
||||
if (!connection->rxBuffer) return 0;
|
||||
connection->txBuffer = pvPortMalloc(UAVTALK_MAX_PACKET_LENGTH);
|
||||
if (!connection->txBuffer) return 0;
|
||||
vSemaphoreCreateBinary(connection->respSema);
|
||||
xSemaphoreTake(connection->respSema, 0); // reset to zero
|
||||
UAVTalkResetStats( (UAVTalkConnection) connection );
|
||||
return (UAVTalkConnection) connection;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the communication output stream
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] outputStream Function pointer that is called to send a data buffer
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
int32_t UAVTalkSetOutputStream(UAVTalkConnection connectionHandle, UAVTalkOutputStream outputStream)
|
||||
{
|
||||
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return -1);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
|
||||
|
||||
// set output stream
|
||||
connection->outStream = outputStream;
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* Get current output stream
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* @return UAVTarlkOutputStream the output stream used
|
||||
*/
|
||||
UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connectionHandle)
|
||||
{
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return NULL);
|
||||
return connection->outStream;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get communication statistics counters
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* @param[out] statsOut Statistics counters
|
||||
*/
|
||||
void UAVTalkGetStats(UAVTalkStats* statsOut)
|
||||
void UAVTalkGetStats(UAVTalkConnection connectionHandle, UAVTalkStats* statsOut)
|
||||
{
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return );
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
|
||||
|
||||
// Copy stats
|
||||
memcpy(statsOut, &stats, sizeof(UAVTalkStats));
|
||||
memcpy(statsOut, &connection->stats, sizeof(UAVTalkStats));
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the statistics counters.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
*/
|
||||
void UAVTalkResetStats()
|
||||
void UAVTalkResetStats(UAVTalkConnection connectionHandle)
|
||||
{
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
|
||||
|
||||
// Clear stats
|
||||
memset(&stats, 0, sizeof(UAVTalkStats));
|
||||
memset(&connection->stats, 0, sizeof(UAVTalkStats));
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
}
|
||||
|
||||
/**
|
||||
* Request an update for the specified object, on success the object data would have been
|
||||
* updated by the GCS.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] obj Object to update
|
||||
* \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances.
|
||||
* \param[in] timeout Time to wait for the response, when zero it will return immediately
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
int32_t UAVTalkSendObjectRequest(UAVObjHandle obj, uint16_t instId, int32_t timeout)
|
||||
int32_t UAVTalkSendObjectRequest(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, int32_t timeout)
|
||||
{
|
||||
return objectTransaction(obj, instId, TYPE_OBJ_REQ, timeout);
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return -1);
|
||||
return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_REQ, timeout);
|
||||
}
|
||||
|
||||
/**
|
||||
* Send the specified object through the telemetry link.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] obj Object to send
|
||||
* \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances.
|
||||
* \param[in] acked Selects if an ack is required (1:ack required, 0: ack not required)
|
||||
@ -144,69 +176,72 @@ int32_t UAVTalkSendObjectRequest(UAVObjHandle obj, uint16_t instId, int32_t time
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
int32_t UAVTalkSendObject(UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs)
|
||||
int32_t UAVTalkSendObject(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs)
|
||||
{
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return -1);
|
||||
// Send object
|
||||
if (acked == 1)
|
||||
{
|
||||
return objectTransaction(obj, instId, TYPE_OBJ_ACK, timeoutMs);
|
||||
return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_ACK, timeoutMs);
|
||||
}
|
||||
else
|
||||
{
|
||||
return objectTransaction(obj, instId, TYPE_OBJ, timeoutMs);
|
||||
return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ, timeoutMs);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Execute the requested transaction on an object.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] obj Object
|
||||
* \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances.
|
||||
* \param[in] type Transaction type
|
||||
* TYPE_OBJ: send object,
|
||||
* TYPE_OBJ_REQ: request object update
|
||||
* TYPE_OBJ_ACK: send object with an ack
|
||||
* UAVTALK_TYPE_OBJ: send object,
|
||||
* UAVTALK_TYPE_OBJ_REQ: request object update
|
||||
* UAVTALK_TYPE_OBJ_ACK: send object with an ack
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
static int32_t objectTransaction(UAVObjHandle obj, uint16_t instId, uint8_t type, int32_t timeoutMs)
|
||||
static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type, int32_t timeoutMs)
|
||||
{
|
||||
int32_t respReceived;
|
||||
|
||||
// Send object depending on if a response is needed
|
||||
if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ)
|
||||
if (type == UAVTALK_TYPE_OBJ_ACK || type == UAVTALK_TYPE_OBJ_REQ)
|
||||
{
|
||||
// Get transaction lock (will block if a transaction is pending)
|
||||
xSemaphoreTakeRecursive(transLock, portMAX_DELAY);
|
||||
xSemaphoreTakeRecursive(connection->transLock, portMAX_DELAY);
|
||||
// Send object
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
respObj = obj;
|
||||
respInstId = instId;
|
||||
sendObject(obj, instId, type);
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
|
||||
connection->respObj = obj;
|
||||
connection->respInstId = instId;
|
||||
sendObject(connection, obj, instId, type);
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
// Wait for response (or timeout)
|
||||
respReceived = xSemaphoreTake(respSema, timeoutMs/portTICK_RATE_MS);
|
||||
respReceived = xSemaphoreTake(connection->respSema, timeoutMs/portTICK_RATE_MS);
|
||||
// Check if a response was received
|
||||
if (respReceived == pdFALSE)
|
||||
{
|
||||
// Cancel transaction
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
xSemaphoreTake(respSema, 0); // non blocking call to make sure the value is reset to zero (binary sema)
|
||||
respObj = 0;
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
xSemaphoreGiveRecursive(transLock);
|
||||
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
|
||||
xSemaphoreTake(connection->respSema, 0); // non blocking call to make sure the value is reset to zero (binary sema)
|
||||
connection->respObj = 0;
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
xSemaphoreGiveRecursive(connection->transLock);
|
||||
return -1;
|
||||
}
|
||||
else
|
||||
{
|
||||
xSemaphoreGiveRecursive(transLock);
|
||||
xSemaphoreGiveRecursive(connection->transLock);
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
else if (type == TYPE_OBJ)
|
||||
else if (type == UAVTALK_TYPE_OBJ)
|
||||
{
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
sendObject(obj, instId, TYPE_OBJ);
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
|
||||
sendObject(connection, obj, instId, UAVTALK_TYPE_OBJ);
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
return 0;
|
||||
}
|
||||
else
|
||||
@ -217,222 +252,214 @@ static int32_t objectTransaction(UAVObjHandle obj, uint16_t instId, uint8_t type
|
||||
|
||||
/**
|
||||
* Process an byte from the telemetry stream.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] rxbyte Received byte
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
int32_t UAVTalkProcessInputStream(uint8_t rxbyte)
|
||||
int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte)
|
||||
{
|
||||
static UAVObjHandle obj;
|
||||
static uint8_t type;
|
||||
static uint16_t packet_size;
|
||||
static uint32_t objId;
|
||||
static uint16_t instId;
|
||||
static uint32_t length;
|
||||
static uint8_t cs, csRx;
|
||||
static int32_t rxCount;
|
||||
static RxState state = STATE_SYNC;
|
||||
static uint16_t rxPacketLength = 0;
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return -1);
|
||||
|
||||
UAVTalkInputProcessor *iproc = &connection->iproc;
|
||||
++connection->stats.rxBytes;
|
||||
|
||||
++stats.rxBytes;
|
||||
|
||||
if (rxPacketLength < 0xffff)
|
||||
rxPacketLength++; // update packet byte count
|
||||
if (iproc->rxPacketLength < 0xffff)
|
||||
iproc->rxPacketLength++; // update packet byte count
|
||||
|
||||
// Receive state machine
|
||||
switch (state)
|
||||
switch (iproc->state)
|
||||
{
|
||||
case STATE_SYNC:
|
||||
if (rxbyte != SYNC_VAL)
|
||||
case UAVTALK_STATE_SYNC:
|
||||
if (rxbyte != UAVTALK_SYNC_VAL)
|
||||
break;
|
||||
|
||||
// Initialize and update the CRC
|
||||
cs = PIOS_CRC_updateByte(0, rxbyte);
|
||||
iproc->cs = PIOS_CRC_updateByte(0, rxbyte);
|
||||
|
||||
rxPacketLength = 1;
|
||||
iproc->rxPacketLength = 1;
|
||||
|
||||
state = STATE_TYPE;
|
||||
iproc->state = UAVTALK_STATE_TYPE;
|
||||
break;
|
||||
|
||||
case STATE_TYPE:
|
||||
case UAVTALK_STATE_TYPE:
|
||||
|
||||
// update the CRC
|
||||
cs = PIOS_CRC_updateByte(cs, rxbyte);
|
||||
iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte);
|
||||
|
||||
if ((rxbyte & TYPE_MASK) != TYPE_VER)
|
||||
if ((rxbyte & UAVTALK_TYPE_MASK) != UAVTALK_TYPE_VER)
|
||||
{
|
||||
state = STATE_SYNC;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
break;
|
||||
}
|
||||
|
||||
type = rxbyte;
|
||||
iproc->type = rxbyte;
|
||||
|
||||
packet_size = 0;
|
||||
iproc->packet_size = 0;
|
||||
|
||||
state = STATE_SIZE;
|
||||
rxCount = 0;
|
||||
iproc->state = UAVTALK_STATE_SIZE;
|
||||
iproc->rxCount = 0;
|
||||
break;
|
||||
|
||||
case STATE_SIZE:
|
||||
case UAVTALK_STATE_SIZE:
|
||||
|
||||
// update the CRC
|
||||
cs = PIOS_CRC_updateByte(cs, rxbyte);
|
||||
iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte);
|
||||
|
||||
if (rxCount == 0)
|
||||
if (iproc->rxCount == 0)
|
||||
{
|
||||
packet_size += rxbyte;
|
||||
rxCount++;
|
||||
iproc->packet_size += rxbyte;
|
||||
iproc->rxCount++;
|
||||
break;
|
||||
}
|
||||
|
||||
packet_size += rxbyte << 8;
|
||||
iproc->packet_size += rxbyte << 8;
|
||||
|
||||
if (packet_size < MIN_HEADER_LENGTH || packet_size > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH)
|
||||
if (iproc->packet_size < UAVTALK_MIN_HEADER_LENGTH || iproc->packet_size > UAVTALK_MAX_HEADER_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH)
|
||||
{ // incorrect packet size
|
||||
state = STATE_SYNC;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
break;
|
||||
}
|
||||
|
||||
rxCount = 0;
|
||||
objId = 0;
|
||||
state = STATE_OBJID;
|
||||
iproc->rxCount = 0;
|
||||
iproc->objId = 0;
|
||||
iproc->state = UAVTALK_STATE_OBJID;
|
||||
break;
|
||||
|
||||
case STATE_OBJID:
|
||||
case UAVTALK_STATE_OBJID:
|
||||
|
||||
// update the CRC
|
||||
cs = PIOS_CRC_updateByte(cs, rxbyte);
|
||||
iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte);
|
||||
|
||||
objId += rxbyte << (8*(rxCount++));
|
||||
iproc->objId += rxbyte << (8*(iproc->rxCount++));
|
||||
|
||||
if (rxCount < 4)
|
||||
if (iproc->rxCount < 4)
|
||||
break;
|
||||
|
||||
// Search for object, if not found reset state machine
|
||||
// except if we got a OBJ_REQ for an object which does not
|
||||
// exist, in which case we'll send a NACK
|
||||
|
||||
obj = UAVObjGetByID(objId);
|
||||
if (obj == 0 && type != TYPE_OBJ_REQ)
|
||||
iproc->obj = UAVObjGetByID(iproc->objId);
|
||||
if (iproc->obj == 0 && iproc->type != UAVTALK_TYPE_OBJ_REQ)
|
||||
{
|
||||
stats.rxErrors++;
|
||||
state = STATE_SYNC;
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
break;
|
||||
}
|
||||
|
||||
// Determine data length
|
||||
if (type == TYPE_OBJ_REQ || type == TYPE_ACK || type == TYPE_NACK)
|
||||
length = 0;
|
||||
if (iproc->type == UAVTALK_TYPE_OBJ_REQ || iproc->type == UAVTALK_TYPE_ACK || iproc->type == UAVTALK_TYPE_NACK)
|
||||
iproc->length = 0;
|
||||
else
|
||||
length = UAVObjGetNumBytes(obj);
|
||||
iproc->length = UAVObjGetNumBytes(iproc->obj);
|
||||
|
||||
// Check length and determine next state
|
||||
if (length >= MAX_PAYLOAD_LENGTH)
|
||||
if (iproc->length >= UAVTALK_MAX_PAYLOAD_LENGTH)
|
||||
{
|
||||
stats.rxErrors++;
|
||||
state = STATE_SYNC;
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
break;
|
||||
}
|
||||
|
||||
// Check the lengths match
|
||||
if ((rxPacketLength + length) != packet_size)
|
||||
if ((iproc->rxPacketLength + iproc->length) != iproc->packet_size)
|
||||
{ // packet error - mismatched packet size
|
||||
stats.rxErrors++;
|
||||
state = STATE_SYNC;
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
break;
|
||||
}
|
||||
|
||||
instId = 0;
|
||||
if (obj == 0)
|
||||
iproc->instId = 0;
|
||||
if (iproc->obj == 0)
|
||||
{
|
||||
// If this is a NACK, we skip to Checksum
|
||||
state = STATE_CS;
|
||||
rxCount = 0;
|
||||
iproc->state = UAVTALK_STATE_CS;
|
||||
iproc->rxCount = 0;
|
||||
|
||||
}
|
||||
// Check if this is a single instance object (i.e. if the instance ID field is coming next)
|
||||
else if (UAVObjIsSingleInstance(obj))
|
||||
else if (UAVObjIsSingleInstance(iproc->obj))
|
||||
{
|
||||
// If there is a payload get it, otherwise receive checksum
|
||||
if (length > 0)
|
||||
state = STATE_DATA;
|
||||
if (iproc->length > 0)
|
||||
iproc->state = UAVTALK_STATE_DATA;
|
||||
else
|
||||
state = STATE_CS;
|
||||
iproc->state = UAVTALK_STATE_CS;
|
||||
|
||||
rxCount = 0;
|
||||
iproc->rxCount = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
state = STATE_INSTID;
|
||||
rxCount = 0;
|
||||
iproc->state = UAVTALK_STATE_INSTID;
|
||||
iproc->rxCount = 0;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case STATE_INSTID:
|
||||
case UAVTALK_STATE_INSTID:
|
||||
|
||||
// update the CRC
|
||||
cs = PIOS_CRC_updateByte(cs, rxbyte);
|
||||
iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte);
|
||||
|
||||
instId += rxbyte << (8*(rxCount++));
|
||||
iproc->instId += rxbyte << (8*(iproc->rxCount++));
|
||||
|
||||
if (rxCount < 2)
|
||||
if (iproc->rxCount < 2)
|
||||
break;
|
||||
|
||||
rxCount = 0;
|
||||
iproc->rxCount = 0;
|
||||
|
||||
// If there is a payload get it, otherwise receive checksum
|
||||
if (length > 0)
|
||||
state = STATE_DATA;
|
||||
if (iproc->length > 0)
|
||||
iproc->state = UAVTALK_STATE_DATA;
|
||||
else
|
||||
state = STATE_CS;
|
||||
iproc->state = UAVTALK_STATE_CS;
|
||||
|
||||
break;
|
||||
|
||||
case STATE_DATA:
|
||||
case UAVTALK_STATE_DATA:
|
||||
|
||||
// update the CRC
|
||||
cs = PIOS_CRC_updateByte(cs, rxbyte);
|
||||
iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte);
|
||||
|
||||
rxBuffer[rxCount++] = rxbyte;
|
||||
if (rxCount < length)
|
||||
connection->rxBuffer[iproc->rxCount++] = rxbyte;
|
||||
if (iproc->rxCount < iproc->length)
|
||||
break;
|
||||
|
||||
state = STATE_CS;
|
||||
rxCount = 0;
|
||||
iproc->state = UAVTALK_STATE_CS;
|
||||
iproc->rxCount = 0;
|
||||
break;
|
||||
|
||||
case STATE_CS:
|
||||
case UAVTALK_STATE_CS:
|
||||
|
||||
// the CRC byte
|
||||
csRx = rxbyte;
|
||||
|
||||
if (csRx != cs)
|
||||
if (rxbyte != iproc->cs)
|
||||
{ // packet error - faulty CRC
|
||||
stats.rxErrors++;
|
||||
state = STATE_SYNC;
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
break;
|
||||
}
|
||||
|
||||
if (rxPacketLength != (packet_size + 1))
|
||||
if (iproc->rxPacketLength != (iproc->packet_size + 1))
|
||||
{ // packet error - mismatched packet size
|
||||
stats.rxErrors++;
|
||||
state = STATE_SYNC;
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
break;
|
||||
}
|
||||
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
receiveObject(type, objId, instId, rxBuffer, length);
|
||||
stats.rxObjectBytes += length;
|
||||
stats.rxObjects++;
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
|
||||
receiveObject(connection, iproc->type, iproc->objId, iproc->instId, connection->rxBuffer, iproc->length);
|
||||
connection->stats.rxObjectBytes += iproc->length;
|
||||
connection->stats.rxObjects++;
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
|
||||
state = STATE_SYNC;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
break;
|
||||
|
||||
default:
|
||||
stats.rxErrors++;
|
||||
state = STATE_SYNC;
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
}
|
||||
|
||||
// Done
|
||||
@ -441,7 +468,8 @@ int32_t UAVTalkProcessInputStream(uint8_t rxbyte)
|
||||
|
||||
/**
|
||||
* Receive an object. This function process objects received through the telemetry stream.
|
||||
* \param[in] type Type of received message (TYPE_OBJ, TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK, TYPE_NACK)
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] type Type of received message (UAVTALK_TYPE_OBJ, UAVTALK_TYPE_OBJ_REQ, UAVTALK_TYPE_OBJ_ACK, UAVTALK_TYPE_ACK, UAVTALK_TYPE_NACK)
|
||||
* \param[in] objId ID of the object to work on
|
||||
* \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances.
|
||||
* \param[in] data Data buffer
|
||||
@ -449,9 +477,9 @@ int32_t UAVTalkProcessInputStream(uint8_t rxbyte)
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length)
|
||||
static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length)
|
||||
{
|
||||
static UAVObjHandle obj;
|
||||
UAVObjHandle obj;
|
||||
int32_t ret = 0;
|
||||
|
||||
// Get the handle to the Object. Will be zero
|
||||
@ -460,21 +488,21 @@ static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint
|
||||
|
||||
// Process message type
|
||||
switch (type) {
|
||||
case TYPE_OBJ:
|
||||
case UAVTALK_TYPE_OBJ:
|
||||
// All instances, not allowed for OBJ messages
|
||||
if (instId != UAVOBJ_ALL_INSTANCES)
|
||||
{
|
||||
// Unpack object, if the instance does not exist it will be created!
|
||||
UAVObjUnpack(obj, instId, data);
|
||||
// Check if an ack is pending
|
||||
updateAck(obj, instId);
|
||||
updateAck(connection, obj, instId);
|
||||
}
|
||||
else
|
||||
{
|
||||
ret = -1;
|
||||
}
|
||||
break;
|
||||
case TYPE_OBJ_ACK:
|
||||
case UAVTALK_TYPE_OBJ_ACK:
|
||||
// All instances, not allowed for OBJ_ACK messages
|
||||
if (instId != UAVOBJ_ALL_INSTANCES)
|
||||
{
|
||||
@ -482,7 +510,7 @@ static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint
|
||||
if ( UAVObjUnpack(obj, instId, data) == 0 )
|
||||
{
|
||||
// Transmit ACK
|
||||
sendObject(obj, instId, TYPE_ACK);
|
||||
sendObject(connection, obj, instId, UAVTALK_TYPE_ACK);
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -494,22 +522,22 @@ static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint
|
||||
ret = -1;
|
||||
}
|
||||
break;
|
||||
case TYPE_OBJ_REQ:
|
||||
case UAVTALK_TYPE_OBJ_REQ:
|
||||
// Send requested object if message is of type OBJ_REQ
|
||||
if (obj == 0)
|
||||
sendNack(objId);
|
||||
sendNack(connection, objId);
|
||||
else
|
||||
sendObject(obj, instId, TYPE_OBJ);
|
||||
sendObject(connection, obj, instId, UAVTALK_TYPE_OBJ);
|
||||
break;
|
||||
case TYPE_NACK:
|
||||
case UAVTALK_TYPE_NACK:
|
||||
// Do nothing on flight side, let it time out.
|
||||
break;
|
||||
case TYPE_ACK:
|
||||
case UAVTALK_TYPE_ACK:
|
||||
// All instances, not allowed for ACK messages
|
||||
if (instId != UAVOBJ_ALL_INSTANCES)
|
||||
{
|
||||
// Check if an ack is pending
|
||||
updateAck(obj, instId);
|
||||
updateAck(connection, obj, instId);
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -525,25 +553,29 @@ static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint
|
||||
|
||||
/**
|
||||
* Check if an ack is pending on an object and give response semaphore
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] obj Object
|
||||
* \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances.
|
||||
*/
|
||||
static void updateAck(UAVObjHandle obj, uint16_t instId)
|
||||
static void updateAck(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId)
|
||||
{
|
||||
if (respObj == obj && (respInstId == instId || respInstId == UAVOBJ_ALL_INSTANCES))
|
||||
if (connection->respObj == obj && (connection->respInstId == instId || connection->respInstId == UAVOBJ_ALL_INSTANCES))
|
||||
{
|
||||
xSemaphoreGive(respSema);
|
||||
respObj = 0;
|
||||
xSemaphoreGive(connection->respSema);
|
||||
connection->respObj = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Send an object through the telemetry link.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] obj Object handle to send
|
||||
* \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances
|
||||
* \param[in] type Transaction type
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
static int32_t sendObject(UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
static int32_t sendObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
{
|
||||
uint32_t numInst;
|
||||
uint32_t n;
|
||||
@ -555,7 +587,7 @@ static int32_t sendObject(UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
}
|
||||
|
||||
// Process message type
|
||||
if ( type == TYPE_OBJ || type == TYPE_OBJ_ACK )
|
||||
if ( type == UAVTALK_TYPE_OBJ || type == UAVTALK_TYPE_OBJ_ACK )
|
||||
{
|
||||
if (instId == UAVOBJ_ALL_INSTANCES)
|
||||
{
|
||||
@ -564,24 +596,24 @@ static int32_t sendObject(UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
// Send all instances
|
||||
for (n = 0; n < numInst; ++n)
|
||||
{
|
||||
sendSingleObject(obj, n, type);
|
||||
sendSingleObject(connection, obj, n, type);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
return sendSingleObject(obj, instId, type);
|
||||
return sendSingleObject(connection, obj, instId, type);
|
||||
}
|
||||
}
|
||||
else if (type == TYPE_OBJ_REQ)
|
||||
else if (type == UAVTALK_TYPE_OBJ_REQ)
|
||||
{
|
||||
return sendSingleObject(obj, instId, TYPE_OBJ_REQ);
|
||||
return sendSingleObject(connection, obj, instId, UAVTALK_TYPE_OBJ_REQ);
|
||||
}
|
||||
else if (type == TYPE_ACK)
|
||||
else if (type == UAVTALK_TYPE_ACK)
|
||||
{
|
||||
if ( instId != UAVOBJ_ALL_INSTANCES )
|
||||
{
|
||||
return sendSingleObject(obj, instId, TYPE_ACK);
|
||||
return sendSingleObject(connection, obj, instId, UAVTALK_TYPE_ACK);
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -596,13 +628,14 @@ static int32_t sendObject(UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
|
||||
/**
|
||||
* Send an object through the telemetry link.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] obj Object handle to send
|
||||
* \param[in] instId The instance ID (can NOT be UAVOBJ_ALL_INSTANCES, use sendObject() instead)
|
||||
* \param[in] type Transaction type
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
{
|
||||
int32_t length;
|
||||
int32_t dataOffset;
|
||||
@ -610,13 +643,13 @@ static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
|
||||
// Setup type and object id fields
|
||||
objId = UAVObjGetID(obj);
|
||||
txBuffer[0] = SYNC_VAL; // sync byte
|
||||
txBuffer[1] = type;
|
||||
connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte
|
||||
connection->txBuffer[1] = type;
|
||||
// data length inserted here below
|
||||
txBuffer[4] = (uint8_t)(objId & 0xFF);
|
||||
txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF);
|
||||
txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF);
|
||||
txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF);
|
||||
connection->txBuffer[4] = (uint8_t)(objId & 0xFF);
|
||||
connection->txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF);
|
||||
connection->txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF);
|
||||
connection->txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF);
|
||||
|
||||
// Setup instance ID if one is required
|
||||
if (UAVObjIsSingleInstance(obj))
|
||||
@ -625,13 +658,13 @@ static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
}
|
||||
else
|
||||
{
|
||||
txBuffer[8] = (uint8_t)(instId & 0xFF);
|
||||
txBuffer[9] = (uint8_t)((instId >> 8) & 0xFF);
|
||||
connection->txBuffer[8] = (uint8_t)(instId & 0xFF);
|
||||
connection->txBuffer[9] = (uint8_t)((instId >> 8) & 0xFF);
|
||||
dataOffset = 10;
|
||||
}
|
||||
|
||||
// Determine data length
|
||||
if (type == TYPE_OBJ_REQ || type == TYPE_ACK)
|
||||
if (type == UAVTALK_TYPE_OBJ_REQ || type == UAVTALK_TYPE_ACK)
|
||||
{
|
||||
length = 0;
|
||||
}
|
||||
@ -641,7 +674,7 @@ static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
}
|
||||
|
||||
// Check length
|
||||
if (length >= MAX_PAYLOAD_LENGTH)
|
||||
if (length >= UAVTALK_MAX_PAYLOAD_LENGTH)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
@ -649,26 +682,34 @@ static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
// Copy data (if any)
|
||||
if (length > 0)
|
||||
{
|
||||
if ( UAVObjPack(obj, instId, &txBuffer[dataOffset]) < 0 )
|
||||
if ( UAVObjPack(obj, instId, &connection->txBuffer[dataOffset]) < 0 )
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
// Store the packet length
|
||||
txBuffer[2] = (uint8_t)((dataOffset+length) & 0xFF);
|
||||
txBuffer[3] = (uint8_t)(((dataOffset+length) >> 8) & 0xFF);
|
||||
connection->txBuffer[2] = (uint8_t)((dataOffset+length) & 0xFF);
|
||||
connection->txBuffer[3] = (uint8_t)(((dataOffset+length) >> 8) & 0xFF);
|
||||
|
||||
// Calculate checksum
|
||||
txBuffer[dataOffset+length] = PIOS_CRC_updateCRC(0, txBuffer, dataOffset+length);
|
||||
|
||||
// Send buffer
|
||||
if (outStream!=NULL) (*outStream)(txBuffer, dataOffset+length+CHECKSUM_LENGTH);
|
||||
connection->txBuffer[dataOffset+length] = PIOS_CRC_updateCRC(0, connection->txBuffer, dataOffset+length);
|
||||
|
||||
// Send buffer (partially if needed)
|
||||
uint32_t sent=0;
|
||||
while (sent < dataOffset+length+UAVTALK_CHECKSUM_LENGTH) {
|
||||
uint32_t sending = dataOffset+length+UAVTALK_CHECKSUM_LENGTH - sent;
|
||||
if ( sending > connection->txSize ) sending = connection->txSize;
|
||||
if ( connection->outStream != NULL ) {
|
||||
(*connection->outStream)(connection->txBuffer+sent, sending);
|
||||
}
|
||||
sent += sending;
|
||||
}
|
||||
|
||||
// Update stats
|
||||
++stats.txObjects;
|
||||
stats.txBytes += dataOffset+length+CHECKSUM_LENGTH;
|
||||
stats.txObjectBytes += length;
|
||||
++connection->stats.txObjects;
|
||||
connection->stats.txBytes += dataOffset+length+UAVTALK_CHECKSUM_LENGTH;
|
||||
connection->stats.txObjectBytes += length;
|
||||
|
||||
// Done
|
||||
return 0;
|
||||
@ -676,36 +717,37 @@ static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type)
|
||||
|
||||
/**
|
||||
* Send a NACK through the telemetry link.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] objId Object ID to send a NACK for
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
static int32_t sendNack(uint32_t objId)
|
||||
static int32_t sendNack(UAVTalkConnectionData *connection, uint32_t objId)
|
||||
{
|
||||
int32_t dataOffset;
|
||||
|
||||
txBuffer[0] = SYNC_VAL; // sync byte
|
||||
txBuffer[1] = TYPE_NACK;
|
||||
connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte
|
||||
connection->txBuffer[1] = UAVTALK_TYPE_NACK;
|
||||
// data length inserted here below
|
||||
txBuffer[4] = (uint8_t)(objId & 0xFF);
|
||||
txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF);
|
||||
txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF);
|
||||
txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF);
|
||||
connection->txBuffer[4] = (uint8_t)(objId & 0xFF);
|
||||
connection->txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF);
|
||||
connection->txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF);
|
||||
connection->txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF);
|
||||
|
||||
dataOffset = 8;
|
||||
|
||||
// Store the packet length
|
||||
txBuffer[2] = (uint8_t)((dataOffset) & 0xFF);
|
||||
txBuffer[3] = (uint8_t)(((dataOffset) >> 8) & 0xFF);
|
||||
connection->txBuffer[2] = (uint8_t)((dataOffset) & 0xFF);
|
||||
connection->txBuffer[3] = (uint8_t)(((dataOffset) >> 8) & 0xFF);
|
||||
|
||||
// Calculate checksum
|
||||
txBuffer[dataOffset] = PIOS_CRC_updateCRC(0, txBuffer, dataOffset);
|
||||
connection->txBuffer[dataOffset] = PIOS_CRC_updateCRC(0, connection->txBuffer, dataOffset);
|
||||
|
||||
// Send buffer
|
||||
if (outStream!=NULL) (*outStream)(txBuffer, dataOffset+CHECKSUM_LENGTH);
|
||||
if (connection->outStream!=NULL) (*connection->outStream)(connection->txBuffer, dataOffset+UAVTALK_CHECKSUM_LENGTH);
|
||||
|
||||
// Update stats
|
||||
stats.txBytes += dataOffset+CHECKSUM_LENGTH;
|
||||
connection->stats.txBytes += dataOffset+UAVTALK_CHECKSUM_LENGTH;
|
||||
|
||||
// Done
|
||||
return 0;
|
||||
|
159
ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp
Normal file
159
ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp
Normal file
@ -0,0 +1,159 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file cachedsvgitem.h
|
||||
* @author Dmytro Poplavskiy Copyright (C) 2011.
|
||||
* @{
|
||||
* @brief OpenGL texture cached SVG item
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "cachedsvgitem.h"
|
||||
#include <QGLContext>
|
||||
#include <QDebug>
|
||||
|
||||
#ifndef GL_CLAMP_TO_EDGE
|
||||
#define GL_CLAMP_TO_EDGE 0x812F
|
||||
#endif
|
||||
|
||||
CachedSvgItem::CachedSvgItem(QGraphicsItem * parent) :
|
||||
QGraphicsSvgItem(parent),
|
||||
m_context(0),
|
||||
m_texture(0),
|
||||
m_scale(1.0)
|
||||
{
|
||||
setCacheMode(NoCache);
|
||||
}
|
||||
|
||||
CachedSvgItem::CachedSvgItem(const QString & fileName, QGraphicsItem * parent):
|
||||
QGraphicsSvgItem(fileName, parent),
|
||||
m_context(0),
|
||||
m_texture(0),
|
||||
m_scale(1.0)
|
||||
{
|
||||
setCacheMode(NoCache);
|
||||
}
|
||||
|
||||
CachedSvgItem::~CachedSvgItem()
|
||||
{
|
||||
if (m_context && m_texture) {
|
||||
m_context->makeCurrent();
|
||||
glDeleteTextures(1, &m_texture);
|
||||
}
|
||||
}
|
||||
|
||||
void CachedSvgItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget)
|
||||
{
|
||||
|
||||
if (painter->paintEngine()->type() != QPaintEngine::OpenGL &&
|
||||
painter->paintEngine()->type() != QPaintEngine::OpenGL2) {
|
||||
//Fallback to direct painting
|
||||
QGraphicsSvgItem::paint(painter, option, widget);
|
||||
return;
|
||||
}
|
||||
|
||||
QRectF br = boundingRect();
|
||||
QTransform transform = painter->worldTransform();
|
||||
qreal sceneScale = transform.map(QLineF(0,0,1,0)).length();
|
||||
|
||||
bool stencilTestEnabled = glIsEnabled(GL_STENCIL_TEST);
|
||||
bool scissorTestEnabled = glIsEnabled(GL_SCISSOR_TEST);
|
||||
|
||||
painter->beginNativePainting();
|
||||
|
||||
if (stencilTestEnabled)
|
||||
glEnable(GL_STENCIL_TEST);
|
||||
if (scissorTestEnabled)
|
||||
glEnable(GL_SCISSOR_TEST);
|
||||
|
||||
bool dirty = false;
|
||||
if (!m_texture) {
|
||||
glGenTextures(1, &m_texture);
|
||||
m_context = const_cast<QGLContext*>(QGLContext::currentContext());
|
||||
|
||||
dirty = true;
|
||||
}
|
||||
|
||||
if (!qFuzzyCompare(sceneScale, m_scale)) {
|
||||
m_scale = sceneScale;
|
||||
dirty = true;
|
||||
}
|
||||
|
||||
int textureWidth = (int(br.width()*m_scale) + 3) & ~3;
|
||||
int textureHeight = (int(br.height()*m_scale) + 3) & ~3;
|
||||
|
||||
if (dirty) {
|
||||
//qDebug() << "re-render image";
|
||||
|
||||
QImage img(textureWidth, textureHeight, QImage::Format_ARGB32);
|
||||
{
|
||||
img.fill(Qt::transparent);
|
||||
QPainter p;
|
||||
p.begin(&img);
|
||||
p.setRenderHints(painter->renderHints());
|
||||
p.translate(br.topLeft());
|
||||
p.scale(m_scale, m_scale);
|
||||
QGraphicsSvgItem::paint(&p, option, 0);
|
||||
p.end();
|
||||
|
||||
img = img.rgbSwapped();
|
||||
}
|
||||
|
||||
glEnable(GL_TEXTURE_2D);
|
||||
|
||||
glBindTexture(GL_TEXTURE_2D, m_texture);
|
||||
glTexImage2D(
|
||||
GL_TEXTURE_2D,
|
||||
0,
|
||||
GL_RGBA,
|
||||
textureWidth,
|
||||
textureHeight,
|
||||
0,
|
||||
GL_RGBA,
|
||||
GL_UNSIGNED_BYTE,
|
||||
img.bits());
|
||||
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
|
||||
|
||||
glDisable(GL_TEXTURE_2D);
|
||||
|
||||
dirty = false;
|
||||
}
|
||||
|
||||
glEnable(GL_BLEND);
|
||||
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
|
||||
glEnable(GL_TEXTURE_2D);
|
||||
|
||||
glBindTexture(GL_TEXTURE_2D, m_texture);
|
||||
|
||||
//texture may be slightly large than svn image, ensure only used area is rendered
|
||||
qreal tw = br.width()*m_scale/textureWidth;
|
||||
qreal th = br.height()*m_scale/textureHeight;
|
||||
|
||||
glBegin(GL_QUADS);
|
||||
glTexCoord2d(0, 0 ); glVertex3d(br.left(), br.top(), -1);
|
||||
glTexCoord2d(tw, 0 ); glVertex3d(br.right(), br.top(), -1);
|
||||
glTexCoord2d(tw, th); glVertex3d(br.right(), br.bottom(), -1);
|
||||
glTexCoord2d(0, th); glVertex3d(br.left(), br.bottom(), -1);
|
||||
glEnd();
|
||||
glDisable(GL_TEXTURE_2D);
|
||||
|
||||
painter->endNativePainting();
|
||||
}
|
54
ground/openpilotgcs/src/libs/utils/cachedsvgitem.h
Normal file
54
ground/openpilotgcs/src/libs/utils/cachedsvgitem.h
Normal file
@ -0,0 +1,54 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file cachedsvgitem.h
|
||||
* @author Dmytro Poplavskiy Copyright (C) 2011.
|
||||
* @{
|
||||
* @brief OpenGL texture cached SVG item
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 CACHEDSVGITEM_H
|
||||
#define CACHEDSVGITEM_H
|
||||
|
||||
#include <QGraphicsSvgItem>
|
||||
#include <QGLContext>
|
||||
|
||||
#include "utils_global.h"
|
||||
|
||||
class QGLContext;
|
||||
|
||||
//Cache Svg item as GL Texture.
|
||||
//Texture is regenerated each time item is scaled
|
||||
//but it's reused during rotation, unlike DeviceCoordinateCache mode
|
||||
class QTCREATOR_UTILS_EXPORT CachedSvgItem: public QGraphicsSvgItem
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
CachedSvgItem(QGraphicsItem * parent = 0);
|
||||
CachedSvgItem(const QString & fileName, QGraphicsItem * parent = 0);
|
||||
~CachedSvgItem();
|
||||
|
||||
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget);
|
||||
|
||||
private:
|
||||
QGLContext *m_context;
|
||||
GLuint m_texture;
|
||||
qreal m_scale;
|
||||
};
|
||||
|
||||
#endif
|
@ -3,7 +3,9 @@ TARGET = Utils
|
||||
|
||||
QT += gui \
|
||||
network \
|
||||
xml
|
||||
xml \
|
||||
svg \
|
||||
opengl
|
||||
|
||||
DEFINES += QTCREATOR_UTILS_LIB
|
||||
|
||||
@ -48,7 +50,8 @@ SOURCES += reloadpromptutils.cpp \
|
||||
homelocationutil.cpp \
|
||||
mytabbedstackwidget.cpp \
|
||||
mytabwidget.cpp \
|
||||
mylistwidget.cpp
|
||||
mylistwidget.cpp \
|
||||
cachedsvgitem.cpp
|
||||
SOURCES += xmlconfig.cpp
|
||||
|
||||
win32 {
|
||||
@ -102,7 +105,8 @@ HEADERS += utils_global.h \
|
||||
homelocationutil.h \
|
||||
mytabbedstackwidget.h \
|
||||
mytabwidget.h \
|
||||
mylistwidget.h
|
||||
mylistwidget.h \
|
||||
cachedsvgitem.h
|
||||
HEADERS += xmlconfig.h
|
||||
|
||||
FORMS += filewizardpage.ui \
|
||||
|
441
ground/openpilotgcs/src/plugins/config/camerastabilization.ui
Normal file
441
ground/openpilotgcs/src/plugins/config/camerastabilization.ui
Normal file
@ -0,0 +1,441 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>CameraStabilizationWidget</class>
|
||||
<widget class="QWidget" name="CameraStabilizationWidget">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>720</width>
|
||||
<height>567</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<widget class="QCheckBox" name="enableCameraStabilization">
|
||||
<property name="text">
|
||||
<string>Enable CameraStabilization module</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_7">
|
||||
<property name="text">
|
||||
<string>After enabling the module, you must power cycle before using and configuring.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="Line" name="line">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="title">
|
||||
<string>Channel Ranges (number of degrees full range)</string>
|
||||
</property>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<layout class="QFormLayout" name="formLayout_2">
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QSpinBox" name="rollOutputRange">
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QSpinBox" name="pitchOutputRange">
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QSpinBox" name="yawOutputRange">
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>212</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_2">
|
||||
<property name="title">
|
||||
<string>Channel Mapping (select output channel or none to disable)</string>
|
||||
</property>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<layout class="QFormLayout" name="formLayout">
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="rollChannel">
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>None</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 1</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 2</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 3</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 4</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 5</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 6</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 7</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 8</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<widget class="QComboBox" name="yawChannel">
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>None</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 1</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 2</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 3</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 4</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 5</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 6</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 7</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 8</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QComboBox" name="pitchChannel">
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>None</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 1</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 2</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 3</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 4</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 5</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 6</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 7</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Channel 8</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>212</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="submitButtons">
|
||||
<item>
|
||||
<widget class="QFrame" name="frame">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="camerastabilizationHelp">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<kerning>true</kerning>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../coreplugin/core.qrc">
|
||||
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="shortcut">
|
||||
<string>Ctrl+S</string>
|
||||
</property>
|
||||
<property name="default">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="camerastabilizationSaveRAM">
|
||||
<property name="toolTip">
|
||||
<string>Save settings to the board (RAM only).
|
||||
|
||||
This does not save the calibration settings, this is done using the
|
||||
specific calibration button on top of the screen.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="camerastabilizationSaveSD">
|
||||
<property name="toolTip">
|
||||
<string>Send settings to the board, and save to the non-volatile memory.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
@ -38,7 +38,8 @@ HEADERS += configplugin.h \
|
||||
defaultattitudewidget.h \
|
||||
smartsavebutton.h \
|
||||
defaulthwsettingswidget.h \
|
||||
inputchannelform.h
|
||||
inputchannelform.h \
|
||||
configcamerastabilizationwidget.h
|
||||
|
||||
SOURCES += configplugin.cpp \
|
||||
configgadgetconfiguration.cpp \
|
||||
@ -67,7 +68,8 @@ SOURCES += configplugin.cpp \
|
||||
defaultattitudewidget.cpp \
|
||||
smartsavebutton.cpp \
|
||||
defaulthwsettingswidget.cpp \
|
||||
inputchannelform.cpp
|
||||
inputchannelform.cpp \
|
||||
configcamerastabilizationwidget.cpp
|
||||
|
||||
FORMS += \
|
||||
airframe.ui \
|
||||
@ -81,6 +83,11 @@ FORMS += \
|
||||
ccattitude.ui \
|
||||
defaultattitude.ui \
|
||||
defaulthwsettings.ui \
|
||||
inputchannelform.ui
|
||||
inputchannelform.ui \
|
||||
camerastabilization.ui
|
||||
|
||||
RESOURCES += configgadget.qrc
|
||||
|
||||
|
||||
|
||||
|
||||
|
@ -0,0 +1,237 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configcamerastabilizationwidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief The Configuration Gadget used to update settings in the firmware
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "configcamerastabilizationwidget.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QTimer>
|
||||
#include <QStringList>
|
||||
#include <QtGui/QWidget>
|
||||
#include <QtGui/QTextEdit>
|
||||
#include <QtGui/QVBoxLayout>
|
||||
#include <QtGui/QPushButton>
|
||||
#include <QThread>
|
||||
#include <iostream>
|
||||
#include <QUrl>
|
||||
#include <QDesktopServices>
|
||||
|
||||
#include "camerastabsettings.h"
|
||||
#include "hwsettings.h"
|
||||
#include "mixersettings.h"
|
||||
|
||||
ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_camerastabilization = new Ui_CameraStabilizationWidget();
|
||||
m_camerastabilization->setupUi(this);
|
||||
|
||||
connectUpdates();
|
||||
|
||||
// Connect buttons
|
||||
connect(m_camerastabilization->camerastabilizationSaveRAM,SIGNAL(clicked()),this,SLOT(applySettings()));
|
||||
connect(m_camerastabilization->camerastabilizationSaveSD,SIGNAL(clicked()),this,SLOT(saveSettings()));
|
||||
connect(m_camerastabilization->camerastabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
}
|
||||
|
||||
ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void ConfigCameraStabilizationWidget::connectUpdates()
|
||||
{
|
||||
// Now connect the widget to the StabilizationSettings object
|
||||
connect(MixerSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
|
||||
connect(CameraStabSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
|
||||
// TODO: This will need to support both CC and OP later
|
||||
connect(HwSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
|
||||
}
|
||||
|
||||
void ConfigCameraStabilizationWidget::disconnectUpdates()
|
||||
{
|
||||
// Now connect the widget to the StabilizationSettings object
|
||||
disconnect(MixerSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
|
||||
disconnect(CameraStabSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
|
||||
// TODO: This will need to support both CC and OP later
|
||||
disconnect(HwSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Populate the gui settings into the appropriate
|
||||
* UAV structures
|
||||
*/
|
||||
void ConfigCameraStabilizationWidget::applySettings()
|
||||
{
|
||||
// Enable or disable the settings
|
||||
HwSettings * hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTABILIZATION] =
|
||||
m_camerastabilization->enableCameraStabilization->isChecked() ?
|
||||
HwSettings::OPTIONALMODULES_ENABLED :
|
||||
HwSettings::OPTIONALMODULES_DISABLED;
|
||||
|
||||
// Update the mixer settings
|
||||
MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager());
|
||||
MixerSettings::DataFields mixerSettingsData = mixerSettings->getData();
|
||||
const int NUM_MIXERS = 8;
|
||||
|
||||
QComboBox * selectors[3] = {
|
||||
m_camerastabilization->rollChannel,
|
||||
m_camerastabilization->pitchChannel,
|
||||
m_camerastabilization->yawChannel
|
||||
};
|
||||
|
||||
// TODO: Need to reformat object so types are an
|
||||
// array themselves. This gets really awkward
|
||||
quint8 * mixerTypes[NUM_MIXERS] = {
|
||||
&mixerSettingsData.Mixer1Type,
|
||||
&mixerSettingsData.Mixer2Type,
|
||||
&mixerSettingsData.Mixer3Type,
|
||||
&mixerSettingsData.Mixer4Type,
|
||||
&mixerSettingsData.Mixer5Type,
|
||||
&mixerSettingsData.Mixer6Type,
|
||||
&mixerSettingsData.Mixer7Type,
|
||||
&mixerSettingsData.Mixer8Type,
|
||||
};
|
||||
|
||||
for (int i = 0; i < 3; i++)
|
||||
{
|
||||
// Channel 1 is second entry, so becomes zero
|
||||
int mixerNum = selectors[i]->currentIndex() - 1;
|
||||
|
||||
if ( mixerNum >= 0 && // Short circuit in case of none
|
||||
*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_DISABLED &&
|
||||
(*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_CAMERAROLL + i) ) {
|
||||
// If the mixer channel already to something that isn't what we are
|
||||
// about to set it to reset to none
|
||||
selectors[i]->setCurrentIndex(0);
|
||||
} else {
|
||||
// Make sure no other channels have this output set
|
||||
for (int j = 0; j < NUM_MIXERS; j++)
|
||||
if (*mixerTypes[j] == (MixerSettings::MIXER1TYPE_CAMERAROLL + i))
|
||||
*mixerTypes[j] = MixerSettings::MIXER1TYPE_DISABLED;
|
||||
|
||||
// If this channel is assigned to one of the outputs that is not disabled
|
||||
// set it
|
||||
if(mixerNum >= 0 && mixerNum < NUM_MIXERS)
|
||||
*mixerTypes[mixerNum] = MixerSettings::MIXER1TYPE_CAMERAROLL + i;
|
||||
}
|
||||
}
|
||||
|
||||
// Update the ranges
|
||||
CameraStabSettings * cameraStab = CameraStabSettings::GetInstance(getObjectManager());
|
||||
CameraStabSettings::DataFields cameraStabData = cameraStab->getData();
|
||||
cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_ROLL] = m_camerastabilization->rollOutputRange->value();
|
||||
cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_PITCH] = m_camerastabilization->pitchOutputRange->value();
|
||||
cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_YAW] = m_camerastabilization->yawOutputRange->value();
|
||||
|
||||
// Because multiple objects are updated, and all of them trigger the callback
|
||||
// they must be done together (if update one then load settings from second
|
||||
// the first update would wipe the UI controls). However to be extra cautious
|
||||
// I'm also disabling updates during the setting to the UAVObjects
|
||||
disconnectUpdates();
|
||||
hwSettings->setData(hwSettingsData);
|
||||
mixerSettings->setData(mixerSettingsData);
|
||||
cameraStab->setData(cameraStabData);
|
||||
connectUpdates();
|
||||
}
|
||||
|
||||
/**
|
||||
* Push settings into UAV objects then save them
|
||||
*/
|
||||
void ConfigCameraStabilizationWidget::saveSettings()
|
||||
{
|
||||
applySettings();
|
||||
UAVObject * obj = HwSettings::GetInstance(getObjectManager());
|
||||
saveObjectToSD(obj);
|
||||
obj = MixerSettings::GetInstance(getObjectManager());
|
||||
saveObjectToSD(obj);
|
||||
obj = CameraStabSettings::GetInstance(getObjectManager());
|
||||
saveObjectToSD(obj);
|
||||
}
|
||||
|
||||
void ConfigCameraStabilizationWidget::refreshValues()
|
||||
{
|
||||
HwSettings * hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
m_camerastabilization->enableCameraStabilization->setChecked(
|
||||
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTABILIZATION] ==
|
||||
HwSettings::OPTIONALMODULES_ENABLED);
|
||||
|
||||
CameraStabSettings * cameraStabSettings = CameraStabSettings::GetInstance(getObjectManager());
|
||||
CameraStabSettings::DataFields cameraStab = cameraStabSettings->getData();
|
||||
m_camerastabilization->rollOutputRange->setValue(cameraStab.OutputRange[CameraStabSettings::OUTPUTRANGE_ROLL]);
|
||||
m_camerastabilization->pitchOutputRange->setValue(cameraStab.OutputRange[CameraStabSettings::OUTPUTRANGE_PITCH]);
|
||||
m_camerastabilization->yawOutputRange->setValue(cameraStab.OutputRange[CameraStabSettings::OUTPUTRANGE_YAW]);
|
||||
|
||||
MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager());
|
||||
MixerSettings::DataFields mixerSettingsData = mixerSettings->getData();
|
||||
const int NUM_MIXERS = 8;
|
||||
QComboBox * selectors[3] = {
|
||||
m_camerastabilization->rollChannel,
|
||||
m_camerastabilization->pitchChannel,
|
||||
m_camerastabilization->yawChannel
|
||||
};
|
||||
|
||||
// TODO: Need to reformat object so types are an
|
||||
// array themselves. This gets really awkward
|
||||
quint8 * mixerTypes[NUM_MIXERS] = {
|
||||
&mixerSettingsData.Mixer1Type,
|
||||
&mixerSettingsData.Mixer2Type,
|
||||
&mixerSettingsData.Mixer3Type,
|
||||
&mixerSettingsData.Mixer4Type,
|
||||
&mixerSettingsData.Mixer5Type,
|
||||
&mixerSettingsData.Mixer6Type,
|
||||
&mixerSettingsData.Mixer7Type,
|
||||
&mixerSettingsData.Mixer8Type,
|
||||
};
|
||||
|
||||
for (int i = 0; i < 3; i++)
|
||||
{
|
||||
// Default to none if not found. Then search for any mixer channels set to
|
||||
// this
|
||||
selectors[i]->setCurrentIndex(0);
|
||||
for (int j = 0; j < NUM_MIXERS; j++)
|
||||
if (*mixerTypes[j] == (MixerSettings::MIXER1TYPE_CAMERAROLL + i) &&
|
||||
selectors[i]->currentIndex() != (j + 1))
|
||||
selectors[i]->setCurrentIndex(j + 1);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigCameraStabilizationWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Camera+Stabilization", QUrl::StrictMode) );
|
||||
}
|
||||
|
||||
void ConfigCameraStabilizationWidget::enableControls(bool enable)
|
||||
{
|
||||
m_camerastabilization->camerastabilizationSaveSD->setEnabled(enable);
|
||||
m_camerastabilization->camerastabilizationSaveRAM->setEnabled(enable);
|
||||
}
|
||||
|
||||
/**
|
||||
@}
|
||||
@}
|
||||
*/
|
@ -0,0 +1,68 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configahrstwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Telemetry configuration panel
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 CONFIGCAMERASTABILIZATIONWIDGET_H
|
||||
#define CONFIGCAMERASTABILIZATIONWIDGET_H
|
||||
|
||||
#include "ui_camerastabilization.h"
|
||||
#include "configtaskwidget.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavobject.h"
|
||||
#include <QtGui/QWidget>
|
||||
#include <QtSvg/QSvgRenderer>
|
||||
#include <QtSvg/QGraphicsSvgItem>
|
||||
#include <QList>
|
||||
#include <QTimer>
|
||||
#include <QMutex>
|
||||
|
||||
#include "camerastabsettings.h"
|
||||
|
||||
class ConfigCameraStabilizationWidget: public ConfigTaskWidget
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
ConfigCameraStabilizationWidget(QWidget *parent = 0);
|
||||
~ConfigCameraStabilizationWidget();
|
||||
|
||||
private:
|
||||
virtual void enableControls(bool enable);
|
||||
|
||||
Ui_CameraStabilizationWidget *m_camerastabilization;
|
||||
|
||||
private slots:
|
||||
void openHelp();
|
||||
void applySettings();
|
||||
void saveSettings();
|
||||
void refreshValues();
|
||||
|
||||
protected:
|
||||
void connectUpdates();
|
||||
void disconnectUpdates();
|
||||
};
|
||||
|
||||
#endif // ConfigCameraStabilization_H
|
@ -16,5 +16,6 @@
|
||||
<file>images/hw_config.png</file>
|
||||
<file>images/gyroscope.png</file>
|
||||
<file>images/TX.svg</file>
|
||||
<file>images/camera.png</file>
|
||||
</qresource>
|
||||
</RCC>
|
||||
|
@ -33,6 +33,7 @@
|
||||
#include "configinputwidget.h"
|
||||
#include "configoutputwidget.h"
|
||||
#include "configstabilizationwidget.h"
|
||||
#include "configcamerastabilizationwidget.h"
|
||||
#include "config_pro_hw_widget.h"
|
||||
#include "config_cc_hw_widget.h"
|
||||
#include "defaultattitudewidget.h"
|
||||
@ -81,6 +82,8 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
qwd = new ConfigStabilizationWidget(this);
|
||||
ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, QIcon(":/configgadget/images/gyroscope.png"), QString("Stabilization"));
|
||||
|
||||
qwd = new ConfigCameraStabilizationWidget(this);
|
||||
ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, QIcon(":/configgadget/images/camera.png"), QString("Camera Stab"));
|
||||
|
||||
|
||||
// qwd = new ConfigPipXtremeWidget(this);
|
||||
|
@ -50,7 +50,7 @@ class ConfigGadgetWidget: public QWidget
|
||||
public:
|
||||
ConfigGadgetWidget(QWidget *parent = 0);
|
||||
~ConfigGadgetWidget();
|
||||
enum widgetTabs {hardware=0, aircraft, input, output, ins, stabilization};
|
||||
enum widgetTabs {hardware=0, aircraft, input, output, ins, stabilization, camerastabilization};
|
||||
|
||||
public slots:
|
||||
void onAutopilotConnect();
|
||||
|
@ -30,7 +30,7 @@
|
||||
#include <QStringList>
|
||||
#include <QTimer>
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
|
||||
#include "objectpersistence.h"
|
||||
|
||||
ConfigPlugin::ConfigPlugin()
|
||||
{
|
||||
@ -58,7 +58,7 @@ bool ConfigPlugin::initialize(const QStringList& args, QString *errMsg)
|
||||
"ConfigPlugin.EraseAll",
|
||||
QList<int>() <<
|
||||
Core::Constants::C_GLOBAL_ID);
|
||||
cmd->action()->setText("Erase all settings from board...");
|
||||
cmd->action()->setText(tr("Erase all settings from board..."));
|
||||
|
||||
ac->menu()->addSeparator();
|
||||
ac->appendGroup("Utilities");
|
||||
@ -80,6 +80,17 @@ bool ConfigPlugin::initialize(const QStringList& args, QString *errMsg)
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Return handle to object manager
|
||||
*/
|
||||
UAVObjectManager * ConfigPlugin::getObjectManager()
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager * objMngr = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(objMngr);
|
||||
return objMngr;
|
||||
}
|
||||
|
||||
void ConfigPlugin::extensionsInitialized()
|
||||
{
|
||||
cmd->action()->setEnabled(false);
|
||||
@ -122,18 +133,19 @@ void ConfigPlugin::eraseAllSettings()
|
||||
return;
|
||||
|
||||
settingsErased = false;
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager * objMngr = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(objMngr);
|
||||
ObjectPersistence* objper = dynamic_cast<ObjectPersistence*>( objMngr->getObject(ObjectPersistence::NAME) );
|
||||
ObjectPersistence* objper = ObjectPersistence::GetInstance(getObjectManager());
|
||||
Q_ASSERT(objper);
|
||||
|
||||
connect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *)));
|
||||
ObjectPersistence::DataFields data;
|
||||
data.Operation = ObjectPersistence::OPERATION_DELETE;
|
||||
data.Selection = ObjectPersistence::SELECTION_ALLSETTINGS;
|
||||
|
||||
ObjectPersistence::DataFields data = objper->getData();
|
||||
data.Operation = ObjectPersistence::OPERATION_FULLERASE;
|
||||
|
||||
// No need for manual updated event, this is triggered by setData
|
||||
// based on UAVO meta data
|
||||
objper->setData(data);
|
||||
objper->updated();
|
||||
QTimer::singleShot(1500,this,SLOT(eraseFailed()));
|
||||
QTimer::singleShot(6000,this,SLOT(eraseFailed()));
|
||||
|
||||
}
|
||||
|
||||
@ -141,37 +153,47 @@ void ConfigPlugin::eraseFailed()
|
||||
{
|
||||
if (settingsErased)
|
||||
return;
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager * objMngr = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(objMngr);
|
||||
ObjectPersistence* objper = dynamic_cast<ObjectPersistence*>( objMngr->getObject(ObjectPersistence::NAME));
|
||||
disconnect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *)));
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Error trying to erase settings."));
|
||||
msgBox.setInformativeText(tr("Power-cycle your board. Settings might be inconsistent."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
|
||||
ObjectPersistence* objper = ObjectPersistence::GetInstance(getObjectManager());
|
||||
|
||||
ObjectPersistence::DataFields data = objper->getData();
|
||||
if(data.Operation == ObjectPersistence::OPERATION_FULLERASE) {
|
||||
// First attempt via flash erase failed. Fall back on erase all settings
|
||||
data.Operation = ObjectPersistence::OPERATION_DELETE;
|
||||
data.Selection = ObjectPersistence::SELECTION_ALLSETTINGS;
|
||||
objper->setData(data);
|
||||
objper->updated();
|
||||
QTimer::singleShot(1500,this,SLOT(eraseFailed()));
|
||||
} else {
|
||||
disconnect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *)));
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Error trying to erase settings."));
|
||||
msgBox.setInformativeText(tr("Power-cycle your board after removing all blades. Settings might be inconsistent."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigPlugin::eraseDone(UAVObject * obj)
|
||||
{
|
||||
QMessageBox msgBox;
|
||||
ObjectPersistence* objper = dynamic_cast<ObjectPersistence*>(sender());
|
||||
Q_ASSERT(obj->getName().compare("ObjectPersistence") == 0);
|
||||
QString tmp = obj->getField("Operation")->getValue().toString();
|
||||
if (obj->getField("Operation")->getValue().toString().compare(QString("Delete")) == 0 ) {
|
||||
ObjectPersistence* objper = ObjectPersistence::GetInstance(getObjectManager());
|
||||
ObjectPersistence::DataFields data = objper->getData();
|
||||
Q_ASSERT(obj->getInstID() == objper->getInstID());
|
||||
|
||||
if(data.Operation != ObjectPersistence::OPERATION_COMPLETED) {
|
||||
return;
|
||||
}
|
||||
|
||||
disconnect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *)));
|
||||
if (obj->getField("Operation")->getValue().toString().compare(QString("Completed")) == 0) {
|
||||
if (data.Operation == ObjectPersistence::OPERATION_COMPLETED) {
|
||||
settingsErased = true;
|
||||
msgBox.setText(tr("Settings are now erased."));
|
||||
msgBox.setInformativeText(tr("Please now power-cycle your board to complete reset."));
|
||||
} else {
|
||||
msgBox.setText(tr("Error trying to erase settings."));
|
||||
msgBox.setInformativeText(tr("Power-cycle your board. Settings might be inconsistent."));
|
||||
msgBox.setInformativeText(tr("Power-cycle your board after removing all blades. Settings might be inconsistent."));
|
||||
}
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
|
@ -48,6 +48,7 @@ public:
|
||||
ConfigPlugin();
|
||||
~ConfigPlugin();
|
||||
|
||||
UAVObjectManager * getObjectManager();
|
||||
void extensionsInitialized();
|
||||
bool initialize(const QStringList & arguments, QString * errorString);
|
||||
void shutdown();
|
||||
|
BIN
ground/openpilotgcs/src/plugins/config/images/camera.png
Normal file
BIN
ground/openpilotgcs/src/plugins/config/images/camera.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 2.8 KiB |
@ -6,649 +6,689 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>639</width>
|
||||
<height>611</height>
|
||||
<width>683</width>
|
||||
<height>685</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<widget class="QScrollArea" name="scrollArea">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>150</height>
|
||||
</size>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Rate Stabilization Coefficients (Inner Loop)</string>
|
||||
<property name="widgetResizable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_12">
|
||||
<property name="text">
|
||||
<string>Kp</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QLabel" name="label_13">
|
||||
<property name="text">
|
||||
<string>Ki</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="label_14">
|
||||
<property name="text">
|
||||
<string>ILimit</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QLabel" name="label_10">
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rateRollKp">
|
||||
<property name="toolTip">
|
||||
<string>Slowly raise Kp until you start seeing clear oscillations when you fly.
|
||||
<widget class="QWidget" name="scrollAreaWidgetContents">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>665</width>
|
||||
<height>627</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>150</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Rate Stabilization Coefficients (Inner Loop)</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_12">
|
||||
<property name="text">
|
||||
<string>Kp</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QLabel" name="label_13">
|
||||
<property name="text">
|
||||
<string>Ki</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="label_14">
|
||||
<property name="text">
|
||||
<string>ILimit</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QLabel" name="label_10">
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rateRollKp">
|
||||
<property name="toolTip">
|
||||
<string>Slowly raise Kp until you start seeing clear oscillations when you fly.
|
||||
Then lower the value by 20% or so.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QDoubleSpinBox" name="rateRollKi">
|
||||
<property name="toolTip">
|
||||
<string>I factor for rate stabilization is usually very low or even zero.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QDoubleSpinBox" name="rateRollILimit">
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QCheckBox" name="linkRateRP">
|
||||
<property name="toolTip">
|
||||
<string>If checked, the Roll and Pitch factors will be identical.
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QDoubleSpinBox" name="rateRollKi">
|
||||
<property name="toolTip">
|
||||
<string>I factor for rate stabilization is usually very low or even zero.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QDoubleSpinBox" name="rateRollILimit">
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QCheckBox" name="linkRateRP">
|
||||
<property name="toolTip">
|
||||
<string>If checked, the Roll and Pitch factors will be identical.
|
||||
When you change one, the other is updated.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Link</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QLabel" name="label_11">
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchKp">
|
||||
<property name="toolTip">
|
||||
<string>Slowly raise Kp until you start seeing clear oscillations when you fly.
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Link</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QLabel" name="label_11">
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchKp">
|
||||
<property name="toolTip">
|
||||
<string>Slowly raise Kp until you start seeing clear oscillations when you fly.
|
||||
Then lower the value by 20% or so.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchKi">
|
||||
<property name="toolTip">
|
||||
<string>I factor for rate stabilization is usually very low or even zero.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchILimit">
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QLabel" name="label_15">
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rateYawKp">
|
||||
<property name="toolTip">
|
||||
<string>Slowly raise Kp until you start seeing clear oscillations when you fly.
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchKi">
|
||||
<property name="toolTip">
|
||||
<string>I factor for rate stabilization is usually very low or even zero.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchILimit">
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QLabel" name="label_15">
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rateYawKp">
|
||||
<property name="toolTip">
|
||||
<string>Slowly raise Kp until you start seeing clear oscillations when you fly.
|
||||
Then lower the value by 20% or so.
|
||||
|
||||
You can usually go for higher values for Yaw factors.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QDoubleSpinBox" name="rateYawKi">
|
||||
<property name="toolTip">
|
||||
<string>As a rule of thumb, you can set YawRate Ki at roughly the same
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QDoubleSpinBox" name="rateYawKi">
|
||||
<property name="toolTip">
|
||||
<string>As a rule of thumb, you can set YawRate Ki at roughly the same
|
||||
value as YawRate Kp.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QDoubleSpinBox" name="rateYawILimit">
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>5</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>150</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Attitude Stabization Coefficients (Outer Loop)</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="3" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rollKp">
|
||||
<property name="toolTip">
|
||||
<string>Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QDoubleSpinBox" name="rateYawILimit">
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>13</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>150</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Attitude Stabization Coefficients (Outer Loop)</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="3" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rollKp">
|
||||
<property name="toolTip">
|
||||
<string>Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
|
||||
</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QDoubleSpinBox" name="rollKi">
|
||||
<property name="toolTip">
|
||||
<string>Ki can usually be almost identical to Kp.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QDoubleSpinBox" name="rollILimit">
|
||||
<property name="toolTip">
|
||||
<string>ILimit can be equal to three to four times Ki, but you can adjust
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QDoubleSpinBox" name="rollKi">
|
||||
<property name="toolTip">
|
||||
<string>Ki can usually be almost identical to Kp.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QDoubleSpinBox" name="rollILimit">
|
||||
<property name="toolTip">
|
||||
<string>ILimit can be equal to three to four times Ki, but you can adjust
|
||||
depending on whether your airframe is well balanced, and your
|
||||
flying style.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QLabel" name="label_19">
|
||||
<property name="text">
|
||||
<string>Kp</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QLabel" name="label_20">
|
||||
<property name="text">
|
||||
<string>Ki</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QLabel" name="label_21">
|
||||
<property name="text">
|
||||
<string>ILimit</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="4">
|
||||
<widget class="QDoubleSpinBox" name="yawILimit">
|
||||
<property name="toolTip">
|
||||
<string>ILimit can be equal to three to four times Ki, but you can adjust
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QLabel" name="label_19">
|
||||
<property name="text">
|
||||
<string>Kp</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QLabel" name="label_20">
|
||||
<property name="text">
|
||||
<string>Ki</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QLabel" name="label_21">
|
||||
<property name="text">
|
||||
<string>ILimit</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="4">
|
||||
<widget class="QDoubleSpinBox" name="yawILimit">
|
||||
<property name="toolTip">
|
||||
<string>ILimit can be equal to three to four times Ki, but you can adjust
|
||||
depending on whether your airframe is well balanced, and your
|
||||
flying style.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="3">
|
||||
<widget class="QDoubleSpinBox" name="yawKi">
|
||||
<property name="toolTip">
|
||||
<string>Ki can usually be almost identical to Kp.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="2">
|
||||
<widget class="QDoubleSpinBox" name="yawKp">
|
||||
<property name="toolTip">
|
||||
<string>Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="3">
|
||||
<widget class="QDoubleSpinBox" name="yawKi">
|
||||
<property name="toolTip">
|
||||
<string>Ki can usually be almost identical to Kp.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="2">
|
||||
<widget class="QDoubleSpinBox" name="yawKp">
|
||||
<property name="toolTip">
|
||||
<string>Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
|
||||
</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<widget class="QDoubleSpinBox" name="pitchKp">
|
||||
<property name="toolTip">
|
||||
<string>Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<widget class="QDoubleSpinBox" name="pitchKp">
|
||||
<property name="toolTip">
|
||||
<string>Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
|
||||
</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<widget class="QLabel" name="label_18">
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QLabel" name="label_17">
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QLabel" name="label_16">
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<widget class="QDoubleSpinBox" name="pitchKi">
|
||||
<property name="toolTip">
|
||||
<string>Ki can usually be almost identical to Kp.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="4">
|
||||
<widget class="QDoubleSpinBox" name="pitchILimit">
|
||||
<property name="toolTip">
|
||||
<string>ILimit can be equal to three to four times Ki, but you can adjust
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<widget class="QLabel" name="label_18">
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QLabel" name="label_17">
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QLabel" name="label_16">
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<widget class="QDoubleSpinBox" name="pitchKi">
|
||||
<property name="toolTip">
|
||||
<string>Ki can usually be almost identical to Kp.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="4">
|
||||
<widget class="QDoubleSpinBox" name="pitchILimit">
|
||||
<property name="toolTip">
|
||||
<string>ILimit can be equal to three to four times Ki, but you can adjust
|
||||
depending on whether your airframe is well balanced, and your
|
||||
flying style.</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QCheckBox" name="linkAttitudeRP">
|
||||
<property name="toolTip">
|
||||
<string>If checked, the Roll and Pitch factors will be identical.
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.100000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QCheckBox" name="linkAttitudeRP">
|
||||
<property name="toolTip">
|
||||
<string>If checked, the Roll and Pitch factors will be identical.
|
||||
When you change one, the other is updated.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Link</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Link</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>13</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Stick range and limits</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout" rowminimumheight="5,5,5,5">
|
||||
<property name="sizeConstraint">
|
||||
<enum>QLayout::SetMinAndMaxSize</enum>
|
||||
</property>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_22">
|
||||
<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_23">
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QSpinBox" name="rollMax">
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QSpinBox" name="pitchMax">
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QSpinBox" name="yawMax">
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>150</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Full stick angle (deg)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>150</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Full stick rate (deg/s)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QSpinBox" name="manualRoll">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QSpinBox" name="manualPitch">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QSpinBox" name="manualYaw">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_24">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>150</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Maximum rate in attitude mode (deg/s)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QSpinBox" name="maximumRoll">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QSpinBox" name="maximumPitch">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QSpinBox" name="maximumYaw">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="lowThrottleZeroIntegral">
|
||||
<property name="text">
|
||||
<string>Zero the integral when throttle is low</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>5</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Stick range and limits</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout" rowminimumheight="5,5,5,5">
|
||||
<property name="sizeConstraint">
|
||||
<enum>QLayout::SetMinAndMaxSize</enum>
|
||||
</property>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_22">
|
||||
<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_23">
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QSpinBox" name="rollMax">
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QSpinBox" name="pitchMax">
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QSpinBox" name="yawMax">
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>150</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Full stick angle (deg)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>150</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Full stick rate (deg/s)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QSpinBox" name="manualRoll">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QSpinBox" name="manualPitch">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QSpinBox" name="manualYaw">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_24">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>150</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Maximum rate in attitude mode (deg/s)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QSpinBox" name="maximumRoll">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QSpinBox" name="maximumPitch">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QSpinBox" name="maximumYaw">
|
||||
<property name="maximum">
|
||||
<number>300</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="lowThrottleZeroIntegral">
|
||||
<property name="text">
|
||||
<string>Zero the integral when throttle is low</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
|
@ -179,6 +179,8 @@ MainWindow::MainWindow() :
|
||||
m_modeStack->setIconSize(QSize(24,24));
|
||||
m_modeStack->setTabPosition(QTabWidget::South);
|
||||
m_modeStack->setMovable(false);
|
||||
m_modeStack->setMinimumWidth(512);
|
||||
m_modeStack->setElideMode(Qt::ElideRight);
|
||||
#ifndef Q_WS_MAC
|
||||
m_modeStack->setDocumentMode(true);
|
||||
#endif
|
||||
|
@ -27,6 +27,7 @@
|
||||
|
||||
#include "pfdgadgetwidget.h"
|
||||
#include <utils/stylehelper.h>
|
||||
#include <utils/cachedsvgitem.h>
|
||||
#include <iostream>
|
||||
#include <QDebug>
|
||||
#include <QPainter>
|
||||
@ -383,7 +384,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
- Battery stats: battery-txt
|
||||
*/
|
||||
l_scene->clear(); // Deletes all items contained in the scene as well.
|
||||
m_background = new QGraphicsSvgItem();
|
||||
m_background = new CachedSvgItem();
|
||||
// All other items will be clipped to the shape of the background
|
||||
m_background->setFlags(QGraphicsItem::ItemClipsChildrenToShape|
|
||||
QGraphicsItem::ItemClipsToShape);
|
||||
@ -391,28 +392,28 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
m_background->setElementId("background");
|
||||
l_scene->addItem(m_background);
|
||||
|
||||
m_world = new QGraphicsSvgItem();
|
||||
m_world = new CachedSvgItem();
|
||||
m_world->setParentItem(m_background);
|
||||
m_world->setSharedRenderer(m_renderer);
|
||||
m_world->setElementId("world");
|
||||
l_scene->addItem(m_world);
|
||||
|
||||
// red Roll scale: rollscale
|
||||
m_rollscale = new QGraphicsSvgItem();
|
||||
m_rollscale = new CachedSvgItem();
|
||||
m_rollscale->setSharedRenderer(m_renderer);
|
||||
m_rollscale->setElementId("rollscale");
|
||||
l_scene->addItem(m_rollscale);
|
||||
|
||||
// Home point:
|
||||
m_homewaypoint = new QGraphicsSvgItem();
|
||||
m_homewaypoint = new CachedSvgItem();
|
||||
// Next point:
|
||||
m_nextwaypoint = new QGraphicsSvgItem();
|
||||
m_nextwaypoint = new CachedSvgItem();
|
||||
// Home point bearing:
|
||||
m_homepointbearing = new QGraphicsSvgItem();
|
||||
m_homepointbearing = new CachedSvgItem();
|
||||
// Next point bearing:
|
||||
m_nextpointbearing = new QGraphicsSvgItem();
|
||||
m_nextpointbearing = new CachedSvgItem();
|
||||
|
||||
QGraphicsSvgItem *m_foreground = new QGraphicsSvgItem();
|
||||
QGraphicsSvgItem *m_foreground = new CachedSvgItem();
|
||||
m_foreground->setParentItem(m_background);
|
||||
m_foreground->setSharedRenderer(m_renderer);
|
||||
m_foreground->setElementId("foreground");
|
||||
@ -429,7 +430,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
// into a QGraphicsSvgItem which we will display at the same
|
||||
// place: we do this so that the heading scale can be clipped to
|
||||
// the compass dial region.
|
||||
m_compass = new QGraphicsSvgItem();
|
||||
m_compass = new CachedSvgItem();
|
||||
m_compass->setSharedRenderer(m_renderer);
|
||||
m_compass->setElementId("compass");
|
||||
m_compass->setFlags(QGraphicsItem::ItemClipsChildrenToShape|
|
||||
@ -440,7 +441,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
m_compass->setTransform(matrix,false);
|
||||
|
||||
// Now place the compass scale inside:
|
||||
m_compassband = new QGraphicsSvgItem();
|
||||
m_compassband = new CachedSvgItem();
|
||||
m_compassband->setSharedRenderer(m_renderer);
|
||||
m_compassband->setElementId("compass-band");
|
||||
m_compassband->setParentItem(m_compass);
|
||||
@ -462,7 +463,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
compassMatrix = m_renderer->matrixForElement("speed-bg");
|
||||
startX = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-bg")).x();
|
||||
startY = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-bg")).y();
|
||||
QGraphicsSvgItem *verticalbg = new QGraphicsSvgItem();
|
||||
QGraphicsSvgItem *verticalbg = new CachedSvgItem();
|
||||
verticalbg->setSharedRenderer(m_renderer);
|
||||
verticalbg->setElementId("speed-bg");
|
||||
verticalbg->setFlags(QGraphicsItem::ItemClipsChildrenToShape|
|
||||
@ -477,7 +478,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
m_speedscale = new QGraphicsItemGroup();
|
||||
m_speedscale->setParentItem(verticalbg);
|
||||
|
||||
QGraphicsSvgItem *speedscalelines = new QGraphicsSvgItem();
|
||||
QGraphicsSvgItem *speedscalelines = new CachedSvgItem();
|
||||
speedscalelines->setSharedRenderer(m_renderer);
|
||||
speedscalelines->setElementId("speed-scale");
|
||||
speedScaleHeight = m_renderer->matrixForElement("speed-scale").mapRect(
|
||||
@ -523,7 +524,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
startX = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).x();
|
||||
startY = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).y();
|
||||
qreal speedWindowHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).height();
|
||||
QGraphicsSvgItem *speedwindow = new QGraphicsSvgItem();
|
||||
QGraphicsSvgItem *speedwindow = new CachedSvgItem();
|
||||
speedwindow->setSharedRenderer(m_renderer);
|
||||
speedwindow->setElementId("speed-window");
|
||||
speedwindow->setFlags(QGraphicsItem::ItemClipsChildrenToShape|
|
||||
@ -548,7 +549,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
compassMatrix = m_renderer->matrixForElement("altitude-bg");
|
||||
startX = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-bg")).x();
|
||||
startY = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-bg")).y();
|
||||
verticalbg = new QGraphicsSvgItem();
|
||||
verticalbg = new CachedSvgItem();
|
||||
verticalbg->setSharedRenderer(m_renderer);
|
||||
verticalbg->setElementId("altitude-bg");
|
||||
verticalbg->setFlags(QGraphicsItem::ItemClipsChildrenToShape|
|
||||
@ -563,7 +564,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
m_altitudescale = new QGraphicsItemGroup();
|
||||
m_altitudescale->setParentItem(verticalbg);
|
||||
|
||||
QGraphicsSvgItem *altitudescalelines = new QGraphicsSvgItem();
|
||||
QGraphicsSvgItem *altitudescalelines = new CachedSvgItem();
|
||||
altitudescalelines->setSharedRenderer(m_renderer);
|
||||
altitudescalelines->setElementId("altitude-scale");
|
||||
altitudeScaleHeight = m_renderer->matrixForElement("altitude-scale").mapRect(
|
||||
@ -604,7 +605,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
startX = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).x();
|
||||
startY = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).y();
|
||||
qreal altitudeWindowHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).height();
|
||||
QGraphicsSvgItem *altitudewindow = new QGraphicsSvgItem();
|
||||
QGraphicsSvgItem *altitudewindow = new CachedSvgItem();
|
||||
altitudewindow->setSharedRenderer(m_renderer);
|
||||
altitudewindow->setElementId("altitude-window");
|
||||
altitudewindow->setFlags(QGraphicsItem::ItemClipsChildrenToShape|
|
||||
@ -633,7 +634,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected");
|
||||
startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x();
|
||||
startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y();
|
||||
gcsTelemetryArrow = new QGraphicsSvgItem();
|
||||
gcsTelemetryArrow = new CachedSvgItem();
|
||||
gcsTelemetryArrow->setSharedRenderer(m_renderer);
|
||||
gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected");
|
||||
l_scene->addItem(gcsTelemetryArrow);
|
||||
@ -669,7 +670,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected");
|
||||
startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x();
|
||||
startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y();
|
||||
gcsTelemetryArrow = new QGraphicsSvgItem();
|
||||
gcsTelemetryArrow = new CachedSvgItem();
|
||||
gcsTelemetryArrow->setSharedRenderer(m_renderer);
|
||||
gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected");
|
||||
l_scene->addItem(gcsTelemetryArrow);
|
||||
@ -702,7 +703,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected");
|
||||
startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x();
|
||||
startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y();
|
||||
gcsTelemetryArrow = new QGraphicsSvgItem();
|
||||
gcsTelemetryArrow = new CachedSvgItem();
|
||||
gcsTelemetryArrow->setSharedRenderer(m_renderer);
|
||||
gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected");
|
||||
l_scene->addItem(gcsTelemetryArrow);
|
||||
@ -771,7 +772,7 @@ void PFDGadgetWidget::setDialFile(QString dfn)
|
||||
{ qDebug()<<"Error on PFD artwork file.";
|
||||
m_renderer->load(QString(":/pfd/images/pfd-default.svg"));
|
||||
l_scene->clear(); // This also deletes all items contained in the scene.
|
||||
m_background = new QGraphicsSvgItem();
|
||||
m_background = new CachedSvgItem();
|
||||
m_background->setSharedRenderer(m_renderer);
|
||||
l_scene->addItem(m_background);
|
||||
pfdError = true;
|
||||
|
@ -31,6 +31,7 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \
|
||||
$$UAVOBJECT_SYNTHETICS/ahrssettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/gcstelemetrystats.h \
|
||||
$$UAVOBJECT_SYNTHETICS/attituderaw.h \
|
||||
$$UAVOBJECT_SYNTHETICS/camerastabsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/flighttelemetrystats.h \
|
||||
$$UAVOBJECT_SYNTHETICS/systemstats.h \
|
||||
$$UAVOBJECT_SYNTHETICS/systemalarms.h \
|
||||
@ -71,7 +72,8 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \
|
||||
$$UAVOBJECT_SYNTHETICS/hwsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/gcsreceiver.h \
|
||||
$$UAVOBJECT_SYNTHETICS/receiveractivity.h \
|
||||
$$UAVOBJECT_SYNTHETICS/attitudesettings.h
|
||||
$$UAVOBJECT_SYNTHETICS/attitudesettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/cameradesired.h
|
||||
|
||||
SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/ahrsstatus.cpp \
|
||||
@ -81,6 +83,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/ahrssettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/gcstelemetrystats.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/attituderaw.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/camerastabsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/flighttelemetrystats.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/systemstats.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/systemalarms.cpp \
|
||||
@ -122,4 +125,5 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/hwsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/gcsreceiver.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/receiveractivity.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/attitudesettings.cpp
|
||||
$$UAVOBJECT_SYNTHETICS/attitudesettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/cameradesired.cpp
|
||||
|
@ -189,7 +189,7 @@ bool deviceWidget::populateBoardStructuredDescription(QByteArray desc)
|
||||
myDevice->lblDescription->setText(QString("Firmware tag: ")+onBoardDescrition.description);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg"));
|
||||
myDevice->lblCertified->setPixmap(pix);
|
||||
myDevice->lblCertified->setToolTip(tr("Official Firmware Build"));
|
||||
myDevice->lblCertified->setToolTip(tr("Tagged officially released firmware build"));
|
||||
|
||||
}
|
||||
else
|
||||
@ -197,7 +197,7 @@ bool deviceWidget::populateBoardStructuredDescription(QByteArray desc)
|
||||
myDevice->lblDescription->setText(onBoardDescrition.description);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
|
||||
myDevice->lblCertified->setPixmap(pix);
|
||||
myDevice->lblCertified->setToolTip(tr("Custom Firmware Build"));
|
||||
myDevice->lblCertified->setToolTip(tr("Untagged or custom firmware build"));
|
||||
}
|
||||
|
||||
myDevice->lblBrdName->setText(idToBoardName(onBoardDescrition.boardType<<8));
|
||||
@ -220,7 +220,7 @@ bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc)
|
||||
myDevice->description->setText(LoadedDescrition.description);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg"));
|
||||
myDevice->lblCertifiedL->setPixmap(pix);
|
||||
myDevice->lblCertifiedL->setToolTip(tr("Official Firmware Build"));
|
||||
myDevice->lblCertifiedL->setToolTip(tr("Tagged officially released firmware build"));
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -228,7 +228,7 @@ bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc)
|
||||
myDevice->description->setText(LoadedDescrition.description);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
|
||||
myDevice->lblCertifiedL->setPixmap(pix);
|
||||
myDevice->lblCertifiedL->setToolTip(tr("Custom Firmware Build"));
|
||||
myDevice->lblCertifiedL->setToolTip(tr("Untagged or custom firmware build"));
|
||||
}
|
||||
myDevice->lblBrdNameL->setText(deviceDescriptorStruct::idToBoardName(LoadedDescrition.boardType<<8));
|
||||
|
||||
@ -315,34 +315,34 @@ void deviceWidget::loadFirmware()
|
||||
myDevice->groupCustom->setVisible(false);
|
||||
if(myDevice->lblCRC->text()==myDevice->lblCRCL->text())
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware the same as on the board. You should not upload it"));
|
||||
myDevice->statusLabel->setText(tr("The board has the same firmware as loaded. No need to update"));
|
||||
px.load(QString(":/uploader/images/warning.svg"));
|
||||
}
|
||||
else if(myDevice->lblDevName->text()!=myDevice->lblBrdNameL->text())
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware is not suited for the HW connected. You shouldn't upload it"));
|
||||
px.load(QString(":/uploader/images/warning.svg"));
|
||||
myDevice->statusLabel->setText(tr("WARNING: the loaded firmware is for different hardware. Do not update!"));
|
||||
px.load(QString(":/uploader/images/error.svg"));
|
||||
}
|
||||
else if(QDateTime::fromString(onBoardDescrition.buildDate)>QDateTime::fromString(LoadedDescrition.buildDate))
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware is older than the firmware on the board. You should not upload it"));
|
||||
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(!LoadedDescrition.description.startsWith("release",Qt::CaseInsensitive))
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware is not an oficial OpenPilot release. You should upload it only if you know what you are doing"));
|
||||
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"));
|
||||
}
|
||||
else
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("Everything seems OK. You should upload the loaded firmware by pressing 'Flash'"));
|
||||
myDevice->statusLabel->setText(tr("This is the tagged officially released OpenPilot firmware"));
|
||||
px.load(QString(":/uploader/images/gtk-info.svg"));
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware was not packaged with the OpenPilot format. You should not upload it unless you know what you are doing."));
|
||||
px.load(QString(":/uploader/images/warning.svg"));
|
||||
myDevice->statusLabel->setText(tr("WARNING: the loaded firmware was not packaged with the OpenPilot format. Do not update unless you know what you are doing"));
|
||||
px.load(QString(":/uploader/images/error.svg"));
|
||||
myDevice->youdont->setChecked(false);
|
||||
myDevice->youdont->setVisible(true);
|
||||
myDevice->verticalGroupBox_loaded->setVisible(false);
|
||||
@ -517,7 +517,7 @@ QString deviceWidget::setOpenFileName()
|
||||
QString fileName = QFileDialog::getOpenFileName(this,
|
||||
tr("Select firmware file"),
|
||||
"",
|
||||
tr("Firmware Files (*.bin *.opfw)"),
|
||||
tr("Firmware Files (*.opfw *.bin)"),
|
||||
&selectedFilter,
|
||||
options);
|
||||
return fileName;
|
||||
|
@ -93,10 +93,10 @@
|
||||
<item>
|
||||
<widget class="QPushButton" name="pbLoad">
|
||||
<property name="toolTip">
|
||||
<string>Loads the firmware</string>
|
||||
<string>Open a file with new firmware image to be flashed</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Load...</string>
|
||||
<string>Open...</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
@ -116,7 +116,7 @@
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Update the firmware on this board.</string>
|
||||
<string>Write loaded firmware image to the board</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Flash</string>
|
||||
@ -126,7 +126,7 @@
|
||||
<item>
|
||||
<widget class="QPushButton" name="retrieveButton">
|
||||
<property name="toolTip">
|
||||
<string>Download the current board firmware to your computer</string>
|
||||
<string>Read and save current board firmware to a file</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Retrieve...</string>
|
||||
@ -228,7 +228,7 @@
|
||||
<item>
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="text">
|
||||
<string>GIT Tag:</string>
|
||||
<string>Git tag:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
|
35
ground/openpilotgcs/src/plugins/uploader/images/error.svg
Normal file
35
ground/openpilotgcs/src/plugins/uploader/images/error.svg
Normal file
@ -0,0 +1,35 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
<svg id="svg3247" xmlns="http://www.w3.org/2000/svg" height="48" width="48" version="1.0" xmlns:xlink="http://www.w3.org/1999/xlink">
|
||||
<defs id="defs3249">
|
||||
<linearGradient id="linearGradient2411" y2="5.4676" gradientUnits="userSpaceOnUse" x2="63.397" gradientTransform="matrix(2.1154 0 0 2.1153 -107.58 32.427)" y1="-12.489" x1="63.397">
|
||||
<stop id="stop4875" style="stop-color:#fff" offset="0"/>
|
||||
<stop id="stop4877" style="stop-color:#fff;stop-opacity:0" offset="1"/>
|
||||
</linearGradient>
|
||||
<linearGradient id="linearGradient2416" y2="3.0816" gradientUnits="userSpaceOnUse" x2="18.379" gradientTransform="matrix(.95844 0 0 .95844 .99752 1.9975)" y1="44.98" x1="18.379">
|
||||
<stop id="stop2492" style="stop-color:#791235" offset="0"/>
|
||||
<stop id="stop2494" style="stop-color:#dd3b27" offset="1"/>
|
||||
</linearGradient>
|
||||
<radialGradient id="radialGradient2414" gradientUnits="userSpaceOnUse" cy="3.99" cx="23.896" gradientTransform="matrix(0 2.2875 -3.0194 0 36.047 -50.63)" r="20.397">
|
||||
<stop id="stop3244" style="stop-color:#f8b17e" offset="0"/>
|
||||
<stop id="stop3246" style="stop-color:#e35d4f" offset=".26238"/>
|
||||
<stop id="stop3248" style="stop-color:#c6262e" offset=".66094"/>
|
||||
<stop id="stop3250" style="stop-color:#690b54" offset="1"/>
|
||||
</radialGradient>
|
||||
<radialGradient id="radialGradient2419" gradientUnits="userSpaceOnUse" cy="4.625" cx="62.625" gradientTransform="matrix(2.1647 0 0 .75294 -111.56 36.518)" r="10.625">
|
||||
<stop id="stop8840" offset="0"/>
|
||||
<stop id="stop8842" style="stop-opacity:0" offset="1"/>
|
||||
</radialGradient>
|
||||
</defs>
|
||||
<g id="layer1">
|
||||
<g id="g3275">
|
||||
<path id="path8836" style="opacity:.3;fill-rule:evenodd;fill:url(#radialGradient2419)" d="m47 40c0 4.418-10.297 8-23 8s-23-3.582-23-8 10.297-8 23-8 23 3.582 23 8z"/>
|
||||
<path id="path2555" style="stroke-linejoin:round;stroke:url(#linearGradient2416);stroke-linecap:round;stroke-width:1.0037;fill:url(#radialGradient2414)" d="m24 5.5018c-10.758 0-19.498 8.7402-19.498 19.498-0.0002 10.758 8.74 19.498 19.498 19.498s19.498-8.74 19.498-19.498-8.74-19.498-19.498-19.498z"/>
|
||||
<path id="path8655" style="opacity:.4;stroke:url(#linearGradient2411);fill:none" d="m42.5 24.999c0 10.218-8.283 18.501-18.5 18.501s-18.5-8.283-18.5-18.501c0-10.217 8.283-18.499 18.5-18.499s18.5 8.282 18.5 18.499z"/>
|
||||
</g>
|
||||
<g id="g3243" transform="translate(51.075 .56862)">
|
||||
<path id="path3295" style="opacity:.2" d="m-29.451 12.554c0.563 5.5 1.208 10.961 1.687 16.482h1.53c0.397-5.302 1.038-10.571 1.501-15.867 0.236-1.254-0.408-2.742-1.732-3.047-1.308-0.3824-2.77 0.565-2.944 1.918-0.029 0.17-0.042 0.342-0.042 0.514zm-0.167 22.359c-0.059 1.637 1.742 2.92 3.28 2.401 1.489-0.38 2.274-2.252 1.51-3.583-0.683-1.375-2.687-1.829-3.84-0.776-0.582 0.479-0.968 1.194-0.95 1.958z"/>
|
||||
<path id="text2315" style="fill:#fff" d="m-29.451 13.555c0.563 5.499 1.208 10.96 1.687 16.481h1.53c0.397-5.301 1.038-10.571 1.501-15.866 0.236-1.254-0.408-2.743-1.732-3.048-1.308-0.382-2.77 0.565-2.944 1.918-0.029 0.17-0.042 0.342-0.042 0.515zm-0.167 22.358c-0.059 1.637 1.742 2.921 3.28 2.402 1.489-0.381 2.274-2.253 1.51-3.584-0.683-1.375-2.687-1.828-3.84-0.776-0.582 0.479-0.968 1.194-0.95 1.958z"/>
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
After Width: | Height: | Size: 3.2 KiB |
@ -1,35 +1,290 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
<svg id="svg3247" xmlns="http://www.w3.org/2000/svg" height="48" width="48" version="1.0" xmlns:xlink="http://www.w3.org/1999/xlink">
|
||||
<defs id="defs3249">
|
||||
<linearGradient id="linearGradient2411" y2="5.4676" gradientUnits="userSpaceOnUse" x2="63.397" gradientTransform="matrix(2.1154 0 0 2.1153 -107.58 32.427)" y1="-12.489" x1="63.397">
|
||||
<stop id="stop4875" style="stop-color:#fff" offset="0"/>
|
||||
<stop id="stop4877" style="stop-color:#fff;stop-opacity:0" offset="1"/>
|
||||
</linearGradient>
|
||||
<linearGradient id="linearGradient2416" y2="3.0816" gradientUnits="userSpaceOnUse" x2="18.379" gradientTransform="matrix(.95844 0 0 .95844 .99752 1.9975)" y1="44.98" x1="18.379">
|
||||
<stop id="stop2492" style="stop-color:#791235" offset="0"/>
|
||||
<stop id="stop2494" style="stop-color:#dd3b27" offset="1"/>
|
||||
</linearGradient>
|
||||
<radialGradient id="radialGradient2414" gradientUnits="userSpaceOnUse" cy="3.99" cx="23.896" gradientTransform="matrix(0 2.2875 -3.0194 0 36.047 -50.63)" r="20.397">
|
||||
<stop id="stop3244" style="stop-color:#f8b17e" offset="0"/>
|
||||
<stop id="stop3246" style="stop-color:#e35d4f" offset=".26238"/>
|
||||
<stop id="stop3248" style="stop-color:#c6262e" offset=".66094"/>
|
||||
<stop id="stop3250" style="stop-color:#690b54" offset="1"/>
|
||||
</radialGradient>
|
||||
<radialGradient id="radialGradient2419" gradientUnits="userSpaceOnUse" cy="4.625" cx="62.625" gradientTransform="matrix(2.1647 0 0 .75294 -111.56 36.518)" r="10.625">
|
||||
<stop id="stop8840" offset="0"/>
|
||||
<stop id="stop8842" style="stop-opacity:0" offset="1"/>
|
||||
</radialGradient>
|
||||
</defs>
|
||||
<g id="layer1">
|
||||
<g id="g3275">
|
||||
<path id="path8836" style="opacity:.3;fill-rule:evenodd;fill:url(#radialGradient2419)" d="m47 40c0 4.418-10.297 8-23 8s-23-3.582-23-8 10.297-8 23-8 23 3.582 23 8z"/>
|
||||
<path id="path2555" style="stroke-linejoin:round;stroke:url(#linearGradient2416);stroke-linecap:round;stroke-width:1.0037;fill:url(#radialGradient2414)" d="m24 5.5018c-10.758 0-19.498 8.7402-19.498 19.498-0.0002 10.758 8.74 19.498 19.498 19.498s19.498-8.74 19.498-19.498-8.74-19.498-19.498-19.498z"/>
|
||||
<path id="path8655" style="opacity:.4;stroke:url(#linearGradient2411);fill:none" d="m42.5 24.999c0 10.218-8.283 18.501-18.5 18.501s-18.5-8.283-18.5-18.501c0-10.217 8.283-18.499 18.5-18.499s18.5 8.282 18.5 18.499z"/>
|
||||
|
||||
<svg
|
||||
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||
xmlns:cc="http://creativecommons.org/ns#"
|
||||
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||
xmlns:svg="http://www.w3.org/2000/svg"
|
||||
xmlns="http://www.w3.org/2000/svg"
|
||||
xmlns:xlink="http://www.w3.org/1999/xlink"
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
width="48"
|
||||
height="48"
|
||||
id="svg2"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.1 "
|
||||
sodipodi:docname="warning.svg">
|
||||
<defs
|
||||
id="defs4">
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
id="linearGradient2850">
|
||||
<stop
|
||||
style="stop-color:#eeeeee;stop-opacity:1;"
|
||||
offset="0"
|
||||
id="stop2852" />
|
||||
<stop
|
||||
style="stop-color:#eeeeee;stop-opacity:0;"
|
||||
offset="1"
|
||||
id="stop2854" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
id="linearGradient3657">
|
||||
<stop
|
||||
style="stop-color:#986601;stop-opacity:1;"
|
||||
offset="0"
|
||||
id="stop3659" />
|
||||
<stop
|
||||
id="stop3665"
|
||||
offset="0.33080238"
|
||||
style="stop-color:#fdca01;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#ffff99;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop3661" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
id="linearGradient3632">
|
||||
<stop
|
||||
style="stop-color:#999999;stop-opacity:0"
|
||||
offset="0"
|
||||
id="stop3634" />
|
||||
<stop
|
||||
id="stop3640"
|
||||
offset="0.50655138"
|
||||
style="stop-color:#e6e6e6;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#999999;stop-opacity:0;"
|
||||
offset="1"
|
||||
id="stop3636" />
|
||||
</linearGradient>
|
||||
<inkscape:perspective
|
||||
sodipodi:type="inkscape:persp3d"
|
||||
inkscape:vp_x="0 : 526.18109 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_z="744.09448 : 526.18109 : 1"
|
||||
inkscape:persp3d-origin="372.04724 : 350.78739 : 1"
|
||||
id="perspective10" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient3632"
|
||||
id="linearGradient3638"
|
||||
x1="19.10717"
|
||||
y1="127.34224"
|
||||
x2="260.11157"
|
||||
y2="127.34224"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0.19402788,0,0,0.19376669,5.5464026,989.71412)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient3632"
|
||||
id="linearGradient3644"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="2.3978782"
|
||||
y1="121.40089"
|
||||
x2="260.11157"
|
||||
y2="127.34224"
|
||||
gradientTransform="matrix(-0.09701394,0.16780688,-0.16803307,-0.09688335,73.208116,1013.465)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient3632"
|
||||
id="linearGradient3648"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0.09701394,0.16780688,0.16803307,-0.09688335,-8.1841884,1014.9031)"
|
||||
x1="19.10717"
|
||||
y1="127.34224"
|
||||
x2="260.11157"
|
||||
y2="127.34224" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient3657"
|
||||
id="linearGradient3680"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="112.5"
|
||||
y1="275.40689"
|
||||
x2="112.5"
|
||||
y2="-4.2200408"
|
||||
gradientTransform="matrix(0.19402788,0,0,0.19376669,5.5464026,989.71412)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient3657"
|
||||
id="linearGradient2847"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0.45813096,0,0,0.45751424,0.67535737,1.90895)"
|
||||
x1="112.5"
|
||||
y1="275.40689"
|
||||
x2="112.5"
|
||||
y2="-4.2200408" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient2850"
|
||||
id="linearGradient2856"
|
||||
x1="63.993164"
|
||||
y1="8.8525076"
|
||||
x2="63.993164"
|
||||
y2="91.242332"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0.42352056,0,0,0.42352056,5.2603749,988.90564)" />
|
||||
</defs>
|
||||
<sodipodi:namedview
|
||||
id="base"
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1.0"
|
||||
inkscape:pageopacity="0.0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:zoom="1"
|
||||
inkscape:cx="-46.02894"
|
||||
inkscape:cy="-0.138668"
|
||||
inkscape:document-units="px"
|
||||
inkscape:current-layer="layer1"
|
||||
showgrid="false"
|
||||
showguides="true"
|
||||
inkscape:guide-bbox="true"
|
||||
inkscape:window-width="1400"
|
||||
inkscape:window-height="1003"
|
||||
inkscape:window-x="-4"
|
||||
inkscape:window-y="-4"
|
||||
inkscape:window-maximized="1"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
fit-margin-bottom="0" />
|
||||
<metadata
|
||||
id="metadata7">
|
||||
<rdf:RDF>
|
||||
<cc:Work
|
||||
rdf:about="">
|
||||
<dc:format>image/svg+xml</dc:format>
|
||||
<dc:type
|
||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||
<dc:title></dc:title>
|
||||
<cc:license
|
||||
rdf:resource="" />
|
||||
</cc:Work>
|
||||
</rdf:RDF>
|
||||
</metadata>
|
||||
<g
|
||||
inkscape:label="Layer 1"
|
||||
inkscape:groupmode="layer"
|
||||
id="layer1"
|
||||
transform="translate(-9.125,-988.32372)">
|
||||
<g
|
||||
id="g2975"
|
||||
transform="matrix(0.42352056,0,0,0.42352056,3.9898132,596.57221)">
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 15.5625,1033.9688 c 35.520833,-1e-4 71.041667,0 106.5625,0 -17.76042,-30.7084 -35.520833,-61.41672 -53.28125,-92.12505 -17.760417,30.70833 -35.520833,61.41665 -53.28125,92.12505 z"
|
||||
id="path2874"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 15.03125,1034.2812 c 35.875,0 71.75,1e-4 107.625,0 -17.9375,-31.0312 -35.875,-62.06245 -53.8125,-93.0937 -17.9375,31.03125 -35.875,62.0625 -53.8125,93.0937 z"
|
||||
id="path2878"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="M 68.78125,940.65625 C 50.914197,971.92452 32.089324,1003.5095 14.75,1034.5625 c 36.091043,-0.084 72.452585,0.167 108.375,-0.125 -18.12273,-31.2282 -36.179858,-62.71402 -54.34375,-93.78125 z"
|
||||
id="path2882"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 68.71875,940.34375 c -18.21641,31.323 -36.515662,62.85885 -54.46875,94.28125 3.741727,0.6849 8.400562,0.01 12.437499,0.25 32.199492,-0.1047 64.634624,0.2091 96.687501,-0.1562 -2.01836,-4.5363 -5.32611,-9.2498 -7.78102,-13.8467 -15.605622,-26.8084 -31.035873,-53.9715 -46.75023,-80.5596 -0.04179,0.009 -0.102865,-0.0245 -0.125,0.0312 z"
|
||||
id="path2886"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 68.625,940.0625 c -1.898442,2.49808 -3.28205,5.61534 -4.997045,8.33338 -16.533965,28.68448 -33.220463,57.33752 -49.659205,86.04162 0.03222,1.4296 2.384617,0.414 3.325,0.7187 35.335267,-0.021 70.705057,0.042 106.01875,-0.031 1.22525,-0.6532 -0.7388,-2.314 -1.00779,-3.2436 -17.6836,-30.5632 -35.377677,-61.22113 -53.05471,-91.72515 -0.17511,-0.11773 -0.421252,-0.17697 -0.625,-0.0937 z"
|
||||
id="path2890"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 68.59375,939.65625 c -0.849146,0.26354 -1.046037,1.3532 -1.557052,2.02713 -17.793483,30.78262 -35.586965,61.56522 -53.380448,92.34782 -0.382416,0.719 0.174709,1.5807 0.975,1.5313 36.175,0 72.35,0 108.525,0 0.89258,-0.022 1.26685,-1.0887 0.72476,-1.7909 -18.05408,-31.2051 -36.108172,-62.41024 -54.16226,-93.61535 -0.138442,-0.39413 -0.699141,-0.63415 -1.125,-0.5 z"
|
||||
id="path2894"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 68.5625,939.4375 c -1.590286,0.85105 -1.905887,3.12983 -3.033256,4.48971 -17.3826,30.12088 -34.865418,60.21889 -52.185494,90.35399 -0.26697,1.59 1.857007,1.73 2.9875,1.5 35.676932,-0.021 71.388394,0.042 107.04375,-0.031 1.49785,-0.393 0.95277,-2.2528 0.0615,-3.1109 -17.9457,-30.9718 -35.823978,-62.04135 -53.8115,-92.9518 -0.298373,-0.1963 -0.695976,-0.36722 -1.0625,-0.25 z"
|
||||
id="path2898"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 68.4375,939.1875 c -2.665517,1.85677 -3.376329,5.93312 -5.441511,8.47941 -16.5968,28.90914 -33.570754,57.68499 -49.933489,86.67689 0.03767,3.0044 4.461608,1.2959 6.268751,1.7187 34.807311,-0.1049 69.688836,0.2093 104.449999,-0.1563 2.48477,-1.8446 -1.4715,-4.7803 -2.01675,-6.799 -17.3631,-29.87443 -34.529605,-59.95355 -52.0145,-89.70095 -0.363201,-0.23912 -0.899825,-0.38311 -1.3125,-0.21875 z"
|
||||
id="path2902"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 68.28125,938.90625 c -4.241668,4.50666 -6.418986,11.25217 -10.039272,16.42758 -15.094516,26.42114 -30.798679,52.67447 -45.523228,79.19737 0.973486,3.9884 7.091213,0.8607 9.912501,1.8438 33.766663,-0.1709 67.711681,0.339 101.368749,-0.25 3.02785,-2.6896 -2.75748,-6.5679 -3.33688,-9.4803 -17.04167,-29.14204 -33.624067,-58.76297 -50.94437,-87.61345 -0.446728,-0.17465 -0.976209,-0.34944 -1.4375,-0.125 z"
|
||||
id="path2906"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 68.25,938.625 c -4.248341,3.6207 -5.799608,10.30836 -9.257129,14.82104 -15.417424,27.05725 -31.592719,53.89936 -46.555371,81.08516 0.983203,4.5373 7.950662,1.0268 11.09375,2.125 33.518304,-0.1928 67.217157,0.3823 100.625,-0.2812 3.39168,-3.0568 -2.98383,-7.3811 -3.69406,-10.6654 C 103.54587,996.81337 87.118698,967.38512 69.90625,938.8125 69.430976,938.55208 68.767472,938.4102 68.25,938.625 z"
|
||||
id="path2910"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.02999998;color:#000000;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 68.15625,938.3125 c -4.44705,3.59724 -5.907996,10.41675 -9.444629,14.97729 -15.460635,27.02312 -31.4413,53.84841 -46.586621,80.99141 0.504744,5.1808 8.151862,1.69 11.40625,2.6876 33.572728,-0.2149 67.307606,0.4253 100.78125,-0.3126 3.72904,-3.2084 -2.74749,-7.7207 -3.56937,-11.1027 C 103.77,996.62017 87.401308,967.12253 70.0625,938.53125 c -0.585006,-0.29694 -1.280735,-0.43981 -1.90625,-0.21875 z"
|
||||
id="path2914"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;color:#000000;fill:#999999;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 32.613292,994.11625 a 0.38809457,0.38757213 0 0 0 -0.315295,0.19377 L 9.3056929,1034.0806 a 0.38809457,0.38757213 0 0 0 0.3334856,0.5814 l 45.9906705,0 a 0.38809457,0.38757213 0 0 0 0.333488,-0.5814 L 32.971031,994.31002 a 0.38809457,0.38757213 0 0 0 -0.357739,-0.19377 z"
|
||||
id="path3618"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path3630"
|
||||
d="m 33.062615,1020.8425 -23.7569221,13.2381 c -0.1349863,0.2336 0.06345,0.5795 0.3334856,0.5814 l 45.9906705,0 c 0.270037,0 0.468473,-0.3478 0.333488,-0.5814 -22.912236,-13.1428 -22.926544,-13.255 -22.900722,-13.2381 z"
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;color:#000000;fill:url(#linearGradient3638);fill-opacity:1;stroke:none;stroke-width:4;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
sodipodi:nodetypes="cccccc"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
sodipodi:nodetypes="cccccc"
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;color:#000000;fill:url(#linearGradient3644);fill-opacity:1;stroke:none;stroke-width:4;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 32.854149,994.53305 c -0.135055,-0.23353 -0.534234,-0.23485 -0.670841,-0.002 L 9.1879715,1034.3063 c -0.1335054,0.2344 0.067312,0.579 0.3373558,0.5791 5.9693077,-5.4781 19.5453407,-12.2128 23.6767387,-14.9216 l -0.347917,-25.43075 z"
|
||||
id="path3642"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path3646"
|
||||
d="m 32.169778,995.97114 c 0.135055,-0.23353 0.534234,-0.23485 0.670842,-0.002 l 22.995335,39.77546 c 0.133507,0.2344 -0.06731,0.5791 -0.337355,0.5791 0.102661,-0.049 -22.526131,-13.897 -22.536175,-13.8982 l -0.792647,-26.45412 z"
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;color:#000000;fill:url(#linearGradient3648);fill-opacity:1;stroke:none;stroke-width:4;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
sodipodi:nodetypes="cccccc"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;color:#000000;fill:url(#linearGradient3680);fill-opacity:1;stroke:none;stroke-width:4;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 12.313125,1032.7243 c 13.547593,0 27.095185,0 40.64278,0 -6.772788,-11.7128 -13.545573,-23.4256 -20.318359,-35.13841 -6.774808,11.71281 -13.549614,23.42561 -20.324421,35.13841 z"
|
||||
id="path2838"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:#000000;stroke:#333333;stroke-width:0.42352057;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 29.60586,1009.936 1.212675,13.8059 3.104446,0 1.649237,-13.8059 -5.966358,0 z"
|
||||
id="path3682"
|
||||
sodipodi:nodetypes="ccccc"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:#000000;stroke:#333333;stroke-width:0.42352057;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 34.747599,1027.8352 c 0,1.3243 -1.075008,2.3979 -2.401095,2.3979 -1.326087,0 -2.401095,-1.0736 -2.401095,-2.3979 0,-1.3243 1.075008,-2.3978 2.401095,-2.3978 1.326087,0 2.401095,1.0735 2.401095,2.3978 z"
|
||||
id="path3684"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.5;color:#000000;fill:#eeeeee;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 32.577451,994.12023 a 0.38809457,0.38757213 0 0 0 -0.277935,0.18529 L 9.3102902,1034.0767 a 0.38809457,0.38757213 0 0 0 0.3308755,0.5824 l 0.3176404,0 22.3407099,-38.65949 a 0.38809457,0.38757213 0 0 1 0.31764,-0.18529 0.38809457,0.38757213 0 0 1 0.357346,0.18529 l 22.340709,38.65949 0.317641,0 a 0.38809457,0.38757213 0 0 0 0.330875,-0.5824 L 32.974502,994.30552 a 0.38809457,0.38757213 0 0 0 -0.357346,-0.18529 0.38809457,0.38757213 0 0 0 -0.0397,0 z"
|
||||
id="path2833"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;opacity:0.4;color:#000000;fill:#eeeeee;fill-opacity:1;stroke:none;stroke-width:1;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 9.4823455,1033.7856 -0.1720553,0.2911 a 0.38809457,0.38757213 0 0 0 0.3308755,0.5824 l 45.9916863,0 a 0.38809457,0.38757213 0 0 0 0.330875,-0.5824 l -0.172055,-0.2911 a 0.38809457,0.38757213 0 0 1 -0.15882,0.026 l -45.9916863,0 a 0.38809457,0.38757213 0 0 1 -0.1588202,-0.026 z"
|
||||
id="path2839"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="font-size:medium;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:normal;letter-spacing:normal;word-spacing:normal;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;color:#000000;fill:url(#linearGradient2856);fill-opacity:1;stroke:none;stroke-width:4;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
d="m 32.643626,997.58781 -12.890907,22.27449 c 4.381105,-2.304 10.146879,-3.6925 16.464362,-3.6925 2.639259,0 5.184404,0.2491 7.57043,0.7014 L 32.643626,997.58781 z"
|
||||
id="path2843"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g id="g3243" transform="translate(51.075 .56862)">
|
||||
<path id="path3295" style="opacity:.2" d="m-29.451 12.554c0.563 5.5 1.208 10.961 1.687 16.482h1.53c0.397-5.302 1.038-10.571 1.501-15.867 0.236-1.254-0.408-2.742-1.732-3.047-1.308-0.3824-2.77 0.565-2.944 1.918-0.029 0.17-0.042 0.342-0.042 0.514zm-0.167 22.359c-0.059 1.637 1.742 2.92 3.28 2.401 1.489-0.38 2.274-2.252 1.51-3.583-0.683-1.375-2.687-1.829-3.84-0.776-0.582 0.479-0.968 1.194-0.95 1.958z"/>
|
||||
<path id="text2315" style="fill:#fff" d="m-29.451 13.555c0.563 5.499 1.208 10.96 1.687 16.481h1.53c0.397-5.301 1.038-10.571 1.501-15.866 0.236-1.254-0.408-2.743-1.732-3.048-1.308-0.382-2.77 0.565-2.944 1.918-0.029 0.17-0.042 0.342-0.042 0.515zm-0.167 22.358c-0.059 1.637 1.742 2.921 3.28 2.402 1.489-0.381 2.274-2.253 1.51-3.584-0.683-1.375-2.687-1.828-3.84-0.776-0.582 0.479-0.968 1.194-0.95 1.958z"/>
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
||||
|
Before Width: | Height: | Size: 3.2 KiB After Width: | Height: | Size: 24 KiB |
@ -117,7 +117,7 @@ void runningDeviceWidget::populate()
|
||||
myDevice->lblFWTag->setText(QString("Firmware tag: ")+devDesc.description);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg"));
|
||||
myDevice->lblCertified->setPixmap(pix);
|
||||
myDevice->lblCertified->setToolTip(tr("Official Firmware Build"));
|
||||
myDevice->lblCertified->setToolTip(tr("Tagged officially released firmware build"));
|
||||
|
||||
}
|
||||
else
|
||||
@ -125,7 +125,7 @@ void runningDeviceWidget::populate()
|
||||
myDevice->lblFWTag->setText(QString("Firmware tag: ")+devDesc.description);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
|
||||
myDevice->lblCertified->setPixmap(pix);
|
||||
myDevice->lblCertified->setToolTip(tr("Custom Firmware Build"));
|
||||
myDevice->lblCertified->setToolTip(tr("Untagged or custom firmware build"));
|
||||
}
|
||||
myDevice->lblGitCommitTag->setText("Git commit tag: "+devDesc.gitTag);
|
||||
myDevice->lblFWDate->setText(QString("Firmware date: ") + devDesc.buildDate);
|
||||
|
@ -11,5 +11,6 @@
|
||||
<file>images/deviceID-0101.svg</file>
|
||||
<file>images/application-certificate.svg</file>
|
||||
<file>images/warning.svg</file>
|
||||
<file>images/error.svg</file>
|
||||
</qresource>
|
||||
</RCC>
|
||||
|
@ -34,6 +34,7 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template
|
||||
<<"uint16_t" << "uint32_t" << "float" << "uint8_t";
|
||||
|
||||
QString flightObjInit,objInc,objFileNames,objNames;
|
||||
qint32 sizeCalc;
|
||||
flightCodePath = QDir( templatepath + QString("flight/UAVObjects"));
|
||||
flightOutputPath = QDir( outputpath + QString("flight") );
|
||||
flightOutputPath.mkpath(flightOutputPath.absolutePath());
|
||||
@ -41,6 +42,7 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template
|
||||
flightCodeTemplate = readFile( flightCodePath.absoluteFilePath("uavobjecttemplate.c") );
|
||||
flightIncludeTemplate = readFile( flightCodePath.absoluteFilePath("inc/uavobjecttemplate.h") );
|
||||
flightInitTemplate = readFile( flightCodePath.absoluteFilePath("uavobjectsinittemplate.c") );
|
||||
flightInitIncludeTemplate = readFile( flightCodePath.absoluteFilePath("inc/uavobjectsinittemplate.h") );
|
||||
flightMakeTemplate = readFile( flightCodePath.absoluteFilePath("Makefiletemplate.inc") );
|
||||
|
||||
if ( flightCodeTemplate.isNull() || flightIncludeTemplate.isNull() || flightInitTemplate.isNull()) {
|
||||
@ -48,6 +50,7 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template
|
||||
return false;
|
||||
}
|
||||
|
||||
sizeCalc = 0;
|
||||
for (int objidx = 0; objidx < parser->getNumObjects(); ++objidx) {
|
||||
ObjectInfo* info=parser->getObjectByIndex(objidx);
|
||||
process_object(info);
|
||||
@ -57,6 +60,9 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template
|
||||
objInc.append("#include \"" + info->namelc + ".h\"\r\n");
|
||||
objFileNames.append(" " + info->namelc);
|
||||
objNames.append(" " + info->name);
|
||||
if (parser->getNumBytes(objidx)>sizeCalc) {
|
||||
sizeCalc = parser->getNumBytes(objidx);
|
||||
}
|
||||
}
|
||||
|
||||
// Write the flight object inialization files
|
||||
@ -65,7 +71,16 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template
|
||||
bool res = writeFileIfDiffrent( flightOutputPath.absolutePath() + "/uavobjectsinit.c",
|
||||
flightInitTemplate );
|
||||
if (!res) {
|
||||
cout << "Error: Could not write flight object init files" << endl;
|
||||
cout << "Error: Could not write flight object init file" << endl;
|
||||
return false;
|
||||
}
|
||||
|
||||
// Write the flight object initialization header
|
||||
flightInitIncludeTemplate.replace( QString("$(SIZECALCULATION)"), QString().setNum(sizeCalc));
|
||||
res = writeFileIfDiffrent( flightOutputPath.absolutePath() + "/uavobjectsinit.h",
|
||||
flightInitIncludeTemplate );
|
||||
if (!res) {
|
||||
cout << "Error: Could not write flight object init header file" << endl;
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -34,7 +34,7 @@ class UAVObjectGeneratorFlight
|
||||
public:
|
||||
bool generate(UAVObjectParser* gen,QString templatepath,QString outputpath);
|
||||
QStringList fieldTypeStrC;
|
||||
QString flightCodeTemplate, flightIncludeTemplate, flightInitTemplate, flightMakeTemplate;
|
||||
QString flightCodeTemplate, flightIncludeTemplate, flightInitTemplate, flightInitIncludeTemplate, flightMakeTemplate;
|
||||
QDir flightCodePath;
|
||||
QDir flightOutputPath;
|
||||
|
||||
|
@ -5,7 +5,7 @@
|
||||
<field name="GyroBias" units="deg/s * 100" type="int16" elementnames="X,Y,Z" defaultvalue="0"/>
|
||||
<field name="BoardRotation" units="deg" type="int16" elementnames="Roll,Pitch,Yaw" defaultvalue="0,0,0"/>
|
||||
<field name="GyroGain" units="(rad/s)/lsb" type="float" elements="1" defaultvalue="0.42"/>
|
||||
<field name="AccelKp" units="channel" type="float" elements="1" defaultvalue="0.03"/>
|
||||
<field name="AccelKp" units="channel" type="float" elements="1" defaultvalue="0.05"/>
|
||||
<field name="AccelKi" units="channel" type="float" elements="1" defaultvalue="0.0001"/>
|
||||
<field name="YawBiasRate" units="channel" type="float" elements="1" defaultvalue="0.000001"/>
|
||||
<field name="ZeroDuringArming" units="channel" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
|
12
shared/uavobjectdefinition/cameradesired.xml
Normal file
12
shared/uavobjectdefinition/cameradesired.xml
Normal file
@ -0,0 +1,12 @@
|
||||
<xml>
|
||||
<object name="CameraDesired" singleinstance="true" settings="false">
|
||||
<description>Desired camera outputs. Comes from @ref CameraStabilization module.</description>
|
||||
<field name="Roll" units="" type="float" elements="1"/>
|
||||
<field name="Pitch" units="" type="float" elements="1"/>
|
||||
<field name="Yaw" units="" type="float" elements="1"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="false" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="false" updatemode="periodic" period="1000"/>
|
||||
<logging updatemode="never" period="0"/>
|
||||
</object>
|
||||
</xml>
|
12
shared/uavobjectdefinition/camerastabsettings.xml
Normal file
12
shared/uavobjectdefinition/camerastabsettings.xml
Normal file
@ -0,0 +1,12 @@
|
||||
<xml>
|
||||
<object name="CameraStabSettings" singleinstance="true" settings="true">
|
||||
<description>Settings for the @ref CameraStab mmodule</description>
|
||||
<field name="Inputs" units="channel" type="enum" elementnames="Roll,Pitch,Yaw" options="Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5,,None" defaultvalue="None"/>
|
||||
<field name="InputRange" units="deg" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="20"/>
|
||||
<field name="OutputRange" units="deg" type="uint8" elementnames="Roll,Pitch,Yaw" defaultvalue="20"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="never" period="0"/>
|
||||
</object>
|
||||
</xml>
|
@ -1,17 +1,21 @@
|
||||
<xml>
|
||||
<object name="HwSettings" singleinstance="true" settings="true">
|
||||
<description>Selection of optional hardware configurations.</description>
|
||||
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,Spektrum1,Spektrum2,ComAux,I2C" defaultvalue="Disabled"/>
|
||||
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,S.Bus,GPS,Spektrum1,Spektrum2,ComAux" defaultvalue="Telemetry"/>
|
||||
<object name="HwSettings" singleinstance="true" settings="true">
|
||||
<description>Selection of optional hardware configurations.</description>
|
||||
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,Spektrum1,Spektrum2,ComAux,I2C" defaultvalue="Disabled"/>
|
||||
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,S.Bus,GPS,Spektrum1,Spektrum2,ComAux" defaultvalue="Telemetry"/>
|
||||
|
||||
<field name="OP_FlexiPort" units="function" type="enum" elements="1" options="Disabled,GPS" defaultvalue="GPS"/>
|
||||
<field name="OP_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry" defaultvalue="Telemetry"/>
|
||||
<field name="OP_AuxPort" units="function" type="enum" elements="1" options="Disabled,Debug,Spektrum1" defaultvalue="Disabled"/>
|
||||
<field name="OP_FlexiPort" units="function" type="enum" elements="1" options="Disabled,GPS" defaultvalue="GPS"/>
|
||||
<field name="OP_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry" defaultvalue="Telemetry"/>
|
||||
<field name="OP_AuxPort" units="function" type="enum" elements="1" options="Disabled,Debug,Spektrum1" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM" defaultvalue="PWM"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="never" period="0"/>
|
||||
<field name="RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM" defaultvalue="PWM"/>
|
||||
|
||||
<field name="OptionalModules" units="" type="enum" elementnames="CameraStabilization,GPS" options="Disabled,Enabled" defaultvalue="Disabled"/>
|
||||
<field name="DSMxBind" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="never" period="0"/>
|
||||
</object>
|
||||
</xml>
|
||||
|
@ -5,24 +5,24 @@
|
||||
<field name="FeedForward" units="" type="float" elements="1" defaultvalue="0"/>
|
||||
<field name="AccelTime" units="ms" type="float" elements="1" defaultvalue="0"/>
|
||||
<field name="DecelTime" units="ms" type="float" elements="1" defaultvalue="0"/>
|
||||
<field name="ThrottleCurve1" units="percent" type="float" elements="5" elementnames="0,25,50,75,100" defaultvalue="0,0,0,0,0"/>
|
||||
<field name="ThrottleCurve1" units="percent" type="float" elements="5" elementnames="0,25,50,75,100" defaultvalue="0,0,0,0,0"/>
|
||||
<field name="Curve2Source" units="" type="enum" elements="1" options="Throttle,Roll,Pitch,Yaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Throttle"/>
|
||||
<field name="ThrottleCurve2" units="percent" type="float" elements="5" elementnames="0,25,50,75,100" defaultvalue="0,0.25,0.5,0.75,1"/>
|
||||
<field name="Mixer1Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer1Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer1Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<field name="Mixer2Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer2Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer2Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<field name="Mixer3Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer3Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer3Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<field name="Mixer4Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer4Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer4Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<field name="Mixer5Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer5Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer5Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<field name="Mixer6Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer6Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer6Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<field name="Mixer7Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer7Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer7Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<field name="Mixer8Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer8Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
|
||||
<field name="Mixer8Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -1,7 +1,7 @@
|
||||
<xml>
|
||||
<object name="ObjectPersistence" singleinstance="true" settings="false">
|
||||
<description>Someone who knows please enter this</description>
|
||||
<field name="Operation" units="" type="enum" elements="1" options="NOP,Load,Save,Delete,Completed"/>
|
||||
<field name="Operation" units="" type="enum" elements="1" options="NOP,Load,Save,Delete,FullErase,Completed"/>
|
||||
<field name="Selection" units="" type="enum" elements="1" options="SingleObject,AllSettings,AllMetaObjects,AllObjects"/>
|
||||
<field name="ObjectID" units="" type="uint32" elements="1"/>
|
||||
<field name="InstanceID" units="" type="uint32" elements="1"/>
|
||||
|
@ -16,7 +16,7 @@
|
||||
|
||||
<field name="GyroTau" units="" type="float" elements="1" defaultvalue="0.005"/>
|
||||
|
||||
<field name="MaxAxisLock" units="deg" type="uint8" elements="1" defaultvalue="5"/>
|
||||
<field name="MaxAxisLock" units="deg" type="uint8" elements="1" defaultvalue="15"/>
|
||||
<field name="MaxAxisLockRate" units="deg/s" type="uint8" elements="1" defaultvalue="2"/>
|
||||
|
||||
<field name="WeakLevelingKp" units="(deg/s)/deg" type="float" elements="1" defaultvalue="0.1"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user