diff --git a/HISTORY.txt b/HISTORY.txt
index ac278b889..b0e1ce8b0 100644
--- a/HISTORY.txt
+++ b/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).
diff --git a/MILESTONES.txt b/MILESTONES.txt
index 776c4a758..14db545d6 100644
--- a/MILESTONES.txt
+++ b/MILESTONES.txt
@@ -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:
diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile
index d437d567d..9485d03d9 100644
--- a/flight/CopterControl/Makefile
+++ b/flight/CopterControl/Makefile
@@ -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
diff --git a/flight/CopterControl/System/alarms.c b/flight/CopterControl/System/alarms.c
index e899be779..01d79a1e5 100644
--- a/flight/CopterControl/System/alarms.c
+++ b/flight/CopterControl/System/alarms.c
@@ -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)
/**
* @}
* @}
- */
+ */
diff --git a/flight/CopterControl/System/coptercontrol.c b/flight/CopterControl/System/coptercontrol.c
index f66cf1cf5..33cb096c2 100644
--- a/flight/CopterControl/System/coptercontrol.c
+++ b/flight/CopterControl/System/coptercontrol.c
@@ -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
-* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
-* 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
+* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
+* 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;
+}
+
+/**
+ * @}
+ * @}
+ */
+
diff --git a/flight/CopterControl/System/inc/FreeRTOSConfig.h b/flight/CopterControl/System/inc/FreeRTOSConfig.h
index 45b0b8902..994956008 100644
--- a/flight/CopterControl/System/inc/FreeRTOSConfig.h
+++ b/flight/CopterControl/System/inc/FreeRTOSConfig.h
@@ -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
/**
diff --git a/flight/CopterControl/System/pios_board.c b/flight/CopterControl/System/pios_board.c
index 59b66ea3a..0fd7a6011 100644
--- a/flight/CopterControl/System/pios_board.c
+++ b/flight/CopterControl/System/pios_board.c
@@ -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);
}
diff --git a/flight/CopterControl/System/pios_board_posix.c b/flight/CopterControl/System/pios_board_posix.c
index 87d8e7402..30f949830 100644
--- a/flight/CopterControl/System/pios_board_posix.c
+++ b/flight/CopterControl/System/pios_board_posix.c
@@ -42,7 +42,6 @@ void PIOS_Board_Init(void) {
/* Initialize UAVObject libraries */
EventDispatcherInitialize();
UAVObjInitialize();
- UAVObjectsInitializeAll();
/* Initialize the alarms library */
AlarmsInitialize();
diff --git a/flight/CopterControl/System/taskmonitor.c b/flight/CopterControl/System/taskmonitor.c
index 8941a616b..6ff6299d0 100644
--- a/flight/CopterControl/System/taskmonitor.c
+++ b/flight/CopterControl/System/taskmonitor.c
@@ -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
}
diff --git a/flight/Libraries/ahrs_comm_objects.c b/flight/Libraries/ahrs_comm_objects.c
index e43c380e4..5fc4f1b20 100644
--- a/flight/Libraries/ahrs_comm_objects.c
+++ b/flight/Libraries/ahrs_comm_objects.c
@@ -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();\
diff --git a/flight/Modules/AHRSComms/ahrs_comms.c b/flight/Modules/AHRSComms/ahrs_comms.c
index 0c98969e3..c3fb45fae 100644
--- a/flight/Modules/AHRSComms/ahrs_comms.c
+++ b/flight/Modules/AHRSComms/ahrs_comms.c
@@ -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;
}
diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c
index 269b9dda6..6b353d20f 100644
--- a/flight/Modules/Actuator/actuator.c
+++ b/flight/Modules/Actuator/actuator.c
@@ -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
diff --git a/flight/Modules/Altitude/altitude.c b/flight/Modules/Altitude/altitude.c
index 363cba15f..d1655aaa8 100644
--- a/flight/Modules/Altitude/altitude.c
+++ b/flight/Modules/Altitude/altitude.c
@@ -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);
diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c
index c70751fa6..b7b535f18 100644
--- a/flight/Modules/Attitude/attitude.c
+++ b/flight/Modules/Attitude/attitude.c
@@ -112,6 +112,10 @@ int32_t AttitudeStart(void)
*/
int32_t AttitudeInitialize(void)
{
+ AttitudeActualInitialize();
+ AttitudeRawInitialize();
+ AttitudeSettingsInitialize();
+
// Initialize quaternion
AttitudeActualData attitude;
AttitudeActualGet(&attitude);
diff --git a/flight/Modules/Battery/battery.c b/flight/Modules/Battery/battery.c
index fe36745bb..a57efd69a 100644
--- a/flight/Modules/Battery/battery.c
+++ b/flight/Modules/Battery/battery.c
@@ -79,6 +79,9 @@ MODULE_INITCALL(BatteryInitialize, 0)
int32_t BatteryInitialize(void)
{
+ BatteryStateInitialze();
+ BatterySettingsInitialize();
+
static UAVObjEvent ev;
memset(&ev,0,sizeof(UAVObjEvent));
diff --git a/flight/Modules/CameraStab/camerastab.c b/flight/Modules/CameraStab/camerastab.c
new file mode 100644
index 000000000..2e21b8e92
--- /dev/null
+++ b/flight/Modules/CameraStab/camerastab.c
@@ -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;
+}
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
diff --git a/flight/UAVObjects/uavobjectsinit_linker.c b/flight/Modules/CameraStab/inc/camerastab.h
similarity index 62%
rename from flight/UAVObjects/uavobjectsinit_linker.c
rename to flight/Modules/CameraStab/inc/camerastab.h
index 3d4abd7eb..5d7bf9d06 100644
--- a/flight/UAVObjects/uavobjectsinit_linker.c
+++ b/flight/Modules/CameraStab/inc/camerastab.h
@@ -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
+
+/**
+ * @}
+ * @}
+ */
diff --git a/flight/Modules/FirmwareIAP/firmwareiap.c b/flight/Modules/FirmwareIAP/firmwareiap.c
index e3372019c..21678397e 100644
--- a/flight/Modules/FirmwareIAP/firmwareiap.c
+++ b/flight/Modules/FirmwareIAP/firmwareiap.c
@@ -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;
diff --git a/flight/Modules/FlightPlan/flightplan.c b/flight/Modules/FlightPlan/flightplan.c
index 5537c8f15..e919dd41e 100644
--- a/flight/Modules/FlightPlan/flightplan.c
+++ b/flight/Modules/FlightPlan/flightplan.c
@@ -74,7 +74,11 @@ int32_t FlightPlanStart()
int32_t FlightPlanInitialize()
{
taskHandle = NULL;
-
+
+ FlightPlanStatusInitialize();
+ FlightPlanControlInitialize();
+ FlightPlanSettingsInitialize();
+
// Listen for object updates
FlightPlanControlConnectCallback(&objectUpdatedCb);
diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c
index dd0905257..d2ab2b3c5 100644
--- a/flight/Modules/GPS/GPS.c
+++ b/flight/Modules/GPS/GPS.c
@@ -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);
}
}
diff --git a/flight/Modules/Guidance/guidance.c b/flight/Modules/Guidance/guidance.c
index 348210675..b90303928 100644
--- a/flight/Modules/Guidance/guidance.c
+++ b/flight/Modules/Guidance/guidance.c
@@ -97,6 +97,12 @@ int32_t GuidanceStart()
*/
int32_t GuidanceInitialize()
{
+
+ GuidanceSettingsInitialize();
+ PositionDesiredInitialize();
+ NedAccelInitialize();
+ VelocityDesiredInitialize();
+
// Create object queue
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c
index 153738dc1..3cc215de9 100644
--- a/flight/Modules/ManualControl/manualcontrol.c
+++ b/flight/Modules/ManualControl/manualcontrol.c
@@ -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)
* @}
* @}
*/
-
diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c
index 9d3a538d0..7142c9770 100644
--- a/flight/Modules/Stabilization/stabilization.c
+++ b/flight/Modules/Stabilization/stabilization.c
@@ -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++)
diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c
index f555d227f..168b46aa6 100644
--- a/flight/Modules/System/systemmod.c
+++ b/flight/Modules/System/systemmod.c
@@ -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
}
/**
diff --git a/flight/Modules/Telemetry/telemetry.c b/flight/Modules/Telemetry/telemetry.c
index 06581fe1a..25abf2c3a 100644
--- a/flight/Modules/Telemetry/telemetry.c
+++ b/flight/Modules/Telemetry/telemetry.c
@@ -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);
diff --git a/flight/OpenPilot/Makefile b/flight/OpenPilot/Makefile
index 60f9d6d30..7d3cdf514 100644
--- a/flight/OpenPilot/Makefile
+++ b/flight/OpenPilot/Makefile
@@ -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)
diff --git a/flight/OpenPilot/System/alarms.c b/flight/OpenPilot/System/alarms.c
index e899be779..e61c7c1ea 100644
--- a/flight/OpenPilot/System/alarms.c
+++ b/flight/OpenPilot/System/alarms.c
@@ -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)
/**
* @}
* @}
- */
+ */
diff --git a/flight/OpenPilot/System/inc/FreeRTOSConfig.h b/flight/OpenPilot/System/inc/FreeRTOSConfig.h
index 75a14ea13..4b37f7e44 100644
--- a/flight/OpenPilot/System/inc/FreeRTOSConfig.h
+++ b/flight/OpenPilot/System/inc/FreeRTOSConfig.h
@@ -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)
diff --git a/flight/OpenPilot/System/inc/pios_config.h b/flight/OpenPilot/System/inc/pios_config.h
index 4d561382e..4e6657cef 100644
--- a/flight/OpenPilot/System/inc/pios_config.h
+++ b/flight/OpenPilot/System/inc/pios_config.h
@@ -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
diff --git a/flight/OpenPilot/System/inc/pios_config_posix.h b/flight/OpenPilot/System/inc/pios_config_posix.h
index 4b779cc49..e8701be90 100644
--- a/flight/OpenPilot/System/inc/pios_config_posix.h
+++ b/flight/OpenPilot/System/inc/pios_config_posix.h
@@ -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
diff --git a/flight/OpenPilot/System/pios_board.c b/flight/OpenPilot/System/pios_board.c
index 9a9397acb..2905c500c 100644
--- a/flight/OpenPilot/System/pios_board.c
+++ b/flight/OpenPilot/System/pios_board.c
@@ -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;
diff --git a/flight/OpenPilot/System/pios_board_posix.c b/flight/OpenPilot/System/pios_board_posix.c
index 2480d0730..e1e8dcc54 100644
--- a/flight/OpenPilot/System/pios_board_posix.c
+++ b/flight/OpenPilot/System/pios_board_posix.c
@@ -29,6 +29,11 @@
#include
#include
+#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();
}
diff --git a/flight/OpenPilot/System/taskmonitor.c b/flight/OpenPilot/System/taskmonitor.c
index d7fa3fde4..dcd08945c 100644
--- a/flight/OpenPilot/System/taskmonitor.c
+++ b/flight/OpenPilot/System/taskmonitor.c
@@ -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
}
diff --git a/flight/OpenPilot/UAVObjects.inc b/flight/OpenPilot/UAVObjects.inc
index 3bb868a7d..1b110e0e9 100644
--- a/flight/OpenPilot/UAVObjects.inc
+++ b/flight/OpenPilot/UAVObjects.inc
@@ -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) )
diff --git a/flight/PiOS.posix/inc/pios_initcall.h b/flight/PiOS.posix/inc/pios_initcall.h
index deb6e0eb6..f88081c33 100644
--- a/flight/PiOS.posix/inc/pios_initcall.h
+++ b/flight/PiOS.posix/inc/pios_initcall.h
@@ -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 { \
diff --git a/flight/PiOS.posix/posix/pios_debug.c b/flight/PiOS.posix/posix/pios_debug.c
index f79f2e730..5956a9d04 100644
--- a/flight/PiOS.posix/posix/pios_debug.c
+++ b/flight/PiOS.posix/posix/pios_debug.c
@@ -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;
+
}
/**
diff --git a/flight/PiOS.posix/posix/pios_udp.c b/flight/PiOS.posix/posix/pios_udp.c
index 39077b455..f7f91f620 100644
--- a/flight/PiOS.posix/posix/pios_udp.c
+++ b/flight/PiOS.posix/posix/pios_udp.c
@@ -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;
}
diff --git a/flight/PiOS.win32/inc/pios_initcall.h b/flight/PiOS.win32/inc/pios_initcall.h
index f370f27ee..edd9ddc08 100644
--- a/flight/PiOS.win32/inc/pios_initcall.h
+++ b/flight/PiOS.win32/inc/pios_initcall.h
@@ -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
diff --git a/flight/PiOS/Common/pios_flashfs_objlist.c b/flight/PiOS/Common/pios_flashfs_objlist.c
index 08fe640c9..2b2fe06fa 100644
--- a/flight/PiOS/Common/pios_flashfs_objlist.c
+++ b/flight/PiOS/Common/pios_flashfs_objlist.c
@@ -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
diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld
index f818fff42..777e09aa6 100644
--- a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld
+++ b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld
@@ -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.*)
diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld
index d2c4abb17..57530d320 100644
--- a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld
+++ b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld
@@ -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 :
{
diff --git a/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld
index 1b3c11e34..3420c385e 100644
--- a/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld
+++ b/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld
@@ -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 :
{
diff --git a/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld
index ef25c9344..bcf498dd0 100644
--- a/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld
+++ b/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld
@@ -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 :
diff --git a/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld
index 7716ccbf2..9cd7c8b4b 100644
--- a/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld
+++ b/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld
@@ -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 :
{
diff --git a/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld
index 87a65d7c1..5d504bfdd 100644
--- a/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld
+++ b/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld
@@ -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 :
diff --git a/flight/PiOS/STM32F10x/pios_spektrum.c b/flight/PiOS/STM32F10x/pios_spektrum.c
index e062e6314..dab724ef8 100644
--- a/flight/PiOS/STM32F10x/pios_spektrum.c
+++ b/flight/PiOS/STM32F10x/pios_spektrum.c
@@ -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++) {
diff --git a/flight/PiOS/inc/pios_flashfs_objlist.h b/flight/PiOS/inc/pios_flashfs_objlist.h
index 945df4068..f5c22d973 100644
--- a/flight/PiOS/inc/pios_flashfs_objlist.h
+++ b/flight/PiOS/inc/pios_flashfs_objlist.h
@@ -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);
\ No newline at end of file
+int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId);
diff --git a/flight/PiOS/inc/pios_initcall.h b/flight/PiOS/inc/pios_initcall.h
index 68b9ef077..e242989c0 100644
--- a/flight/PiOS/inc/pios_initcall.h
+++ b/flight/PiOS/inc/pios_initcall.h
@@ -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++) \
diff --git a/flight/PiOS/inc/pios_spektrum_priv.h b/flight/PiOS/inc/pios_spektrum_priv.h
index eb82c4f44..17b330cae 100644
--- a/flight/PiOS/inc/pios_spektrum_priv.h
+++ b/flight/PiOS/inc/pios_spektrum_priv.h
@@ -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 */
diff --git a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj
index 3a0fc1dfa..ceca7eafb 100644
--- a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj
+++ b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj
@@ -85,6 +85,7 @@
6549E0D21279B3C800C5476F /* fifo_buffer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = fifo_buffer.c; sourceTree = ""; };
6549E0D31279B3CF00C5476F /* fifo_buffer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fifo_buffer.h; sourceTree = ""; };
655268BC121FBD2900410C6E /* ahrscalibration.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrscalibration.xml; sourceTree = ""; };
+ 655B1A8E13B2FC0900B0E48D /* camerastabsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = camerastabsettings.xml; sourceTree = ""; };
656268C612DC1923007B0A0F /* nedaccel.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = nedaccel.xml; sourceTree = ""; };
6562BE1713CCAD0600C823E8 /* pios_rcvr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rcvr.c; sourceTree = ""; };
65632DF51251650300469B77 /* pios_board.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_board.h; sourceTree = ""; };
@@ -2680,7 +2681,6 @@
65C35E7912EFB2F3004811C2 /* watchdogstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = watchdogstatus.xml; sourceTree = ""; };
65C35E9E12F0A834004811C2 /* uavobjecttemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjecttemplate.c; sourceTree = ""; };
65C35E9F12F0A834004811C2 /* uavobjectsinittemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectsinittemplate.c; sourceTree = ""; };
- 65C35EA012F0A834004811C2 /* uavobjectsinit_cc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectsinit_cc.c; sourceTree = ""; };
65C35EA112F0A834004811C2 /* uavobjectmanager.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectmanager.c; sourceTree = ""; };
65C35EA312F0A834004811C2 /* eventdispatcher.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = eventdispatcher.h; sourceTree = ""; };
65C35EA412F0A834004811C2 /* uavobjectmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectmanager.h; sourceTree = ""; };
@@ -2690,9 +2690,13 @@
65C35EA812F0A834004811C2 /* eventdispatcher.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = eventdispatcher.c; sourceTree = ""; };
65C35F6612F0DC2D004811C2 /* attitude.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = attitude.c; sourceTree = ""; };
65C35F6812F0DC2D004811C2 /* attitude.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = attitude.h; sourceTree = ""; };
+ 65C9903C13A871B90082BD60 /* camerastab.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = camerastab.c; sourceTree = ""; };
+ 65C9903E13A871B90082BD60 /* camerastab.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = camerastab.h; sourceTree = ""; };
65D2CA841248F9A400B1E7D6 /* mixersettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixersettings.xml; sourceTree = ""; };
65D2CA851248F9A400B1E7D6 /* mixerstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixerstatus.xml; sourceTree = ""; };
+ 65DEA79113F2143B00095B06 /* cameradesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = cameradesired.xml; sourceTree = ""; };
65E410AE12F65AEA00725888 /* attitudesettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitudesettings.xml; sourceTree = ""; };
+ 65E6D80713E3A4D0002A557A /* hwsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = hwsettings.xml; sourceTree = ""; };
65E6DF7112E02E8E00058553 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; };
65E6DF7312E02E8E00058553 /* alarms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = alarms.c; sourceTree = ""; };
65E6DF7412E02E8E00058553 /* coptercontrol.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = coptercontrol.c; sourceTree = ""; };
@@ -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 = "";
@@ -7501,6 +7508,23 @@
path = inc;
sourceTree = "";
};
+ 65C9903B13A871B90082BD60 /* CameraStab */ = {
+ isa = PBXGroup;
+ children = (
+ 65C9903C13A871B90082BD60 /* camerastab.c */,
+ 65C9903D13A871B90082BD60 /* inc */,
+ );
+ path = CameraStab;
+ sourceTree = "";
+ };
+ 65C9903D13A871B90082BD60 /* inc */ = {
+ isa = PBXGroup;
+ children = (
+ 65C9903E13A871B90082BD60 /* camerastab.h */,
+ );
+ path = inc;
+ sourceTree = "";
+ };
65E6DF7012E02E8E00058553 /* CopterControl */ = {
isa = PBXGroup;
children = (
diff --git a/flight/UAVObjects/inc/uavobjectsinit.h b/flight/UAVObjects/inc/uavobjectsinittemplate.h
similarity index 93%
rename from flight/UAVObjects/inc/uavobjectsinit.h
rename to flight/UAVObjects/inc/uavobjectsinittemplate.h
index ec946ba92..ec11c47ad 100644
--- a/flight/UAVObjects/inc/uavobjectsinit.h
+++ b/flight/UAVObjects/inc/uavobjectsinittemplate.h
@@ -29,4 +29,6 @@
void UAVObjectsInitializeAll();
+#define UAVOBJECTS_LARGEST $(SIZECALCULATION)
+
#endif // UAVOBJECTSINIT_H
diff --git a/flight/UAVObjects/uavobjectsinittemplate.c b/flight/UAVObjects/uavobjectsinittemplate.c
index 75a104d18..97a1525a4 100644
--- a/flight/UAVObjects/uavobjectsinittemplate.c
+++ b/flight/UAVObjects/uavobjectsinittemplate.c
@@ -36,5 +36,7 @@ $(OBJINC)
*/
void UAVObjectsInitializeAll()
{
+return;
+// This function is no longer used anyway
$(OBJINIT)
}
diff --git a/flight/UAVObjects/uavobjecttemplate.c b/flight/UAVObjects/uavobjecttemplate.c
index 9dd45b09f..6d572dbcb 100644
--- a/flight/UAVObjects/uavobjecttemplate.c
+++ b/flight/UAVObjects/uavobjecttemplate.c
@@ -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
diff --git a/flight/UAVTalk/inc/uavtalk.h b/flight/UAVTalk/inc/uavtalk.h
index 7a257620d..71114ce74 100644
--- a/flight/UAVTalk/inc/uavtalk.h
+++ b/flight/UAVTalk/inc/uavtalk.h
@@ -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
/**
diff --git a/flight/UAVTalk/inc/uavtalk_priv.h b/flight/UAVTalk/inc/uavtalk_priv.h
new file mode 100644
index 000000000..06f08b997
--- /dev/null
+++ b/flight/UAVTalk/inc/uavtalk_priv.h
@@ -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
+/**
+ * @}
+ * @}
+ */
diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c
index 48ad03f53..236915b28 100644
--- a/flight/UAVTalk/uavtalk.c
+++ b/flight/UAVTalk/uavtalk.c
@@ -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;
diff --git a/ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp
new file mode 100644
index 000000000..2edef8ddf
--- /dev/null
+++ b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp
@@ -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
+#include
+
+#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::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();
+}
diff --git a/ground/openpilotgcs/src/libs/utils/cachedsvgitem.h b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.h
new file mode 100644
index 000000000..747ef391c
--- /dev/null
+++ b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.h
@@ -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
+#include
+
+#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
diff --git a/ground/openpilotgcs/src/libs/utils/utils.pro b/ground/openpilotgcs/src/libs/utils/utils.pro
index 804f7c813..003497b4d 100644
--- a/ground/openpilotgcs/src/libs/utils/utils.pro
+++ b/ground/openpilotgcs/src/libs/utils/utils.pro
@@ -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 \
diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui
new file mode 100644
index 000000000..28e7740c1
--- /dev/null
+++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui
@@ -0,0 +1,441 @@
+
+
+ CameraStabilizationWidget
+
+
+
+ 0
+ 0
+ 720
+ 567
+
+
+
+ Form
+
+
+ -
+
+
+ Enable CameraStabilization module
+
+
+
+ -
+
+
+ After enabling the module, you must power cycle before using and configuring.
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ Channel Ranges (number of degrees full range)
+
+
+
-
+
+
-
+
+
+ Pitch
+
+
+
+ -
+
+
+ Yaw
+
+
+
+ -
+
+
+ Roll
+
+
+
+ -
+
+
+ 180
+
+
+
+ -
+
+
+ 180
+
+
+
+ -
+
+
+ 180
+
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 212
+ 20
+
+
+
+
+
+
+
+ -
+
+
+ Channel Mapping (select output channel or none to disable)
+
+
+
-
+
+
-
+
+
+ Roll
+
+
+
+ -
+
+
-
+
+ None
+
+
+ -
+
+ Channel 1
+
+
+ -
+
+ Channel 2
+
+
+ -
+
+ Channel 3
+
+
+ -
+
+ Channel 4
+
+
+ -
+
+ Channel 5
+
+
+ -
+
+ Channel 6
+
+
+ -
+
+ Channel 7
+
+
+ -
+
+ Channel 8
+
+
+
+
+ -
+
+
-
+
+ None
+
+
+ -
+
+ Channel 1
+
+
+ -
+
+ Channel 2
+
+
+ -
+
+ Channel 3
+
+
+ -
+
+ Channel 4
+
+
+ -
+
+ Channel 5
+
+
+ -
+
+ Channel 6
+
+
+ -
+
+ Channel 7
+
+
+ -
+
+ Channel 8
+
+
+
+
+ -
+
+
+ Pitch
+
+
+
+ -
+
+
-
+
+ None
+
+
+ -
+
+ Channel 1
+
+
+ -
+
+ Channel 2
+
+
+ -
+
+ Channel 3
+
+
+ -
+
+ Channel 4
+
+
+ -
+
+ Channel 5
+
+
+ -
+
+ Channel 6
+
+
+ -
+
+ Channel 7
+
+
+ -
+
+ Channel 8
+
+
+
+
+ -
+
+
+ Yaw
+
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 212
+ 20
+
+
+
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+ -
+
+
-
+
+
+ QFrame::StyledPanel
+
+
+ QFrame::Raised
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+
+ 32
+ 32
+
+
+
+
+ true
+
+
+
+
+
+
+
+ :/core/images/helpicon.svg:/core/images/helpicon.svg
+
+
+
+ 32
+ 32
+
+
+
+ Ctrl+S
+
+
+ false
+
+
+ true
+
+
+
+ -
+
+
+ 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.
+
+
+ Apply
+
+
+
+ -
+
+
+ Send settings to the board, and save to the non-volatile memory.
+
+
+ Save
+
+
+ false
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/ground/openpilotgcs/src/plugins/config/config.pro b/ground/openpilotgcs/src/plugins/config/config.pro
index 62bdc327e..29d872ec9 100644
--- a/ground/openpilotgcs/src/plugins/config/config.pro
+++ b/ground/openpilotgcs/src/plugins/config/config.pro
@@ -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
+
+
+
+
diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp
new file mode 100644
index 000000000..afbdae760
--- /dev/null
+++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp
@@ -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
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#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);
+}
+
+/**
+ @}
+ @}
+ */
diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h
new file mode 100644
index 000000000..f5440e360
--- /dev/null
+++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h
@@ -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
+#include
+#include
+#include
+#include
+#include
+
+#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
diff --git a/ground/openpilotgcs/src/plugins/config/configgadget.qrc b/ground/openpilotgcs/src/plugins/config/configgadget.qrc
index e157ee0ca..f24cb68b8 100644
--- a/ground/openpilotgcs/src/plugins/config/configgadget.qrc
+++ b/ground/openpilotgcs/src/plugins/config/configgadget.qrc
@@ -16,5 +16,6 @@
images/hw_config.png
images/gyroscope.png
images/TX.svg
+ images/camera.png
diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp
index af8368c1f..a8509d091 100644
--- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp
+++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp
@@ -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);
diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h
index 356d11a74..633253507 100644
--- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h
+++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h
@@ -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();
diff --git a/ground/openpilotgcs/src/plugins/config/configplugin.cpp b/ground/openpilotgcs/src/plugins/config/configplugin.cpp
index dced1c231..622b3db9b 100644
--- a/ground/openpilotgcs/src/plugins/config/configplugin.cpp
+++ b/ground/openpilotgcs/src/plugins/config/configplugin.cpp
@@ -30,7 +30,7 @@
#include
#include
#include
-
+#include "objectpersistence.h"
ConfigPlugin::ConfigPlugin()
{
@@ -58,7 +58,7 @@ bool ConfigPlugin::initialize(const QStringList& args, QString *errMsg)
"ConfigPlugin.EraseAll",
QList() <<
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();
+ 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();
- Q_ASSERT(objMngr);
- ObjectPersistence* objper = dynamic_cast( 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();
- Q_ASSERT(objMngr);
- ObjectPersistence* objper = dynamic_cast( 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(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);
diff --git a/ground/openpilotgcs/src/plugins/config/configplugin.h b/ground/openpilotgcs/src/plugins/config/configplugin.h
index f4fa677de..7091ad460 100644
--- a/ground/openpilotgcs/src/plugins/config/configplugin.h
+++ b/ground/openpilotgcs/src/plugins/config/configplugin.h
@@ -48,6 +48,7 @@ public:
ConfigPlugin();
~ConfigPlugin();
+ UAVObjectManager * getObjectManager();
void extensionsInitialized();
bool initialize(const QStringList & arguments, QString * errorString);
void shutdown();
diff --git a/ground/openpilotgcs/src/plugins/config/images/camera.png b/ground/openpilotgcs/src/plugins/config/images/camera.png
new file mode 100644
index 000000000..50ee47904
Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/camera.png differ
diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui
index 96c414055..799c50880 100644
--- a/ground/openpilotgcs/src/plugins/config/stabilization.ui
+++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui
@@ -6,649 +6,689 @@
0
0
- 639
- 611
+ 683
+ 685
Form
-
+
-
-
+
-
+
0
- 0
+ 1
-
-
- 0
- 150
-
+
+ QFrame::NoFrame
-
- Rate Stabilization Coefficients (Inner Loop)
+
+ true
-
-
-
-
-
- Kp
-
-
- Qt::AlignCenter
-
-
-
- -
-
-
- Ki
-
-
- Qt::AlignCenter
-
-
-
- -
-
-
- ILimit
-
-
- Qt::AlignCenter
-
-
-
- -
-
-
- Roll
-
-
-
- -
-
-
- Slowly raise Kp until you start seeing clear oscillations when you fly.
+
+
+
+ 0
+ 0
+ 665
+ 627
+
+
+
+
+ 0
+ 0
+
+
+
+
+ 0
+
+
+ 0
+
+
-
+
+
+
+ 0
+ 0
+
+
+
+
+ 0
+ 150
+
+
+
+ Rate Stabilization Coefficients (Inner Loop)
+
+
+
-
+
+
+ Kp
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ Ki
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ ILimit
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ Roll
+
+
+
+ -
+
+
+ Slowly raise Kp until you start seeing clear oscillations when you fly.
Then lower the value by 20% or so.
-
-
- 6
-
-
- 0.000100000000000
-
-
-
- -
-
-
- I factor for rate stabilization is usually very low or even zero.
-
-
- 6
-
-
- 0.000100000000000
-
-
-
- -
-
-
- 6
-
-
- 0.000100000000000
-
-
-
- -
-
-
- If checked, the Roll and Pitch factors will be identical.
+
+
+ 6
+
+
+ 0.000100000000000
+
+
+
+ -
+
+
+ I factor for rate stabilization is usually very low or even zero.
+
+
+ 6
+
+
+ 0.000100000000000
+
+
+
+ -
+
+
+ 6
+
+
+ 0.000100000000000
+
+
+
+ -
+
+
+ If checked, the Roll and Pitch factors will be identical.
When you change one, the other is updated.
-
-
- Link
-
-
-
- -
-
-
- Pitch
-
-
-
- -
-
-
- Slowly raise Kp until you start seeing clear oscillations when you fly.
+
+
+ Link
+
+
+
+ -
+
+
+ Pitch
+
+
+
+ -
+
+
+ Slowly raise Kp until you start seeing clear oscillations when you fly.
Then lower the value by 20% or so.
-
-
- 6
-
-
- 0.000100000000000
-
-
-
- -
-
-
- I factor for rate stabilization is usually very low or even zero.
-
-
- 6
-
-
- 0.000100000000000
-
-
-
- -
-
-
- 6
-
-
- 0.000100000000000
-
-
-
- -
-
-
- Yaw
-
-
-
- -
-
-
- Slowly raise Kp until you start seeing clear oscillations when you fly.
+
+
+ 6
+
+
+ 0.000100000000000
+
+
+
+ -
+
+
+ I factor for rate stabilization is usually very low or even zero.
+
+
+ 6
+
+
+ 0.000100000000000
+
+
+
+ -
+
+
+ 6
+
+
+ 0.000100000000000
+
+
+
+ -
+
+
+ Yaw
+
+
+
+ -
+
+
+ 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.
-
-
- 6
-
-
- 0.000100000000000
-
-
-
- -
-
-
- As a rule of thumb, you can set YawRate Ki at roughly the same
+
+
+ 6
+
+
+ 0.000100000000000
+
+
+
+ -
+
+
+ As a rule of thumb, you can set YawRate Ki at roughly the same
value as YawRate Kp.
-
-
- 6
-
-
- 0.000100000000000
-
-
-
- -
-
-
- 6
-
-
- 0.000100000000000
-
-
-
-
-
-
- -
-
-
- Qt::Vertical
-
-
- QSizePolicy::Fixed
-
-
-
- 20
- 5
-
-
-
-
- -
-
-
-
- 0
- 0
-
-
-
-
- 0
- 150
-
-
-
- Attitude Stabization Coefficients (Outer Loop)
-
-
-
-
-
-
- Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
+
+
+ 6
+
+
+ 0.000100000000000
+
+
+
+ -
+
+
+ 6
+
+
+ 0.000100000000000
+
+
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+ QSizePolicy::Fixed
+
+
+
+ 20
+ 13
+
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+
+ 0
+ 150
+
+
+
+ Attitude Stabization Coefficients (Outer Loop)
+
+
+
-
+
+
+ Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
-
-
- 6
-
-
- 0.100000000000000
-
-
-
- -
-
-
- Ki can usually be almost identical to Kp.
-
-
- 6
-
-
- 0.100000000000000
-
-
-
- -
-
-
- ILimit can be equal to three to four times Ki, but you can adjust
+
+
+ 6
+
+
+ 0.100000000000000
+
+
+
+ -
+
+
+ Ki can usually be almost identical to Kp.
+
+
+ 6
+
+
+ 0.100000000000000
+
+
+
+ -
+
+
+ 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.
-
-
- 6
-
-
- 0.100000000000000
-
-
-
- -
-
-
- Kp
-
-
- Qt::AlignCenter
-
-
-
- -
-
-
- Ki
-
-
- Qt::AlignCenter
-
-
-
- -
-
-
- ILimit
-
-
- Qt::AlignCenter
-
-
-
- -
-
-
- ILimit can be equal to three to four times Ki, but you can adjust
+
+
+ 6
+
+
+ 0.100000000000000
+
+
+
+ -
+
+
+ Kp
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ Ki
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ ILimit
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ 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.
-
-
- 6
-
-
- 0.100000000000000
-
-
-
- -
-
-
- Ki can usually be almost identical to Kp.
-
-
- 6
-
-
- 0.100000000000000
-
-
-
- -
-
-
- Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
+
+
+ 6
+
+
+ 0.100000000000000
+
+
+
+ -
+
+
+ Ki can usually be almost identical to Kp.
+
+
+ 6
+
+
+ 0.100000000000000
+
+
+
+ -
+
+
+ Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
-
-
- 6
-
-
- 0.100000000000000
-
-
-
- -
-
-
- Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
+
+
+ 6
+
+
+ 0.100000000000000
+
+
+
+ -
+
+
+ Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so.
-
-
- 6
-
-
- 0.100000000000000
-
-
-
- -
-
-
- Yaw
-
-
-
- -
-
-
- Pitch
-
-
-
- -
-
-
- Roll
-
-
-
- -
-
-
- Ki can usually be almost identical to Kp.
-
-
- 6
-
-
- 0.100000000000000
-
-
-
- -
-
-
- ILimit can be equal to three to four times Ki, but you can adjust
+
+
+ 6
+
+
+ 0.100000000000000
+
+
+
+ -
+
+
+ Yaw
+
+
+
+ -
+
+
+ Pitch
+
+
+
+ -
+
+
+ Roll
+
+
+
+ -
+
+
+ Ki can usually be almost identical to Kp.
+
+
+ 6
+
+
+ 0.100000000000000
+
+
+
+ -
+
+
+ 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.
-
-
- 6
-
-
- 0.100000000000000
-
-
-
- -
-
-
- If checked, the Roll and Pitch factors will be identical.
+
+
+ 6
+
+
+ 0.100000000000000
+
+
+
+ -
+
+
+ If checked, the Roll and Pitch factors will be identical.
When you change one, the other is updated.
-
-
- Link
-
-
-
-
+
+
+ Link
+
+
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+ QSizePolicy::Fixed
+
+
+
+ 20
+ 13
+
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+
+ 0
+ 0
+
+
+
+ Stick range and limits
+
+
+
+ QLayout::SetMinAndMaxSize
+
+
-
+
+
+ Roll
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ Pitch
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ Yaw
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ 180
+
+
+
+ -
+
+
+ 180
+
+
+
+ -
+
+
+ 180
+
+
+
+ -
+
+
+
+ 150
+ 0
+
+
+
+
+ 50
+ false
+
+
+
+ Full stick angle (deg)
+
+
+
+ -
+
+
+
+ 150
+ 0
+
+
+
+
+ 50
+ false
+
+
+
+ Full stick rate (deg/s)
+
+
+
+ -
+
+
+ 300
+
+
+
+ -
+
+
+ 300
+
+
+
+ -
+
+
+ 300
+
+
+
+ -
+
+
+
+ 150
+ 0
+
+
+
+
+ 50
+ false
+
+
+
+
+
+
+ Maximum rate in attitude mode (deg/s)
+
+
+
+ -
+
+
+ 300
+
+
+
+ -
+
+
+ 300
+
+
+
+ -
+
+
+ 300
+
+
+
+
+
+
+ -
+
+
+ Zero the integral when throttle is low
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 0
+
+
+
+
+
+
- -
-
-
- Qt::Vertical
-
-
- QSizePolicy::Fixed
-
-
-
- 20
- 5
-
-
-
-
- -
-
-
-
- 0
- 0
-
-
-
-
- 0
- 0
-
-
-
- Stick range and limits
-
-
-
- QLayout::SetMinAndMaxSize
-
-
-
-
-
- Roll
-
-
- Qt::AlignCenter
-
-
-
- -
-
-
- Pitch
-
-
- Qt::AlignCenter
-
-
-
- -
-
-
- Yaw
-
-
- Qt::AlignCenter
-
-
-
- -
-
-
- 180
-
-
-
- -
-
-
- 180
-
-
-
- -
-
-
- 180
-
-
-
- -
-
-
-
- 150
- 0
-
-
-
-
- 50
- false
-
-
-
- Full stick angle (deg)
-
-
-
- -
-
-
-
- 150
- 0
-
-
-
-
- 50
- false
-
-
-
- Full stick rate (deg/s)
-
-
-
- -
-
-
- 300
-
-
-
- -
-
-
- 300
-
-
-
- -
-
-
- 300
-
-
-
- -
-
-
-
- 150
- 0
-
-
-
-
- 50
- false
-
-
-
-
-
-
- Maximum rate in attitude mode (deg/s)
-
-
-
- -
-
-
- 300
-
-
-
- -
-
-
- 300
-
-
-
- -
-
-
- 300
-
-
-
-
-
-
- -
-
-
- Zero the integral when throttle is low
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 40
-
-
-
-
-
-
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp
index a2b8137f4..1849b4e8b 100644
--- a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp
+++ b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp
@@ -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
diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp
index 079a206b5..a38e943a3 100644
--- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp
+++ b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp
@@ -27,6 +27,7 @@
#include "pfdgadgetwidget.h"
#include
+#include
#include
#include
#include
@@ -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;
diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro
index f5e17d3ca..63eefa5bf 100644
--- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro
+++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro
@@ -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
diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp
index 28fe4f18f..6ef7850e0 100644
--- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp
+++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.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;
diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.ui b/ground/openpilotgcs/src/plugins/uploader/devicewidget.ui
index 6f7ed132f..c5c7a807e 100644
--- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.ui
+++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.ui
@@ -93,10 +93,10 @@
-
- Loads the firmware
+ Open a file with new firmware image to be flashed
- Load...
+ Open...
@@ -116,7 +116,7 @@
false
- Update the firmware on this board.
+ Write loaded firmware image to the board
Flash
@@ -126,7 +126,7 @@
-
- Download the current board firmware to your computer
+ Read and save current board firmware to a file
Retrieve...
@@ -228,7 +228,7 @@
-
- GIT Tag:
+ Git tag:
Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter
diff --git a/ground/openpilotgcs/src/plugins/uploader/images/error.svg b/ground/openpilotgcs/src/plugins/uploader/images/error.svg
new file mode 100644
index 000000000..8de454769
--- /dev/null
+++ b/ground/openpilotgcs/src/plugins/uploader/images/error.svg
@@ -0,0 +1,35 @@
+
+
+
diff --git a/ground/openpilotgcs/src/plugins/uploader/images/warning.svg b/ground/openpilotgcs/src/plugins/uploader/images/warning.svg
index 8de454769..697b80a56 100644
--- a/ground/openpilotgcs/src/plugins/uploader/images/warning.svg
+++ b/ground/openpilotgcs/src/plugins/uploader/images/warning.svg
@@ -1,35 +1,290 @@
-
diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp
index 0db22efb0..2cb513344 100644
--- a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp
+++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp
@@ -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);
diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.qrc b/ground/openpilotgcs/src/plugins/uploader/uploader.qrc
index f51ea265c..7d2677927 100644
--- a/ground/openpilotgcs/src/plugins/uploader/uploader.qrc
+++ b/ground/openpilotgcs/src/plugins/uploader/uploader.qrc
@@ -11,5 +11,6 @@
images/deviceID-0101.svg
images/application-certificate.svg
images/warning.svg
+ images/error.svg
diff --git a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp
index 8d3a30b30..3d9fd12b6 100644
--- a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp
+++ b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp
@@ -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;
}
diff --git a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h
index 1050b2943..db728374b 100644
--- a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h
+++ b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h
@@ -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;
diff --git a/shared/uavobjectdefinition/attitudesettings.xml b/shared/uavobjectdefinition/attitudesettings.xml
index 522fd6f3a..677493d68 100644
--- a/shared/uavobjectdefinition/attitudesettings.xml
+++ b/shared/uavobjectdefinition/attitudesettings.xml
@@ -5,7 +5,7 @@
-
+
diff --git a/shared/uavobjectdefinition/cameradesired.xml b/shared/uavobjectdefinition/cameradesired.xml
new file mode 100644
index 000000000..022728f7e
--- /dev/null
+++ b/shared/uavobjectdefinition/cameradesired.xml
@@ -0,0 +1,12 @@
+
+
+
diff --git a/shared/uavobjectdefinition/camerastabsettings.xml b/shared/uavobjectdefinition/camerastabsettings.xml
new file mode 100644
index 000000000..09199b77a
--- /dev/null
+++ b/shared/uavobjectdefinition/camerastabsettings.xml
@@ -0,0 +1,12 @@
+
+
+
diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml
index 7b4ed7ec4..242cba679 100644
--- a/shared/uavobjectdefinition/hwsettings.xml
+++ b/shared/uavobjectdefinition/hwsettings.xml
@@ -1,17 +1,21 @@
-
diff --git a/shared/uavobjectdefinition/mixersettings.xml b/shared/uavobjectdefinition/mixersettings.xml
index 02ff69013..e070814c5 100644
--- a/shared/uavobjectdefinition/mixersettings.xml
+++ b/shared/uavobjectdefinition/mixersettings.xml
@@ -5,24 +5,24 @@
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
diff --git a/shared/uavobjectdefinition/objectpersistence.xml b/shared/uavobjectdefinition/objectpersistence.xml
index 94076de9a..aa7a58e8c 100644
--- a/shared/uavobjectdefinition/objectpersistence.xml
+++ b/shared/uavobjectdefinition/objectpersistence.xml
@@ -1,7 +1,7 @@
Someone who knows please enter this
-
+
diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml
index b6668350d..653c7cce8 100644
--- a/shared/uavobjectdefinition/stabilizationsettings.xml
+++ b/shared/uavobjectdefinition/stabilizationsettings.xml
@@ -16,7 +16,7 @@
-
+