mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Merge branch 'next' into revo
Conflicts: flight/Modules/ManualControl/manualcontrol.c ground/openpilotgcs/src/plugins/config/input.ui ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp shared/uavobjectdefinition/manualcontrolsettings.xml
This commit is contained in:
commit
d150fd5331
@ -1,5 +1,13 @@
|
||||
Short summary of changes. For a complete list see the git log.
|
||||
|
||||
2012-07-10
|
||||
On Windows the installation mode was changed from per-user to per-machine
|
||||
(for all users) installation. It is recommended to completely uninstall
|
||||
previous version before installing new one to remove per-user installed
|
||||
files. Per-machine installation requires elevated (administrator) previleges
|
||||
during install. But since the same rights are now required to install
|
||||
optional CDC driver (virtual communication port), it was deemed acceptable.
|
||||
|
||||
2012-06-04
|
||||
AeroSimRC support merged into next
|
||||
|
||||
|
@ -109,7 +109,10 @@ class UAVObject:
|
||||
|
||||
def addField(self, field):
|
||||
append(self.fields, field)
|
||||
|
||||
'''
|
||||
#
|
||||
# Support for getName was removed from embedded UAVO database to save RAM + Flash
|
||||
#
|
||||
def getName(self):
|
||||
"""__NATIVE__
|
||||
UAVObjHandle objHandle;
|
||||
@ -143,6 +146,7 @@ class UAVObject:
|
||||
return PM_RET_OK;
|
||||
"""
|
||||
pass
|
||||
'''
|
||||
|
||||
def read(self):
|
||||
"""__NATIVE__
|
||||
|
@ -60,7 +60,6 @@
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY+4)
|
||||
#define UPDATE_PERIOD_MS 20
|
||||
#define THROTTLE_FAILSAFE -0.1f
|
||||
#define FLIGHT_MODE_LIMIT 1.0f/3.0f
|
||||
#define ARMED_TIME_MS 1000
|
||||
#define ARMED_THRESHOLD 0.50f
|
||||
//safe band to allow a bit of calibration error or trim offset (in microseconds)
|
||||
@ -241,19 +240,23 @@ static void manualControlTask(void *parameters)
|
||||
settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE ||
|
||||
settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE ||
|
||||
settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE ||
|
||||
settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE ||
|
||||
// Check all channel mappings are valid
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] == (uint16_t) PIOS_RCVR_INVALID ||
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] == (uint16_t) PIOS_RCVR_INVALID ||
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] == (uint16_t) PIOS_RCVR_INVALID ||
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] == (uint16_t) PIOS_RCVR_INVALID ||
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t) PIOS_RCVR_INVALID ||
|
||||
// Check the driver is exists
|
||||
// Check the driver exists
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] == (uint16_t) PIOS_RCVR_NODRIVER ||
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] == (uint16_t) PIOS_RCVR_NODRIVER ||
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] == (uint16_t) PIOS_RCVR_NODRIVER ||
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] == (uint16_t) PIOS_RCVR_NODRIVER ||
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t) PIOS_RCVR_NODRIVER) {
|
||||
// Check the FlightModeNumber is valid
|
||||
settings.FlightModeNumber < 1 || settings.FlightModeNumber > MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_NUMELEM ||
|
||||
// Similar checks for FlightMode channel but only if more than one flight mode has been set. Otherwise don't care
|
||||
((settings.FlightModeNumber > 1) && (
|
||||
settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE ||
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t) PIOS_RCVR_INVALID ||
|
||||
cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t) PIOS_RCVR_NODRIVER))) {
|
||||
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
cmd.Connected = MANUALCONTROLCOMMAND_CONNECTED_FALSE;
|
||||
@ -362,8 +365,6 @@ static void manualControlTask(void *parameters)
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
if (processFailsafe(cmd.Connected == MANUALCONTROLCOMMAND_CONNECTED_TRUE, &settings) == false) {
|
||||
@ -998,30 +999,27 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Determine which of three positions the flight mode switch is in and set flight mode accordingly
|
||||
* @brief Determine which of N positions the flight mode switch is in and set flight mode accordingly
|
||||
* @param[out] cmd Pointer to the command structure to set the flight mode in
|
||||
* @param[in] settings The settings which indicate which position is which mode
|
||||
* @param[in] flightMode the value of the switch position
|
||||
*/
|
||||
static void processFlightMode(ManualControlSettingsData * settings, float flightMode)
|
||||
static void processFlightMode(ManualControlSettingsData *settings, float flightMode)
|
||||
{
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
|
||||
uint8_t newMode;
|
||||
// Note here the code is ass
|
||||
if (flightMode < -FLIGHT_MODE_LIMIT)
|
||||
newMode = settings->FlightModePosition[0];
|
||||
else if (flightMode > FLIGHT_MODE_LIMIT)
|
||||
newMode = settings->FlightModePosition[2];
|
||||
else
|
||||
newMode = settings->FlightModePosition[1];
|
||||
// Convert flightMode value into the switch position in the range [0..N-1]
|
||||
uint8_t pos = ((int16_t)(flightMode * 256.0f) + 256) * settings->FlightModeNumber >> 9;
|
||||
if (pos >= settings->FlightModeNumber)
|
||||
pos = settings->FlightModeNumber - 1;
|
||||
|
||||
if(flightStatus.FlightMode != newMode) {
|
||||
uint8_t newMode = settings->FlightModePosition[pos];
|
||||
|
||||
if (flightStatus.FlightMode != newMode) {
|
||||
flightStatus.FlightMode = newMode;
|
||||
FlightStatusSet(&flightStatus);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -255,9 +255,9 @@ static int32_t RadioComBridgeInitialize(void)
|
||||
PipXSettingsPairIDGet(&(data->pairStats[0].pairID));
|
||||
|
||||
// Configure our UAVObjects for updates.
|
||||
UAVObjConnectQueue(UAVObjGetByName("PipXStatus"), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
|
||||
UAVObjConnectQueue(UAVObjGetByName("GCSReceiver"), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
|
||||
UAVObjConnectQueue(UAVObjGetByName("ObjectPersistence"), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL);
|
||||
UAVObjConnectQueue(UAVObjGetByID(PIPXSTATUS_OBJID), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
|
||||
UAVObjConnectQueue(UAVObjGetByID(GCSRECEIVER_OBJID), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
|
||||
UAVObjConnectQueue(UAVObjGetByID(OBJECTPERSISTENCE_OBJID), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -444,7 +444,6 @@ static float bound(float val)
|
||||
|
||||
static void SettingsUpdatedCb(UAVObjEvent * ev)
|
||||
{
|
||||
memset(pids,0,sizeof (pid_type) * PID_MAX);
|
||||
StabilizationSettingsGet(&settings);
|
||||
|
||||
// Set the roll rate PID constants
|
||||
|
12
flight/PiOS.posix/inc/pios_struct_helper.h
Normal file
12
flight/PiOS.posix/inc/pios_struct_helper.h
Normal file
@ -0,0 +1,12 @@
|
||||
/* Taken from include/linux/kernel.h from the Linux kernel tree */
|
||||
|
||||
/**
|
||||
* container_of - cast a member of a structure out to the containing structure
|
||||
* @ptr: the pointer to the member.
|
||||
* @type: the type of the container struct this is embedded in.
|
||||
* @member: the name of the member within the struct.
|
||||
*
|
||||
*/
|
||||
#define container_of(ptr, type, member) ({ \
|
||||
const typeof( ((type *)0)->member ) *__mptr = (ptr); \
|
||||
(type *)( (char *)__mptr - offsetof(type,member) );})
|
@ -274,7 +274,6 @@ void vPortStartFirstTask( void )
|
||||
*/
|
||||
portBASE_TYPE xPortStartScheduler( void )
|
||||
{
|
||||
portBASE_TYPE xResult;
|
||||
sigset_t xSignalToBlock;
|
||||
|
||||
/**
|
||||
@ -337,9 +336,9 @@ portBASE_TYPE xPortStartScheduler( void )
|
||||
|
||||
PORT_PRINT( "Cleaning Up, Exiting.\n" );
|
||||
/* Cleanup the mutexes */
|
||||
xResult = pthread_mutex_destroy( &xRunningThreadMutex );
|
||||
xResult = pthread_mutex_destroy( &xYieldingThreadMutex );
|
||||
xResult = pthread_mutex_destroy( &xGuardMutex );
|
||||
pthread_mutex_destroy( &xRunningThreadMutex );
|
||||
pthread_mutex_destroy( &xYieldingThreadMutex );
|
||||
pthread_mutex_destroy( &xGuardMutex );
|
||||
vPortFree( (void *)pxThreads );
|
||||
|
||||
/* Should not get here! */
|
||||
@ -353,13 +352,12 @@ portBASE_TYPE xPortStartScheduler( void )
|
||||
void vPortEndScheduler( void )
|
||||
{
|
||||
portBASE_TYPE xNumberOfThreads;
|
||||
portBASE_TYPE xResult;
|
||||
for ( xNumberOfThreads = 0; xNumberOfThreads < MAX_NUMBER_OF_TASKS; xNumberOfThreads++ )
|
||||
{
|
||||
if ( ( pthread_t )NULL != pxThreads[ xNumberOfThreads ].hThread )
|
||||
{
|
||||
/* Kill all of the threads, they are in the detached state. */
|
||||
xResult = pthread_cancel( pxThreads[ xNumberOfThreads ].hThread );
|
||||
pthread_cancel( pxThreads[ xNumberOfThreads ].hThread );
|
||||
}
|
||||
}
|
||||
|
||||
@ -683,7 +681,6 @@ void vPortForciblyEndThread( void *pxTaskToDelete )
|
||||
xTaskHandle hTaskToDelete = ( xTaskHandle )pxTaskToDelete;
|
||||
xThreadState* xTaskToDelete;
|
||||
xThreadState* xTaskToResume;
|
||||
portBASE_TYPE xResult;
|
||||
|
||||
PORT_ENTER();
|
||||
|
||||
@ -706,7 +703,7 @@ portBASE_TYPE xResult;
|
||||
|
||||
/* Send a signal to wake the task so that it definitely cancels. */
|
||||
pthread_testcancel();
|
||||
xResult = pthread_cancel( xTaskToDelete->hThread );
|
||||
pthread_cancel( xTaskToDelete->hThread );
|
||||
|
||||
}
|
||||
else
|
||||
|
12
flight/PiOS/inc/pios_struct_helper.h
Normal file
12
flight/PiOS/inc/pios_struct_helper.h
Normal file
@ -0,0 +1,12 @@
|
||||
/* Taken from include/linux/kernel.h from the Linux kernel tree */
|
||||
|
||||
/**
|
||||
* container_of - cast a member of a structure out to the containing structure
|
||||
* @ptr: the pointer to the member.
|
||||
* @type: the type of the container struct this is embedded in.
|
||||
* @member: the name of the member within the struct.
|
||||
*
|
||||
*/
|
||||
#define container_of(ptr, type, member) ({ \
|
||||
const typeof( ((type *)0)->member ) *__mptr = (ptr); \
|
||||
(type *)( (char *)__mptr - offsetof(type,member) );})
|
1
flight/Project/gdb/simposix
Normal file
1
flight/Project/gdb/simposix
Normal file
@ -0,0 +1 @@
|
||||
handle SIGUSR1 noprint nostop
|
@ -38,7 +38,7 @@ OUTDIR := $(TOP)/build/$(TARGET)
|
||||
|
||||
# Set developer code and compile options
|
||||
# Set to YES for debugging
|
||||
DEBUG ?= NO
|
||||
DEBUG ?= YES
|
||||
|
||||
# Set to YES when using Code Sourcery toolchain
|
||||
CODE_SOURCERY ?= NO
|
||||
|
@ -133,7 +133,7 @@ typedef void (*UAVObjEventCallback)(UAVObjEvent* ev);
|
||||
/**
|
||||
* Callback used to initialize the object fields to their default values.
|
||||
*/
|
||||
typedef void (*UAVObjInitializeCallback)(UAVObjHandle obj, uint16_t instId);
|
||||
typedef void (*UAVObjInitializeCallback)(UAVObjHandle obj_handle, uint16_t instId);
|
||||
|
||||
/**
|
||||
* Event manager statistics
|
||||
@ -148,25 +148,23 @@ typedef struct {
|
||||
int32_t UAVObjInitialize();
|
||||
void UAVObjGetStats(UAVObjStats* statsOut);
|
||||
void UAVObjClearStats();
|
||||
UAVObjHandle UAVObjRegister(uint32_t id, const char* name, const char* metaName, int32_t isMetaobject,
|
||||
UAVObjHandle UAVObjRegister(uint32_t id,
|
||||
int32_t isSingleInstance, int32_t isSettings, uint32_t numBytes, UAVObjInitializeCallback initCb);
|
||||
UAVObjHandle UAVObjGetByID(uint32_t id);
|
||||
UAVObjHandle UAVObjGetByName(char* name);
|
||||
uint32_t UAVObjGetID(UAVObjHandle obj);
|
||||
const char* UAVObjGetName(UAVObjHandle obj);
|
||||
uint32_t UAVObjGetNumBytes(UAVObjHandle obj);
|
||||
uint16_t UAVObjGetNumInstances(UAVObjHandle obj);
|
||||
UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj);
|
||||
uint16_t UAVObjCreateInstance(UAVObjHandle obj, UAVObjInitializeCallback initCb);
|
||||
int32_t UAVObjIsSingleInstance(UAVObjHandle obj);
|
||||
int32_t UAVObjIsMetaobject(UAVObjHandle obj);
|
||||
int32_t UAVObjIsSettings(UAVObjHandle obj);
|
||||
int32_t UAVObjUnpack(UAVObjHandle obj, uint16_t instId, const uint8_t* dataIn);
|
||||
int32_t UAVObjPack(UAVObjHandle obj, uint16_t instId, uint8_t* dataOut);
|
||||
int32_t UAVObjSave(UAVObjHandle obj, uint16_t instId);
|
||||
int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId);
|
||||
int32_t UAVObjDelete(UAVObjHandle obj, uint16_t instId);
|
||||
int32_t UAVObjSaveToFile(UAVObjHandle obj, uint16_t instId, FILEINFO* file);
|
||||
uint16_t UAVObjCreateInstance(UAVObjHandle obj_handle, UAVObjInitializeCallback initCb);
|
||||
bool UAVObjIsSingleInstance(UAVObjHandle obj);
|
||||
bool UAVObjIsMetaobject(UAVObjHandle obj);
|
||||
bool UAVObjIsSettings(UAVObjHandle obj);
|
||||
int32_t UAVObjUnpack(UAVObjHandle obj_handle, uint16_t instId, const uint8_t* dataIn);
|
||||
int32_t UAVObjPack(UAVObjHandle obj_handle, uint16_t instId, uint8_t* dataOut);
|
||||
int32_t UAVObjSave(UAVObjHandle obj_handle, uint16_t instId);
|
||||
int32_t UAVObjLoad(UAVObjHandle obj_handle, uint16_t instId);
|
||||
int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId);
|
||||
int32_t UAVObjSaveToFile(UAVObjHandle obj_handle, uint16_t instId, FILEINFO* file);
|
||||
UAVObjHandle UAVObjLoadFromFile(FILEINFO* file);
|
||||
int32_t UAVObjSaveSettings();
|
||||
int32_t UAVObjLoadSettings();
|
||||
@ -174,18 +172,17 @@ int32_t UAVObjDeleteSettings();
|
||||
int32_t UAVObjSaveMetaobjects();
|
||||
int32_t UAVObjLoadMetaobjects();
|
||||
int32_t UAVObjDeleteMetaobjects();
|
||||
int32_t UAVObjSetData(UAVObjHandle obj, const void* dataIn);
|
||||
int32_t UAVObjSetDataField(UAVObjHandle obj, const void* dataIn, uint32_t offset, uint32_t size);
|
||||
int32_t UAVObjGetData(UAVObjHandle obj, void* dataOut);
|
||||
int32_t UAVObjGetDataField(UAVObjHandle obj, void* dataOut, uint32_t offset, uint32_t size);
|
||||
int32_t UAVObjSetInstanceData(UAVObjHandle obj, uint16_t instId, const void* dataIn);
|
||||
int32_t UAVObjSetInstanceDataField(UAVObjHandle obj, uint16_t instId, const void* dataIn, uint32_t offset, uint32_t size);
|
||||
int32_t UAVObjGetInstanceData(UAVObjHandle obj, uint16_t instId, void* dataOut);
|
||||
int32_t UAVObjGetInstanceDataField(UAVObjHandle obj, uint16_t instId, void* dataOut, uint32_t offset, uint32_t size);
|
||||
int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata* dataIn);
|
||||
int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata* dataOut);
|
||||
int32_t UAVObjSetData(UAVObjHandle obj_handle, const void* dataIn);
|
||||
int32_t UAVObjSetDataField(UAVObjHandle obj_handle, const void* dataIn, uint32_t offset, uint32_t size);
|
||||
int32_t UAVObjGetData(UAVObjHandle obj_handle, void* dataOut);
|
||||
int32_t UAVObjGetDataField(UAVObjHandle obj_handle, void* dataOut, uint32_t offset, uint32_t size);
|
||||
int32_t UAVObjSetInstanceData(UAVObjHandle obj_handle, uint16_t instId, const void* dataIn);
|
||||
int32_t UAVObjSetInstanceDataField(UAVObjHandle obj_handle, uint16_t instId, const void* dataIn, uint32_t offset, uint32_t size);
|
||||
int32_t UAVObjGetInstanceData(UAVObjHandle obj_handle, uint16_t instId, void* dataOut);
|
||||
int32_t UAVObjGetInstanceDataField(UAVObjHandle obj_handle, uint16_t instId, void* dataOut, uint32_t offset, uint32_t size);
|
||||
int32_t UAVObjSetMetadata(UAVObjHandle obj_handle, const UAVObjMetadata* dataIn);
|
||||
int32_t UAVObjGetMetadata(UAVObjHandle obj_handle, UAVObjMetadata* dataOut);
|
||||
uint8_t UAVObjGetMetadataAccess(const UAVObjMetadata* dataOut);
|
||||
void UAVObjMetadataInitialize(UAVObjMetadata* dataOut);
|
||||
UAVObjAccessType UAVObjGetAccess(const UAVObjMetadata* dataOut);
|
||||
void UAVObjSetAccess(UAVObjMetadata* dataOut, UAVObjAccessType mode);
|
||||
UAVObjAccessType UAVObjGetGcsAccess(const UAVObjMetadata* dataOut);
|
||||
@ -199,14 +196,14 @@ void UAVObjSetTelemetryUpdateMode(UAVObjMetadata* dataOut, UAVObjUpdateMode val)
|
||||
UAVObjUpdateMode UAVObjGetGcsTelemetryUpdateMode(const UAVObjMetadata* dataOut);
|
||||
void UAVObjSetTelemetryGcsUpdateMode(UAVObjMetadata* dataOut, UAVObjUpdateMode val);
|
||||
int8_t UAVObjReadOnly(UAVObjHandle obj);
|
||||
int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue, uint8_t eventMask);
|
||||
int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue);
|
||||
int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb, uint8_t eventMask);
|
||||
int32_t UAVObjDisconnectCallback(UAVObjHandle obj, UAVObjEventCallback cb);
|
||||
int32_t UAVObjConnectQueue(UAVObjHandle obj_handle, xQueueHandle queue, uint8_t eventMask);
|
||||
int32_t UAVObjDisconnectQueue(UAVObjHandle obj_handle, xQueueHandle queue);
|
||||
int32_t UAVObjConnectCallback(UAVObjHandle obj_handle, UAVObjEventCallback cb, uint8_t eventMask);
|
||||
int32_t UAVObjDisconnectCallback(UAVObjHandle obj_handle, UAVObjEventCallback cb);
|
||||
void UAVObjRequestUpdate(UAVObjHandle obj);
|
||||
void UAVObjRequestInstanceUpdate(UAVObjHandle obj, uint16_t instId);
|
||||
void UAVObjRequestInstanceUpdate(UAVObjHandle obj_handle, uint16_t instId);
|
||||
void UAVObjUpdated(UAVObjHandle obj);
|
||||
void UAVObjInstanceUpdated(UAVObjHandle obj, uint16_t instId);
|
||||
void UAVObjInstanceUpdated(UAVObjHandle obj_handle, uint16_t instId);
|
||||
void UAVObjIterate(void (*iterator)(UAVObjHandle obj));
|
||||
|
||||
#endif // UAVOBJECTMANAGER_H
|
||||
|
@ -42,8 +42,6 @@
|
||||
|
||||
// Object constants
|
||||
#define $(NAMEUC)_OBJID $(OBJIDHEX)
|
||||
#define $(NAMEUC)_NAME "$(NAME)"
|
||||
#define $(NAMEUC)_METANAME "$(NAME)Meta"
|
||||
#define $(NAMEUC)_ISSINGLEINST $(ISSINGLEINST)
|
||||
#define $(NAMEUC)_ISSETTINGS $(ISSETTINGS)
|
||||
#define $(NAMEUC)_NUMBYTES sizeof($(NAME)Data)
|
||||
|
@ -1,20 +1,20 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup UAVObjects OpenPilot UAVObjects
|
||||
* @{
|
||||
* @addtogroup UAV Object Manager
|
||||
* @brief The core UAV Objects functions, most of which are wrappered by
|
||||
* autogenerated defines
|
||||
* @{
|
||||
*
|
||||
*
|
||||
* @file uavobjectmanager.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Object manager library. This library holds a collection of all objects.
|
||||
* It can be used by all modules/libraries to find an object reference.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
******************************************************************************
|
||||
* @addtogroup UAVObjects OpenPilot UAVObjects
|
||||
* @{
|
||||
* @addtogroup UAV Object Manager
|
||||
* @brief The core UAV Objects functions, most of which are wrappered by
|
||||
* autogenerated defines
|
||||
* @{
|
||||
*
|
||||
*
|
||||
* @file uavobjectmanager.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Object manager library. This library holds a collection of all objects.
|
||||
* It can be used by all modules/libraries to find an object reference.
|
||||
* @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
|
||||
@ -32,6 +32,7 @@
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "pios_struct_helper.h"
|
||||
|
||||
// Constants
|
||||
|
||||
@ -39,84 +40,144 @@
|
||||
|
||||
// Macros
|
||||
#define SET_BITS(var, shift, value, mask) var = (var & ~(mask << shift)) | (value << shift);
|
||||
#define OLGetIsMetaobject(olp) ((olp)->flags & OL_IS_METAOBJECT)
|
||||
#define OLSetIsMetaobject(olp, val) ((olp)->flags = (((val) == 0) ? ((olp)->flags & ~OL_IS_METAOBJECT) : ((olp)->flags | OL_IS_METAOBJECT)))
|
||||
#define OLGetIsSingleInstance(olp) ((olp)->flags & OL_IS_SINGLE_INSTANCE)
|
||||
#define OLSetIsSingleInstance(olp, val) ((olp)->flags = (((val) == 0) ? ((olp)->flags & ~OL_IS_SINGLE_INSTANCE) : ((olp)->flags | OL_IS_SINGLE_INSTANCE)))
|
||||
#define OLGetIsSettings(olp) ((olp)->flags & OL_IS_SETTINGS)
|
||||
#define OLSetIsSettings(olp, val) ((olp)->flags = (((val) == 0) ? ((olp)->flags & ~OL_IS_SETTINGS) : ((olp)->flags | OL_IS_SETTINGS)))
|
||||
|
||||
/**
|
||||
* List of event queues and the eventmask associated with the queue.
|
||||
*/
|
||||
struct ObjectEventListStruct {
|
||||
xQueueHandle queue;
|
||||
UAVObjEventCallback cb;
|
||||
uint8_t eventMask;
|
||||
struct ObjectEventListStruct *next;
|
||||
};
|
||||
typedef struct ObjectEventListStruct ObjectEventList;
|
||||
|
||||
/**
|
||||
* List of object instances, holds the actual data structure and instance ID
|
||||
*/
|
||||
struct ObjectInstListStruct {
|
||||
void *data;
|
||||
uint16_t instId;
|
||||
struct ObjectInstListStruct *next;
|
||||
};
|
||||
typedef struct ObjectInstListStruct ObjectInstList;
|
||||
/** opaque type for instances **/
|
||||
typedef void* InstanceHandle;
|
||||
|
||||
typedef enum {
|
||||
OL_IS_METAOBJECT = 0x01, /** Set if this is a metaobject */
|
||||
OL_IS_SINGLE_INSTANCE = 0x02, /** Set if this object has a single instance */
|
||||
OL_IS_SETTINGS = 0x04 /** Set if this object is a settings object */
|
||||
} ObjectListFlags;
|
||||
|
||||
/**
|
||||
* List of objects registered in the object manager
|
||||
*/
|
||||
struct ObjectListStruct {
|
||||
uint32_t id;
|
||||
/** The object ID */
|
||||
const char *name;
|
||||
/** The object name */
|
||||
ObjectListFlags flags;
|
||||
/** The object list mode flags */
|
||||
uint16_t numBytes;
|
||||
/** Number of data bytes contained in the object (for a single instance) */
|
||||
uint16_t numInstances;
|
||||
/** Number of instances */
|
||||
struct ObjectListStruct *linkedObj;
|
||||
/** Linked object, for regular objects this is the metaobject and for metaobjects it is the parent object */
|
||||
ObjectInstList instances;
|
||||
/** List of object instances, instance 0 always exists */
|
||||
ObjectEventList *events;
|
||||
/** Event queues registered on the object */
|
||||
struct ObjectListStruct *next;
|
||||
/** Needed by linked list library (utlist.h) */
|
||||
struct ObjectEventEntry {
|
||||
xQueueHandle queue;
|
||||
UAVObjEventCallback cb;
|
||||
uint8_t eventMask;
|
||||
struct ObjectEventEntry * next;
|
||||
};
|
||||
typedef struct ObjectListStruct ObjectList;
|
||||
|
||||
/*
|
||||
MetaInstance == [UAVOBase [UAVObjMetadata]]
|
||||
SingleInstance == [UAVOBase [UAVOData [InstanceData]]]
|
||||
MultiInstance == [UAVOBase [UAVOData [NumInstances [InstanceData0 [next]]]]
|
||||
____________________/
|
||||
\-->[InstanceData1 [next]]
|
||||
_________...________/
|
||||
\-->[InstanceDataN [next]]
|
||||
*/
|
||||
|
||||
/*
|
||||
* UAVO Base Type
|
||||
* - All Types of UAVObjects are of this base type
|
||||
* - The flags determine what type(s) this object
|
||||
*/
|
||||
struct UAVOBase {
|
||||
/* Let these objects be added to an event queue */
|
||||
struct ObjectEventEntry * next_event;
|
||||
|
||||
/* Describe the type of object that follows this header */
|
||||
struct UAVOInfo {
|
||||
bool isMeta : 1;
|
||||
bool isSingle : 1;
|
||||
bool isSettings : 1;
|
||||
} flags;
|
||||
|
||||
} __attribute__((packed));
|
||||
|
||||
/* Augmented type for Meta UAVO */
|
||||
struct UAVOMeta {
|
||||
struct UAVOBase base;
|
||||
UAVObjMetadata instance0;
|
||||
} __attribute__((packed));
|
||||
|
||||
/* Shared data structure for all data-carrying UAVObjects (UAVOSingle and UAVOMulti) */
|
||||
struct UAVOData {
|
||||
struct UAVOBase base;
|
||||
uint32_t id;
|
||||
/*
|
||||
* Embed the Meta object as another complete UAVO
|
||||
* inside the payload for this UAVO.
|
||||
*/
|
||||
struct UAVOMeta metaObj;
|
||||
struct UAVOData * next;
|
||||
uint16_t instance_size;
|
||||
} __attribute__((packed));
|
||||
|
||||
/* Augmented type for Single Instance Data UAVO */
|
||||
struct UAVOSingle {
|
||||
struct UAVOData uavo;
|
||||
|
||||
uint8_t instance0[];
|
||||
/*
|
||||
* Additional space will be malloc'd here to hold the
|
||||
* the data for this instance.
|
||||
*/
|
||||
} __attribute__((packed));
|
||||
|
||||
/* Part of a linked list of instances chained off of a multi instance UAVO. */
|
||||
struct UAVOMultiInst {
|
||||
struct UAVOMultiInst * next;
|
||||
uint8_t instance[];
|
||||
/*
|
||||
* Additional space will be malloc'd here to hold the
|
||||
* the data for this instance.
|
||||
*/
|
||||
} __attribute__((packed));
|
||||
|
||||
/* Augmented type for Multi Instance Data UAVO */
|
||||
struct UAVOMulti {
|
||||
struct UAVOData uavo;
|
||||
|
||||
uint16_t num_instances;
|
||||
struct UAVOMultiInst instance0;
|
||||
/*
|
||||
* Additional space will be malloc'd here to hold the
|
||||
* the data for instance 0.
|
||||
*/
|
||||
} __attribute__((packed));
|
||||
|
||||
/** all information about a metaobject are hardcoded constants **/
|
||||
#define MetaNumBytes sizeof(UAVObjMetadata)
|
||||
#define MetaBaseObjectPtr(obj) ((struct UAVOData *)((obj)-offsetof(struct UAVOData, metaObj)))
|
||||
#define MetaObjectPtr(obj) ((struct UAVODataMeta*) &((obj)->metaObj))
|
||||
#define MetaDataPtr(obj) ((UAVObjMetadata*)&((obj)->instance0))
|
||||
#define LinkedMetaDataPtr(obj) ((UAVObjMetadata*)&((obj)->metaObj.instance0))
|
||||
#define MetaObjectId(id) ((id)+1)
|
||||
|
||||
/** all information about instances are dependant on object type **/
|
||||
#define ObjSingleInstanceDataOffset(obj) ((void*)(&(( (struct UAVOSingle*)obj )->instance0)))
|
||||
#define InstanceDataOffset(inst) ((void*)&(( (struct UAVOMultiInst*)inst )->instance))
|
||||
#define InstanceData(instance) (void*)instance
|
||||
|
||||
// Private functions
|
||||
static int32_t sendEvent(ObjectList * obj, uint16_t instId,
|
||||
UAVObjEventType event);
|
||||
static ObjectInstList *createInstance(ObjectList * obj, uint16_t instId);
|
||||
static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId);
|
||||
static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue,
|
||||
UAVObjEventCallback cb, uint8_t eventMask);
|
||||
static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue,
|
||||
UAVObjEventCallback cb);
|
||||
static int32_t sendEvent(struct UAVOBase * obj, uint16_t instId,
|
||||
UAVObjEventType event);
|
||||
static InstanceHandle createInstance(struct UAVOData * obj, uint16_t instId);
|
||||
static InstanceHandle getInstance(struct UAVOData * obj, uint16_t instId);
|
||||
static int32_t connectObj(UAVObjHandle obj_handle, xQueueHandle queue,
|
||||
UAVObjEventCallback cb, uint8_t eventMask);
|
||||
static int32_t disconnectObj(UAVObjHandle obj_handle, xQueueHandle queue,
|
||||
UAVObjEventCallback cb);
|
||||
|
||||
#if defined(PIOS_INCLUDE_SDCARD)
|
||||
static void objectFilename(ObjectList * obj, uint8_t * filename);
|
||||
static void objectFilename(UAVObjHandle obj_handle, uint8_t * filename);
|
||||
static void customSPrintf(uint8_t * buffer, uint8_t * format, ...);
|
||||
#endif
|
||||
|
||||
// Private variables
|
||||
static ObjectList *objList;
|
||||
static struct UAVOData * uavo_list;
|
||||
static xSemaphoreHandle mutex;
|
||||
static UAVObjMetadata defMetadata;
|
||||
static const UAVObjMetadata defMetadata = {
|
||||
.flags = (ACCESS_READWRITE << UAVOBJ_ACCESS_SHIFT |
|
||||
ACCESS_READWRITE << UAVOBJ_GCS_ACCESS_SHIFT |
|
||||
1 << UAVOBJ_TELEMETRY_ACKED_SHIFT |
|
||||
1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT |
|
||||
UPDATEMODE_ONCHANGE << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT |
|
||||
UPDATEMODE_ONCHANGE << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT),
|
||||
.telemetryUpdatePeriod = 0,
|
||||
.gcsTelemetryUpdatePeriod = 0,
|
||||
.loggingUpdatePeriod = 0,
|
||||
};
|
||||
|
||||
static UAVObjStats stats;
|
||||
|
||||
/**
|
||||
@ -126,31 +187,32 @@ static UAVObjStats stats;
|
||||
*/
|
||||
int32_t UAVObjInitialize()
|
||||
{
|
||||
// Initialize variables
|
||||
objList = NULL;
|
||||
memset(&stats, 0, sizeof(UAVObjStats));
|
||||
// Initialize variables
|
||||
uavo_list = NULL;
|
||||
memset(&stats, 0, sizeof(UAVObjStats));
|
||||
|
||||
// Create mutex
|
||||
mutex = xSemaphoreCreateRecursiveMutex();
|
||||
if (mutex == NULL)
|
||||
return -1;
|
||||
// Create mutex
|
||||
mutex = xSemaphoreCreateRecursiveMutex();
|
||||
if (mutex == NULL)
|
||||
return -1;
|
||||
|
||||
// Initialize default metadata structure (metadata of metaobjects)
|
||||
UAVObjMetadataInitialize(&defMetadata);
|
||||
|
||||
// Done
|
||||
return 0;
|
||||
// Done
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*****************
|
||||
* Statistics
|
||||
****************/
|
||||
|
||||
/**
|
||||
* Get the statistics counters
|
||||
* @param[out] statsOut The statistics counters will be copied there
|
||||
*/
|
||||
void UAVObjGetStats(UAVObjStats * statsOut)
|
||||
{
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
memcpy(statsOut, &stats, sizeof(UAVObjStats));
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
memcpy(statsOut, &stats, sizeof(UAVObjStats));
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -158,17 +220,84 @@ void UAVObjGetStats(UAVObjStats * statsOut)
|
||||
*/
|
||||
void UAVObjClearStats()
|
||||
{
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
memset(&stats, 0, sizeof(UAVObjStats));
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
memset(&stats, 0, sizeof(UAVObjStats));
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
}
|
||||
|
||||
/************************
|
||||
* Object Initialization
|
||||
***********************/
|
||||
|
||||
static void UAVObjInitMetaData (struct UAVOMeta * obj_meta)
|
||||
{
|
||||
/* Fill in the common part of the UAVO */
|
||||
struct UAVOBase * uavo_base = &(obj_meta->base);
|
||||
memset(uavo_base, 0, sizeof(*uavo_base));
|
||||
uavo_base->flags.isMeta = true;
|
||||
uavo_base->flags.isSingle = true;
|
||||
uavo_base->next_event = NULL;
|
||||
|
||||
/* Clear the instance data carried in the UAVO */
|
||||
memset(&(obj_meta->instance0), 0, sizeof(obj_meta->instance0));
|
||||
}
|
||||
|
||||
static struct UAVOData * UAVObjAllocSingle(uint32_t num_bytes)
|
||||
{
|
||||
/* Compute the complete size of the object, including the data for a single embedded instance */
|
||||
uint32_t object_size = sizeof(struct UAVOSingle) + num_bytes;
|
||||
|
||||
/* Allocate the object from the heap */
|
||||
struct UAVOSingle * uavo_single = (struct UAVOSingle *) pvPortMalloc(object_size);
|
||||
if (!uavo_single)
|
||||
return (NULL);
|
||||
|
||||
/* Fill in the common part of the UAVO */
|
||||
struct UAVOBase * uavo_base = &(uavo_single->uavo.base);
|
||||
memset(uavo_base, 0, sizeof(*uavo_base));
|
||||
uavo_base->flags.isSingle = true;
|
||||
uavo_base->next_event = NULL;
|
||||
|
||||
/* Clear the instance data carried in the UAVO */
|
||||
memset(&(uavo_single->instance0), 0, num_bytes);
|
||||
|
||||
/* Give back the generic UAVO part */
|
||||
return (&(uavo_single->uavo));
|
||||
}
|
||||
|
||||
static struct UAVOData * UAVObjAllocMulti(uint32_t num_bytes)
|
||||
{
|
||||
/* Compute the complete size of the object, including the data for a single embedded instance */
|
||||
uint32_t object_size = sizeof(struct UAVOMulti) + num_bytes;
|
||||
|
||||
/* Allocate the object from the heap */
|
||||
struct UAVOMulti * uavo_multi = (struct UAVOMulti *) pvPortMalloc(object_size);
|
||||
if (!uavo_multi)
|
||||
return (NULL);
|
||||
|
||||
/* Fill in the common part of the UAVO */
|
||||
struct UAVOBase * uavo_base = &(uavo_multi->uavo.base);
|
||||
memset(uavo_base, 0, sizeof(*uavo_base));
|
||||
uavo_base->flags.isSingle = false;
|
||||
uavo_base->next_event = NULL;
|
||||
|
||||
/* Set up the type-specific part of the UAVO */
|
||||
uavo_multi->num_instances = 1;
|
||||
|
||||
/* Clear the instance data carried in the UAVO */
|
||||
memset (&(uavo_multi->instance0), 0, num_bytes);
|
||||
|
||||
/* Give back the generic UAVO part */
|
||||
return (&(uavo_multi->uavo));
|
||||
}
|
||||
|
||||
/**************************
|
||||
* UAVObject Database APIs
|
||||
*************************/
|
||||
|
||||
/**
|
||||
* Register and new object in the object manager.
|
||||
* \param[in] id Unique object ID
|
||||
* \param[in] name Object name
|
||||
* \param[in] nameName Metaobject name
|
||||
* \param[in] isMetaobject Is this a metaobject (1:true, 0:false)
|
||||
* \param[in] isSingleInstance Is this a single instance or multi-instance object
|
||||
* \param[in] isSettings Is this a settings object
|
||||
* \param[in] numBytes Number of bytes of object data (for one instance)
|
||||
@ -176,85 +305,60 @@ void UAVObjClearStats()
|
||||
* \return Object handle, or NULL if failure.
|
||||
* \return
|
||||
*/
|
||||
UAVObjHandle UAVObjRegister(uint32_t id, const char *name,
|
||||
const char *metaName, int32_t isMetaobject,
|
||||
int32_t isSingleInstance, int32_t isSettings,
|
||||
uint32_t numBytes,
|
||||
UAVObjInitializeCallback initCb)
|
||||
UAVObjHandle UAVObjRegister(uint32_t id,
|
||||
int32_t isSingleInstance, int32_t isSettings,
|
||||
uint32_t num_bytes,
|
||||
UAVObjInitializeCallback initCb)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
ObjectInstList *instEntry;
|
||||
ObjectList *metaObj;
|
||||
struct UAVOData * uavo_data = NULL;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Check that the object is not already registered
|
||||
LL_FOREACH(objList, objEntry) {
|
||||
if (objEntry->id == id) {
|
||||
// Already registered, ignore
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
/* Don't allow duplicate registrations */
|
||||
if (UAVObjGetByID(id))
|
||||
goto unlock_exit;
|
||||
|
||||
// Create and append entry
|
||||
objEntry = (ObjectList *) pvPortMalloc(sizeof(ObjectList));
|
||||
if (objEntry == NULL) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
objEntry->id = id;
|
||||
objEntry->name = name;
|
||||
OLSetIsMetaobject(objEntry, isMetaobject);
|
||||
OLSetIsSingleInstance(objEntry, isSingleInstance);
|
||||
OLSetIsSettings(objEntry, isSettings);
|
||||
objEntry->numBytes = numBytes;
|
||||
objEntry->events = NULL;
|
||||
objEntry->numInstances = 0;
|
||||
objEntry->instances.data = NULL;
|
||||
objEntry->instances.instId = 0xFFFF;
|
||||
objEntry->instances.next = NULL;
|
||||
objEntry->linkedObj = NULL; // will be set later
|
||||
LL_APPEND(objList, objEntry);
|
||||
/* Map the various flags to one of the UAVO types we understand */
|
||||
if (isSingleInstance) {
|
||||
uavo_data = UAVObjAllocSingle (num_bytes);
|
||||
} else {
|
||||
uavo_data = UAVObjAllocMulti (num_bytes);
|
||||
}
|
||||
|
||||
// Create instance zero
|
||||
instEntry = createInstance(objEntry, 0);
|
||||
if (instEntry == NULL) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
// Create metaobject and update linkedObj
|
||||
if (isMetaobject) {
|
||||
objEntry->linkedObj = NULL; // will be set later
|
||||
} else {
|
||||
// Create metaobject
|
||||
metaObj =
|
||||
(ObjectList *) UAVObjRegister(id + 1, metaName,
|
||||
NULL, 1, 1, 0,
|
||||
sizeof
|
||||
(UAVObjMetadata),
|
||||
NULL);
|
||||
// Link two objects
|
||||
objEntry->linkedObj = metaObj;
|
||||
metaObj->linkedObj = objEntry;
|
||||
}
|
||||
if (!uavo_data)
|
||||
goto unlock_exit;
|
||||
|
||||
// Initialize object fields and metadata to default values
|
||||
if (initCb != NULL) {
|
||||
initCb((UAVObjHandle) objEntry, 0);
|
||||
}
|
||||
// Attempt to load object's metadata from the SD card (not done directly on the metaobject, but through the object)
|
||||
if (!OLGetIsMetaobject(objEntry)) {
|
||||
UAVObjLoad((UAVObjHandle) objEntry->linkedObj, 0);
|
||||
}
|
||||
// If this is a settings object, attempt to load from SD card
|
||||
if (OLGetIsSettings(objEntry)) {
|
||||
UAVObjLoad((UAVObjHandle) objEntry, 0);
|
||||
}
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return (UAVObjHandle) objEntry;
|
||||
/* Fill in the details about this UAVO */
|
||||
uavo_data->id = id;
|
||||
uavo_data->instance_size = num_bytes;
|
||||
if (isSettings) {
|
||||
uavo_data->base.flags.isSettings = true;
|
||||
}
|
||||
|
||||
/* Initialize the embedded meta UAVO */
|
||||
UAVObjInitMetaData (&uavo_data->metaObj);
|
||||
|
||||
/* Add the newly created object to the global list of objects */
|
||||
LL_APPEND(uavo_list, uavo_data);
|
||||
|
||||
/* Initialize object fields and metadata to default values */
|
||||
if (initCb)
|
||||
initCb((UAVObjHandle) uavo_data, 0);
|
||||
|
||||
/* Always try to load the meta object from flash */
|
||||
UAVObjLoad((UAVObjHandle) &(uavo_data->metaObj), 0);
|
||||
|
||||
/* Attempt to load settings object from flash */
|
||||
if (uavo_data->base.flags.isSettings)
|
||||
UAVObjLoad((UAVObjHandle) uavo_data, 0);
|
||||
|
||||
// fire events for outer object and its embedded meta object
|
||||
UAVObjInstanceUpdated((UAVObjHandle) uavo_data, 0);
|
||||
UAVObjInstanceUpdated((UAVObjHandle) &(uavo_data->metaObj), 0);
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return (UAVObjHandle) uavo_data;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -264,52 +368,27 @@ UAVObjHandle UAVObjRegister(uint32_t id, const char *name,
|
||||
*/
|
||||
UAVObjHandle UAVObjGetByID(uint32_t id)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
UAVObjHandle * found_obj = (UAVObjHandle *) NULL;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Look for object
|
||||
LL_FOREACH(objList, objEntry) {
|
||||
if (objEntry->id == id) {
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
// Done, object found
|
||||
return (UAVObjHandle) objEntry;
|
||||
}
|
||||
}
|
||||
// Look for object
|
||||
struct UAVOData * tmp_obj;
|
||||
LL_FOREACH(uavo_list, tmp_obj) {
|
||||
if (tmp_obj->id == id) {
|
||||
found_obj = (UAVObjHandle *)tmp_obj;
|
||||
goto unlock_exit;
|
||||
}
|
||||
if (MetaObjectId(tmp_obj->id) == id) {
|
||||
found_obj = (UAVObjHandle *)&(tmp_obj->metaObj);
|
||||
goto unlock_exit;
|
||||
}
|
||||
}
|
||||
|
||||
// Object not found, release lock and return error
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/**
|
||||
* Retrieve an object from the list given its name
|
||||
* \param[in] name The name of the object
|
||||
* \return The object or NULL if not found.
|
||||
*/
|
||||
UAVObjHandle UAVObjGetByName(char *name)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Look for object
|
||||
LL_FOREACH(objList, objEntry) {
|
||||
if (objEntry->name != NULL
|
||||
&& strcmp(objEntry->name, name) == 0) {
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
// Done, object found
|
||||
return (UAVObjHandle) objEntry;
|
||||
}
|
||||
}
|
||||
|
||||
// Object not found, release lock and return error
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return found_obj;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -317,19 +396,24 @@ UAVObjHandle UAVObjGetByName(char *name)
|
||||
* \param[in] obj The object handle
|
||||
* \return The object ID
|
||||
*/
|
||||
uint32_t UAVObjGetID(UAVObjHandle obj)
|
||||
uint32_t UAVObjGetID(UAVObjHandle obj_handle)
|
||||
{
|
||||
return ((ObjectList *) obj)->id;
|
||||
}
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
/**
|
||||
* Get the object's name
|
||||
* \param[in] obj The object handle
|
||||
* \return The object's name
|
||||
*/
|
||||
const char *UAVObjGetName(UAVObjHandle obj)
|
||||
{
|
||||
return ((ObjectList *) obj)->name;
|
||||
/* Recover the common object header */
|
||||
struct UAVOBase * uavo_base = (struct UAVOBase *) obj_handle;
|
||||
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
/* We have a meta object, find our containing UAVO */
|
||||
struct UAVOData * uavo_data = container_of ((struct UAVOMeta *)uavo_base, struct UAVOData, metaObj);
|
||||
|
||||
return MetaObjectId (uavo_data->id);
|
||||
} else {
|
||||
/* We have a data object, augment our pointer */
|
||||
struct UAVOData * uavo_data = (struct UAVOData *) uavo_base;
|
||||
|
||||
return (uavo_data->id);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -339,7 +423,23 @@ const char *UAVObjGetName(UAVObjHandle obj)
|
||||
*/
|
||||
uint32_t UAVObjGetNumBytes(UAVObjHandle obj)
|
||||
{
|
||||
return ((ObjectList *) obj)->numBytes;
|
||||
PIOS_Assert(obj);
|
||||
|
||||
uint32_t instance_size;
|
||||
|
||||
/* Recover the common object header */
|
||||
struct UAVOBase * uavo_base = (struct UAVOBase *) obj;
|
||||
|
||||
if (uavo_base->flags.isMeta) {
|
||||
instance_size = MetaNumBytes;
|
||||
} else {
|
||||
/* We have a data object, augment our pointer */
|
||||
struct UAVOData * uavo = (struct UAVOData *) uavo_base;
|
||||
|
||||
instance_size = uavo->instance_size;
|
||||
}
|
||||
|
||||
return (instance_size);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -349,9 +449,24 @@ uint32_t UAVObjGetNumBytes(UAVObjHandle obj)
|
||||
* \param[in] obj The object handle
|
||||
* \return The object linked object handle
|
||||
*/
|
||||
UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj)
|
||||
UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj_handle)
|
||||
{
|
||||
return (UAVObjHandle) (((ObjectList *) obj)->linkedObj);
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
/* Recover the common object header */
|
||||
struct UAVOBase * uavo_base = (struct UAVOBase *) obj_handle;
|
||||
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
/* We have a meta object, find our containing UAVO. */
|
||||
struct UAVOData * uavo_data = container_of ((struct UAVOMeta *)uavo_base, struct UAVOData, metaObj);
|
||||
|
||||
return (UAVObjHandle) uavo_data;
|
||||
} else {
|
||||
/* We have a data object, augment our pointer */
|
||||
struct UAVOData * uavo_data = (struct UAVOData *) uavo_base;
|
||||
|
||||
return (UAVObjHandle) &(uavo_data->metaObj);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -359,13 +474,19 @@ UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj)
|
||||
* \param[in] obj The object handle
|
||||
* \return The number of instances
|
||||
*/
|
||||
uint16_t UAVObjGetNumInstances(UAVObjHandle obj)
|
||||
uint16_t UAVObjGetNumInstances(UAVObjHandle obj_handle)
|
||||
{
|
||||
uint32_t numInstances;
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
numInstances = ((ObjectList *) obj)->numInstances;
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return numInstances;
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
if (UAVObjIsSingleInstance(obj_handle)) {
|
||||
/* Only one instance is allowed */
|
||||
return 1;
|
||||
} else {
|
||||
/* Multi-instance object. Inspect the object */
|
||||
/* Augment our pointer to reflect the proper type */
|
||||
struct UAVOMulti * uavo_multi = (struct UAVOMulti *) obj_handle;
|
||||
return uavo_multi->num_instances;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -373,29 +494,37 @@ uint16_t UAVObjGetNumInstances(UAVObjHandle obj)
|
||||
* \param[in] obj The object handle
|
||||
* \return The instance ID or 0 if an error
|
||||
*/
|
||||
uint16_t UAVObjCreateInstance(UAVObjHandle obj,
|
||||
UAVObjInitializeCallback initCb)
|
||||
uint16_t UAVObjCreateInstance(UAVObjHandle obj_handle,
|
||||
UAVObjInitializeCallback initCb)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
ObjectInstList *instEntry;
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Create new instance
|
||||
objEntry = (ObjectList *) obj;
|
||||
instEntry = createInstance(objEntry, objEntry->numInstances);
|
||||
if (instEntry == NULL) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Initialize instance data
|
||||
if (initCb != NULL) {
|
||||
initCb(obj, instEntry->instId);
|
||||
}
|
||||
// Unlock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return instEntry->instId;
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
InstanceHandle instEntry;
|
||||
uint16_t instId = 0;
|
||||
|
||||
// Create new instance
|
||||
instId = UAVObjGetNumInstances(obj_handle);
|
||||
instEntry = createInstance( (struct UAVOData *)obj_handle, instId);
|
||||
if (instEntry == NULL) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
|
||||
// Initialize instance data
|
||||
if (initCb) {
|
||||
initCb(obj_handle, instId);
|
||||
}
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
|
||||
return instId;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -403,9 +532,14 @@ uint16_t UAVObjCreateInstance(UAVObjHandle obj,
|
||||
* \param[in] obj The object handle
|
||||
* \return True (1) if this is a single instance object
|
||||
*/
|
||||
int32_t UAVObjIsSingleInstance(UAVObjHandle obj)
|
||||
bool UAVObjIsSingleInstance(UAVObjHandle obj_handle)
|
||||
{
|
||||
return OLGetIsSingleInstance((ObjectList *) obj);
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
/* Recover the common object header */
|
||||
struct UAVOBase * uavo_base = (struct UAVOBase *) obj_handle;
|
||||
|
||||
return uavo_base->flags.isSingle;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -413,9 +547,14 @@ int32_t UAVObjIsSingleInstance(UAVObjHandle obj)
|
||||
* \param[in] obj The object handle
|
||||
* \return True (1) if this is metaobject
|
||||
*/
|
||||
int32_t UAVObjIsMetaobject(UAVObjHandle obj)
|
||||
bool UAVObjIsMetaobject(UAVObjHandle obj_handle)
|
||||
{
|
||||
return OLGetIsMetaobject((ObjectList *) obj);
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
/* Recover the common object header */
|
||||
struct UAVOBase * uavo_base = (struct UAVOBase *) obj_handle;
|
||||
|
||||
return uavo_base->flags.isMeta;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -423,9 +562,14 @@ int32_t UAVObjIsMetaobject(UAVObjHandle obj)
|
||||
* \param[in] obj The object handle
|
||||
* \return True (1) if this is a settings object
|
||||
*/
|
||||
int32_t UAVObjIsSettings(UAVObjHandle obj)
|
||||
bool UAVObjIsSettings(UAVObjHandle obj_handle)
|
||||
{
|
||||
return OLGetIsSettings((ObjectList *) obj);
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
/* Recover the common object header */
|
||||
struct UAVOBase * uavo_base = (struct UAVOBase *) obj_handle;
|
||||
|
||||
return uavo_base->flags.isSettings;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -435,39 +579,49 @@ int32_t UAVObjIsSettings(UAVObjHandle obj)
|
||||
* \param[in] dataIn The byte array
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjUnpack(UAVObjHandle obj, uint16_t instId,
|
||||
const uint8_t * dataIn)
|
||||
int32_t UAVObjUnpack(UAVObjHandle obj_handle, uint16_t instId,
|
||||
const uint8_t * dataIn)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
ObjectInstList *instEntry;
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Cast handle to object
|
||||
objEntry = (ObjectList *) obj;
|
||||
int32_t rc = -1;
|
||||
|
||||
// Get the instance
|
||||
instEntry = getInstance(objEntry, instId);
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
if (instId != 0) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
memcpy(MetaDataPtr((struct UAVOMeta *)obj_handle), dataIn, MetaNumBytes);
|
||||
} else {
|
||||
struct UAVOData *obj;
|
||||
InstanceHandle instEntry;
|
||||
|
||||
// If the instance does not exist create it and any other instances before it
|
||||
if (instEntry == NULL) {
|
||||
instEntry = createInstance(objEntry, instId);
|
||||
if (instEntry == NULL) {
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
// Set the data
|
||||
memcpy(instEntry->data, dataIn, objEntry->numBytes);
|
||||
// Cast handle to object
|
||||
obj = (struct UAVOData *) obj_handle;
|
||||
|
||||
// Fire event
|
||||
sendEvent(objEntry, instId, EV_UNPACKED);
|
||||
// Get the instance
|
||||
instEntry = getInstance(obj, instId);
|
||||
|
||||
// Unlock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
// If the instance does not exist create it and any other instances before it
|
||||
if (instEntry == NULL) {
|
||||
instEntry = createInstance(obj, instId);
|
||||
if (instEntry == NULL) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
}
|
||||
// Set the data
|
||||
memcpy(InstanceData(instEntry), dataIn, obj->instance_size);
|
||||
}
|
||||
|
||||
// Fire event
|
||||
sendEvent((struct UAVOBase*)obj_handle, instId, EV_UNPACKED);
|
||||
rc = 0;
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -477,30 +631,41 @@ int32_t UAVObjUnpack(UAVObjHandle obj, uint16_t instId,
|
||||
* \param[out] dataOut The byte array
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjPack(UAVObjHandle obj, uint16_t instId, uint8_t * dataOut)
|
||||
int32_t UAVObjPack(UAVObjHandle obj_handle, uint16_t instId, uint8_t * dataOut)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
ObjectInstList *instEntry;
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Cast handle to object
|
||||
objEntry = (ObjectList *) obj;
|
||||
int32_t rc = -1;
|
||||
|
||||
// Get the instance
|
||||
instEntry = getInstance(objEntry, instId);
|
||||
if (instEntry == NULL) {
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Pack data
|
||||
memcpy(dataOut, instEntry->data, objEntry->numBytes);
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
if (instId != 0) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
memcpy(dataOut, MetaDataPtr((struct UAVOMeta *)obj_handle), MetaNumBytes);
|
||||
} else {
|
||||
struct UAVOData *obj;
|
||||
InstanceHandle instEntry;
|
||||
|
||||
// Unlock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
// Cast handle to object
|
||||
obj = (struct UAVOData *) obj_handle;
|
||||
|
||||
// Get the instance
|
||||
instEntry = getInstance(obj, instId);
|
||||
if (instEntry == NULL) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
// Pack data
|
||||
memcpy(dataOut, InstanceData(instEntry), obj->instance_size);
|
||||
}
|
||||
|
||||
rc = 0;
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -512,50 +677,72 @@ int32_t UAVObjPack(UAVObjHandle obj, uint16_t instId, uint8_t * dataOut)
|
||||
* @param[in] file File to append to
|
||||
* @return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjSaveToFile(UAVObjHandle obj, uint16_t instId,
|
||||
FILEINFO * file)
|
||||
int32_t UAVObjSaveToFile(UAVObjHandle obj_handle, uint16_t instId,
|
||||
FILEINFO * file)
|
||||
{
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
#if defined(PIOS_INCLUDE_SDCARD)
|
||||
uint32_t bytesWritten;
|
||||
ObjectList *objEntry;
|
||||
ObjectInstList *instEntry;
|
||||
uint32_t bytesWritten;
|
||||
// Check for file system availability
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
return -1;
|
||||
}
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Check for file system availability
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
return -1;
|
||||
}
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
// Get the instance information
|
||||
if (instId != 0) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Write the object ID
|
||||
uint32_t objId = UAVObjGetID(obj_handle);
|
||||
PIOS_FWRITE(file, &objId, sizeof(objId),
|
||||
&bytesWritten);
|
||||
|
||||
// Cast to object
|
||||
objEntry = (ObjectList *) obj;
|
||||
// Write the data and check that the write was successful
|
||||
PIOS_FWRITE(file, MetaDataPtr((struct UAVOMeta *)obj_handle), MetaNumBytes,
|
||||
&bytesWritten);
|
||||
if (bytesWritten != MetaNumBytes) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
} else {
|
||||
struct UAVOData * uavo;
|
||||
InstanceHandle instEntry;
|
||||
|
||||
// Get the instance information
|
||||
instEntry = getInstance(objEntry, instId);
|
||||
if (instEntry == NULL) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Write the object ID
|
||||
PIOS_FWRITE(file, &objEntry->id, sizeof(objEntry->id),
|
||||
&bytesWritten);
|
||||
// Cast to object
|
||||
uavo = (struct UAVOData *) obj_handle;
|
||||
|
||||
// Write the instance ID
|
||||
if (!OLGetIsSingleInstance(objEntry)) {
|
||||
PIOS_FWRITE(file, &instEntry->instId,
|
||||
sizeof(instEntry->instId), &bytesWritten);
|
||||
}
|
||||
// Write the data and check that the write was successful
|
||||
PIOS_FWRITE(file, instEntry->data, objEntry->numBytes,
|
||||
&bytesWritten);
|
||||
if (bytesWritten != objEntry->numBytes) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
// Get the instance information
|
||||
instEntry = getInstance(uavo, instId);
|
||||
if (instEntry == NULL) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Write the object ID
|
||||
PIOS_FWRITE(file, &uavo->id, sizeof(uavo->id),
|
||||
&bytesWritten);
|
||||
|
||||
// Write the instance ID
|
||||
if (!UAVObjIsSingleInstance(obj_handle)) {
|
||||
PIOS_FWRITE(file, &instId,
|
||||
sizeof(instId), &bytesWritten);
|
||||
}
|
||||
// Write the data and check that the write was successful
|
||||
PIOS_FWRITE(file, InstanceData(instEntry), uavo->instance_size,
|
||||
&bytesWritten);
|
||||
if (bytesWritten != uavo->instance_size) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
#endif /* PIOS_INCLUDE_SDCARD */
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -568,59 +755,60 @@ int32_t UAVObjSaveToFile(UAVObjHandle obj, uint16_t instId,
|
||||
* @param[in] file File to append to
|
||||
* @return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjSave(UAVObjHandle obj, uint16_t instId)
|
||||
int32_t UAVObjSave(UAVObjHandle obj_handle, uint16_t instId)
|
||||
{
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
|
||||
ObjectList *objEntry = (ObjectList *) obj;
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
if (instId != 0)
|
||||
return -1;
|
||||
|
||||
if (objEntry == NULL)
|
||||
return -1;
|
||||
if (PIOS_FLASHFS_ObjSave(obj_handle, instId, (uint8_t*) MetaDataPtr((struct UAVOMeta *)obj_handle)) != 0)
|
||||
return -1;
|
||||
} else {
|
||||
InstanceHandle instEntry = getInstance( (struct UAVOData *)obj_handle, instId);
|
||||
|
||||
ObjectInstList *instEntry = getInstance(objEntry, instId);
|
||||
if (instEntry == NULL)
|
||||
return -1;
|
||||
|
||||
if (instEntry == NULL)
|
||||
return -1;
|
||||
if (InstanceData(instEntry) == NULL)
|
||||
return -1;
|
||||
|
||||
if (instEntry->data == NULL)
|
||||
return -1;
|
||||
|
||||
if (PIOS_FLASHFS_ObjSave(obj, instId, instEntry->data) != 0)
|
||||
return -1;
|
||||
if (PIOS_FLASHFS_ObjSave(obj_handle, instId, InstanceData(instEntry)) != 0)
|
||||
return -1;
|
||||
}
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_SDCARD)
|
||||
FILEINFO file;
|
||||
ObjectList *objEntry;
|
||||
uint8_t filename[14];
|
||||
FILEINFO file;
|
||||
uint8_t filename[14];
|
||||
|
||||
// Check for file system availability
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
return -1;
|
||||
}
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Check for file system availability
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
return -1;
|
||||
}
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Cast to object
|
||||
objEntry = (ObjectList *) obj;
|
||||
// Get filename
|
||||
objectFilename(obj_handle, filename);
|
||||
|
||||
// Get filename
|
||||
objectFilename(objEntry, filename);
|
||||
|
||||
// Open file
|
||||
if (PIOS_FOPEN_WRITE(filename, file)) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Append object
|
||||
if (UAVObjSaveToFile(obj, instId, &file) == -1) {
|
||||
PIOS_FCLOSE(file);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Done, close file and unlock
|
||||
PIOS_FCLOSE(file);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
// Open file
|
||||
if (PIOS_FOPEN_WRITE(filename, file)) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Append object
|
||||
if (UAVObjSaveToFile(obj_handle, instId, &file) == -1) {
|
||||
PIOS_FCLOSE(file);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Done, close file and unlock
|
||||
PIOS_FCLOSE(file);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
#endif /* PIOS_INCLUDE_SDCARD */
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -631,68 +819,87 @@ int32_t UAVObjSave(UAVObjHandle obj, uint16_t instId)
|
||||
UAVObjHandle UAVObjLoadFromFile(FILEINFO * file)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_SDCARD)
|
||||
uint32_t bytesRead;
|
||||
ObjectList *objEntry;
|
||||
ObjectInstList *instEntry;
|
||||
uint32_t objId;
|
||||
uint16_t instId;
|
||||
UAVObjHandle obj;
|
||||
uint32_t bytesRead;
|
||||
struct UAVOBase *objEntry;
|
||||
InstanceHandle instEntry;
|
||||
uint32_t objId;
|
||||
uint16_t instId;
|
||||
UAVObjHandle obj_handle;
|
||||
|
||||
// Check for file system availability
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
return NULL;
|
||||
}
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Check for file system availability
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
return NULL;
|
||||
}
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Read the object ID
|
||||
if (PIOS_FREAD(file, &objId, sizeof(objId), &bytesRead)) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
// Get the object
|
||||
obj = UAVObjGetByID(objId);
|
||||
if (obj == 0) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
objEntry = (ObjectList *) obj;
|
||||
// Read the object ID
|
||||
if (PIOS_FREAD(file, &objId, sizeof(objId), &bytesRead)) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
// Get the object
|
||||
obj_handle = UAVObjGetByID(objId);
|
||||
if (obj_handle == 0) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
objEntry = (struct UAVOBase *) obj_handle;
|
||||
|
||||
// Get the instance ID
|
||||
instId = 0;
|
||||
if (!OLGetIsSingleInstance(objEntry)) {
|
||||
if (PIOS_FREAD
|
||||
// Get the instance ID
|
||||
instId = 0;
|
||||
if (!UAVObjIsSingleInstance(obj_handle)) {
|
||||
if (PIOS_FREAD
|
||||
(file, &instId, sizeof(instId), &bytesRead)) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
// Get the instance information
|
||||
instEntry = getInstance(objEntry, instId);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
// If the instance does not exist create it and any other instances before it
|
||||
if (instEntry == NULL) {
|
||||
instEntry = createInstance(objEntry, instId);
|
||||
if (instEntry == NULL) {
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
// Read the instance data
|
||||
if (PIOS_FREAD
|
||||
(file, instEntry->data, objEntry->numBytes, &bytesRead)) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
// Fire event
|
||||
sendEvent(objEntry, instId, EV_UNPACKED);
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
// If the instance does not exist create it and any other instances before it
|
||||
if (instId != 0) {
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
// Read the instance data
|
||||
if (PIOS_FREAD
|
||||
(file, MetaDataPtr((struct UAVOMeta *)obj_handle), MetaNumBytes, &bytesRead)) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
} else {
|
||||
|
||||
// Unlock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return obj;
|
||||
// Get the instance information
|
||||
instEntry = getInstance((struct UAVOData *)objEntry, instId);
|
||||
|
||||
// If the instance does not exist create it and any other instances before it
|
||||
if (instEntry == NULL) {
|
||||
instEntry = createInstance((struct UAVOData *)objEntry, instId);
|
||||
if (instEntry == NULL) {
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
// Read the instance data
|
||||
if (PIOS_FREAD
|
||||
(file, InstanceData(instEntry), ((struct UAVOData *)objEntry)->instance_size, &bytesRead)) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Fire event
|
||||
sendEvent(objEntry, instId, EV_UNPACKED);
|
||||
|
||||
// Unlock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return obj_handle;
|
||||
#else /* PIOS_INCLUDE_SDCARD */
|
||||
return NULL;
|
||||
return NULL;
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -704,74 +911,74 @@ UAVObjHandle UAVObjLoadFromFile(FILEINFO * file)
|
||||
* @param[in] instId The object instance
|
||||
* @return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId)
|
||||
int32_t UAVObjLoad(UAVObjHandle obj_handle, uint16_t instId)
|
||||
{
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
|
||||
ObjectList *objEntry = (ObjectList *) obj;
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
if (instId != 0)
|
||||
return -1;
|
||||
|
||||
if (objEntry == NULL)
|
||||
return -1;
|
||||
// Fire event on success
|
||||
if (PIOS_FLASHFS_ObjLoad(obj_handle, instId, (uint8_t*) MetaDataPtr((struct UAVOMeta *)obj_handle)) == 0)
|
||||
sendEvent((struct UAVOBase*)obj_handle, instId, EV_UNPACKED);
|
||||
else
|
||||
return -1;
|
||||
} else {
|
||||
|
||||
ObjectInstList *instEntry = getInstance(objEntry, instId);
|
||||
InstanceHandle instEntry = getInstance( (struct UAVOData *)obj_handle, instId);
|
||||
|
||||
if (instEntry == NULL)
|
||||
return -1;
|
||||
if (instEntry == NULL)
|
||||
return -1;
|
||||
|
||||
if (instEntry->data == NULL)
|
||||
return -1;
|
||||
// Fire event on success
|
||||
if (PIOS_FLASHFS_ObjLoad(obj_handle, instId, InstanceData(instEntry)) == 0)
|
||||
sendEvent((struct UAVOBase*)obj_handle, instId, EV_UNPACKED);
|
||||
else
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Fire event on success
|
||||
int32_t retval;
|
||||
if ((retval = PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data)) == 0)
|
||||
sendEvent(objEntry, instId, EV_UNPACKED);
|
||||
else
|
||||
return retval;
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_SDCARD)
|
||||
FILEINFO file;
|
||||
ObjectList *objEntry;
|
||||
UAVObjHandle loadedObj;
|
||||
ObjectList *loadedObjEntry;
|
||||
uint8_t filename[14];
|
||||
FILEINFO file;
|
||||
UAVObjHandle loadedObj;
|
||||
uint8_t filename[14];
|
||||
|
||||
// Check for file system availability
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
return -1;
|
||||
}
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Check for file system availability
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
return -1;
|
||||
}
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Cast to object
|
||||
objEntry = (ObjectList *) obj;
|
||||
// Get filename
|
||||
objectFilename(obj_handle, filename);
|
||||
|
||||
// Get filename
|
||||
objectFilename(objEntry, filename);
|
||||
|
||||
// Open file
|
||||
if (PIOS_FOPEN_READ(filename, file)) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Load object
|
||||
loadedObj = UAVObjLoadFromFile(&file);
|
||||
if (loadedObj == 0) {
|
||||
PIOS_FCLOSE(file);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Check that the IDs match
|
||||
loadedObjEntry = (ObjectList *) loadedObj;
|
||||
if (loadedObjEntry->id != objEntry->id) {
|
||||
PIOS_FCLOSE(file);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Done, close file and unlock
|
||||
PIOS_FCLOSE(file);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
// Open file
|
||||
if (PIOS_FOPEN_READ(filename, file)) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Load object
|
||||
loadedObj = UAVObjLoadFromFile(&file);
|
||||
if (loadedObj == 0) {
|
||||
PIOS_FCLOSE(file);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Check that the IDs match
|
||||
if (UAVObjGetID(loadedObj) != UAVObjGetID(obj_handle)) {
|
||||
PIOS_FCLOSE(file);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Done, close file and unlock
|
||||
PIOS_FCLOSE(file);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
#endif /* PIOS_INCLUDE_SDCARD */
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -780,35 +987,32 @@ int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId)
|
||||
* @param[in] instId The object instance
|
||||
* @return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjDelete(UAVObjHandle obj, uint16_t instId)
|
||||
int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId)
|
||||
{
|
||||
PIOS_Assert(obj_handle);
|
||||
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
|
||||
PIOS_FLASHFS_ObjDelete(obj, instId);
|
||||
PIOS_FLASHFS_ObjDelete(obj_handle, instId);
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_SDCARD)
|
||||
ObjectList *objEntry;
|
||||
uint8_t filename[14];
|
||||
uint8_t filename[14];
|
||||
|
||||
// Check for file system availability
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
return -1;
|
||||
}
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Check for file system availability
|
||||
if (PIOS_SDCARD_IsMounted() == 0) {
|
||||
return -1;
|
||||
}
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Cast to object
|
||||
objEntry = (ObjectList *) obj;
|
||||
// Get filename
|
||||
objectFilename(obj_handle, filename);
|
||||
|
||||
// Get filename
|
||||
objectFilename(objEntry, filename);
|
||||
// Delete file
|
||||
PIOS_FUNLINK(filename);
|
||||
|
||||
// Delete file
|
||||
PIOS_FUNLINK(filename);
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
#endif /* PIOS_INCLUDE_SDCARD */
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -817,27 +1021,30 @@ int32_t UAVObjDelete(UAVObjHandle obj, uint16_t instId)
|
||||
*/
|
||||
int32_t UAVObjSaveSettings()
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Save all settings objects
|
||||
LL_FOREACH(objList, objEntry) {
|
||||
// Check if this is a settings object
|
||||
if (OLGetIsSettings(objEntry)) {
|
||||
// Save object
|
||||
if (UAVObjSave((UAVObjHandle) objEntry, 0) ==
|
||||
-1) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
int32_t rc = -1;
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
// Save all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
// Check if this is a settings object
|
||||
if (UAVObjIsSettings(obj)) {
|
||||
// Save object
|
||||
if (UAVObjSave((UAVObjHandle) obj, 0) ==
|
||||
-1) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
rc = 0;
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -846,27 +1053,30 @@ int32_t UAVObjSaveSettings()
|
||||
*/
|
||||
int32_t UAVObjLoadSettings()
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Load all settings objects
|
||||
LL_FOREACH(objList, objEntry) {
|
||||
// Check if this is a settings object
|
||||
if (OLGetIsSettings(objEntry)) {
|
||||
// Load object
|
||||
if (UAVObjLoad((UAVObjHandle) objEntry, 0) ==
|
||||
-1) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
int32_t rc = -1;
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
// Load all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
// Check if this is a settings object
|
||||
if (UAVObjIsSettings(obj)) {
|
||||
// Load object
|
||||
if (UAVObjLoad((UAVObjHandle) obj, 0) ==
|
||||
-1) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
rc = 0;
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -875,27 +1085,30 @@ int32_t UAVObjLoadSettings()
|
||||
*/
|
||||
int32_t UAVObjDeleteSettings()
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Save all settings objects
|
||||
LL_FOREACH(objList, objEntry) {
|
||||
// Check if this is a settings object
|
||||
if (OLGetIsSettings(objEntry)) {
|
||||
// Save object
|
||||
if (UAVObjDelete((UAVObjHandle) objEntry, 0)
|
||||
== -1) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
int32_t rc = -1;
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
// Save all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
// Check if this is a settings object
|
||||
if (UAVObjIsSettings(obj)) {
|
||||
// Save object
|
||||
if (UAVObjDelete((UAVObjHandle) obj, 0)
|
||||
== -1) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
rc = 0;
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -904,27 +1117,27 @@ int32_t UAVObjDeleteSettings()
|
||||
*/
|
||||
int32_t UAVObjSaveMetaobjects()
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Save all settings objects
|
||||
LL_FOREACH(objList, objEntry) {
|
||||
// Check if this is a settings object
|
||||
if (OLGetIsMetaobject(objEntry)) {
|
||||
// Save object
|
||||
if (UAVObjSave((UAVObjHandle) objEntry, 0) ==
|
||||
-1) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
int32_t rc = -1;
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
// Save all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
// Save object
|
||||
if (UAVObjSave( (UAVObjHandle) MetaObjectPtr(obj), 0) ==
|
||||
-1) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
}
|
||||
|
||||
rc = 0;
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -933,27 +1146,27 @@ int32_t UAVObjSaveMetaobjects()
|
||||
*/
|
||||
int32_t UAVObjLoadMetaobjects()
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Load all settings objects
|
||||
LL_FOREACH(objList, objEntry) {
|
||||
// Check if this is a settings object
|
||||
if (OLGetIsMetaobject(objEntry)) {
|
||||
// Load object
|
||||
if (UAVObjLoad((UAVObjHandle) objEntry, 0) ==
|
||||
-1) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
int32_t rc = -1;
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
// Load all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
// Load object
|
||||
if (UAVObjLoad((UAVObjHandle) MetaObjectPtr(obj), 0) ==
|
||||
-1) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
}
|
||||
|
||||
rc = 0;
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -962,253 +1175,293 @@ int32_t UAVObjLoadMetaobjects()
|
||||
*/
|
||||
int32_t UAVObjDeleteMetaobjects()
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
struct UAVOData *obj;
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Load all settings objects
|
||||
LL_FOREACH(objList, objEntry) {
|
||||
// Check if this is a settings object
|
||||
if (OLGetIsMetaobject(objEntry)) {
|
||||
// Load object
|
||||
if (UAVObjDelete((UAVObjHandle) objEntry, 0)
|
||||
== -1) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the object data
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] dataIn The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjSetData(UAVObjHandle obj, const void *dataIn)
|
||||
{
|
||||
return UAVObjSetInstanceData(obj, 0, dataIn);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the object data
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] dataIn The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjSetDataField(UAVObjHandle obj, const void* dataIn, uint32_t offset, uint32_t size)
|
||||
{
|
||||
return UAVObjSetInstanceDataField(obj, 0, dataIn, offset, size);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the object data
|
||||
* \param[in] obj The object handle
|
||||
* \param[out] dataOut The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjGetData(UAVObjHandle obj, void *dataOut)
|
||||
{
|
||||
return UAVObjGetInstanceData(obj, 0, dataOut);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the object data
|
||||
* \param[in] obj The object handle
|
||||
* \param[out] dataOut The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjGetDataField(UAVObjHandle obj, void* dataOut, uint32_t offset, uint32_t size)
|
||||
{
|
||||
return UAVObjGetInstanceDataField(obj, 0, dataOut, offset, size);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the data of a specific object instance
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] instId The object instance ID
|
||||
* \param[in] dataIn The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjSetInstanceData(UAVObjHandle obj, uint16_t instId,
|
||||
const void *dataIn)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
ObjectInstList *instEntry;
|
||||
UAVObjMetadata *mdata;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Cast to object info
|
||||
objEntry = (ObjectList *) obj;
|
||||
|
||||
// Check access level
|
||||
if (!OLGetIsMetaobject(objEntry)) {
|
||||
mdata =
|
||||
(UAVObjMetadata *) (objEntry->linkedObj->instances.
|
||||
data);
|
||||
if (UAVObjGetAccess(mdata) == ACCESS_READONLY) {
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
// Get instance information
|
||||
instEntry = getInstance(objEntry, instId);
|
||||
if (instEntry == NULL) {
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Set data
|
||||
memcpy(instEntry->data, dataIn, objEntry->numBytes);
|
||||
|
||||
// Fire event
|
||||
sendEvent(objEntry, instId, EV_UPDATED);
|
||||
|
||||
// Unlock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the data of a specific object instance
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] instId The object instance ID
|
||||
* \param[in] dataIn The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjSetInstanceDataField(UAVObjHandle obj, uint16_t instId, const void* dataIn, uint32_t offset, uint32_t size)
|
||||
{
|
||||
ObjectList* objEntry;
|
||||
ObjectInstList* instEntry;
|
||||
UAVObjMetadata* mdata;
|
||||
|
||||
// Lock
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Cast to object info
|
||||
objEntry = (ObjectList*)obj;
|
||||
int32_t rc = -1;
|
||||
|
||||
// Check access level
|
||||
if ( !OLGetIsMetaobject(objEntry) )
|
||||
{
|
||||
mdata = (UAVObjMetadata*)(objEntry->linkedObj->instances.data);
|
||||
if ( UAVObjGetAccess(mdata) == ACCESS_READONLY )
|
||||
{
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
// Load all settings objects
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
// Load object
|
||||
if (UAVObjDelete((UAVObjHandle) MetaObjectPtr(obj), 0)
|
||||
== -1) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
}
|
||||
|
||||
// Get instance information
|
||||
instEntry = getInstance(objEntry, instId);
|
||||
if ( instEntry == NULL )
|
||||
{
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
rc = 0;
|
||||
|
||||
// return if we set too much of what we have
|
||||
if ( (size + offset) > objEntry->numBytes) {
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Set data
|
||||
memcpy(instEntry->data + offset, dataIn, size);
|
||||
|
||||
// Fire event
|
||||
sendEvent(objEntry, instId, EV_UPDATED);
|
||||
|
||||
// Unlock
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the data of a specific object instance
|
||||
* Set the object data
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] instId The object instance ID
|
||||
* \param[out] dataOut The object's data structure
|
||||
* \param[in] dataIn The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjGetInstanceData(UAVObjHandle obj, uint16_t instId,
|
||||
void *dataOut)
|
||||
int32_t UAVObjSetData(UAVObjHandle obj_handle, const void *dataIn)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
ObjectInstList *instEntry;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Cast to object info
|
||||
objEntry = (ObjectList *) obj;
|
||||
|
||||
// Get instance information
|
||||
instEntry = getInstance(objEntry, instId);
|
||||
if (instEntry == NULL) {
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
// Set data
|
||||
memcpy(dataOut, instEntry->data, objEntry->numBytes);
|
||||
|
||||
// Unlock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
return UAVObjSetInstanceData(obj_handle, 0, dataIn);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the data of a specific object instance
|
||||
* Set the object data
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] dataIn The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjSetDataField(UAVObjHandle obj_handle, const void* dataIn, uint32_t offset, uint32_t size)
|
||||
{
|
||||
return UAVObjSetInstanceDataField(obj_handle, 0, dataIn, offset, size);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the object data
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] instId The object instance ID
|
||||
* \param[out] dataOut The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjGetInstanceDataField(UAVObjHandle obj, uint16_t instId, void* dataOut, uint32_t offset, uint32_t size)
|
||||
int32_t UAVObjGetData(UAVObjHandle obj_handle, void *dataOut)
|
||||
{
|
||||
ObjectList* objEntry;
|
||||
ObjectInstList* instEntry;
|
||||
return UAVObjGetInstanceData(obj_handle, 0, dataOut);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the object data
|
||||
* \param[in] obj The object handle
|
||||
* \param[out] dataOut The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjGetDataField(UAVObjHandle obj_handle, void* dataOut, uint32_t offset, uint32_t size)
|
||||
{
|
||||
return UAVObjGetInstanceDataField(obj_handle, 0, dataOut, offset, size);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the data of a specific object instance
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] instId The object instance ID
|
||||
* \param[in] dataIn The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjSetInstanceData(UAVObjHandle obj_handle, uint16_t instId,
|
||||
const void *dataIn)
|
||||
{
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Cast to object info
|
||||
objEntry = (ObjectList*)obj;
|
||||
int32_t rc = -1;
|
||||
|
||||
// Get instance information
|
||||
instEntry = getInstance(objEntry, instId);
|
||||
if ( instEntry == NULL )
|
||||
{
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
if (instId != 0) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
memcpy(MetaDataPtr((struct UAVOMeta *)obj_handle), dataIn, MetaNumBytes);
|
||||
} else {
|
||||
struct UAVOData *obj;
|
||||
InstanceHandle instEntry;
|
||||
|
||||
// Cast to object info
|
||||
obj = (struct UAVOData *) obj_handle;
|
||||
|
||||
// Check access level
|
||||
if (UAVObjReadOnly(obj_handle)) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
// Get instance information
|
||||
instEntry = getInstance(obj, instId);
|
||||
if (instEntry == NULL) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
// Set data
|
||||
memcpy(InstanceData(instEntry), dataIn, obj->instance_size);
|
||||
}
|
||||
|
||||
// return if we request too much of what we can give
|
||||
if ( (size + offset) > objEntry->numBytes)
|
||||
{
|
||||
// Error, unlock and return
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Set data
|
||||
memcpy(dataOut, instEntry->data + offset, size);
|
||||
// Fire event
|
||||
sendEvent((struct UAVOBase *)obj_handle, instId, EV_UPDATED);
|
||||
rc = 0;
|
||||
|
||||
// Unlock
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the data of a specific object instance
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] instId The object instance ID
|
||||
* \param[in] dataIn The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjSetInstanceDataField(UAVObjHandle obj_handle, uint16_t instId, const void* dataIn, uint32_t offset, uint32_t size)
|
||||
{
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
int32_t rc = -1;
|
||||
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
// Get instance information
|
||||
if (instId != 0) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
|
||||
// Check for overrun
|
||||
if ((size + offset) > MetaNumBytes) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
|
||||
// Set data
|
||||
memcpy(MetaDataPtr((struct UAVOMeta *)obj_handle) + offset, dataIn, size);
|
||||
} else {
|
||||
struct UAVOData * obj;
|
||||
InstanceHandle instEntry;
|
||||
|
||||
// Cast to object info
|
||||
obj = (struct UAVOData *)obj_handle;
|
||||
|
||||
// Check access level
|
||||
if (UAVObjReadOnly(obj_handle)) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
|
||||
// Get instance information
|
||||
instEntry = getInstance(obj, instId);
|
||||
if (instEntry == NULL) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
|
||||
// Check for overrun
|
||||
if ((size + offset) > obj->instance_size) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
|
||||
// Set data
|
||||
memcpy(InstanceData(instEntry) + offset, dataIn, size);
|
||||
}
|
||||
|
||||
|
||||
// Fire event
|
||||
sendEvent((struct UAVOBase *)obj_handle, instId, EV_UPDATED);
|
||||
rc = 0;
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the data of a specific object instance
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] instId The object instance ID
|
||||
* \param[out] dataOut The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjGetInstanceData(UAVObjHandle obj_handle, uint16_t instId,
|
||||
void *dataOut)
|
||||
{
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
int32_t rc = -1;
|
||||
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
// Get instance information
|
||||
if (instId != 0) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
// Set data
|
||||
memcpy(dataOut, MetaDataPtr((struct UAVOMeta *)obj_handle), MetaNumBytes);
|
||||
} else {
|
||||
struct UAVOData *obj;
|
||||
InstanceHandle instEntry;
|
||||
|
||||
// Cast to object info
|
||||
obj = (struct UAVOData *) obj_handle;
|
||||
|
||||
// Get instance information
|
||||
instEntry = getInstance(obj, instId);
|
||||
if (instEntry == NULL) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
// Set data
|
||||
memcpy(dataOut, InstanceData(instEntry), obj->instance_size);
|
||||
}
|
||||
|
||||
rc = 0;
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the data of a specific object instance
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] instId The object instance ID
|
||||
* \param[out] dataOut The object's data structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjGetInstanceDataField(UAVObjHandle obj_handle, uint16_t instId, void* dataOut, uint32_t offset, uint32_t size)
|
||||
{
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
int32_t rc = -1;
|
||||
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
// Get instance information
|
||||
if (instId != 0) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
|
||||
// Check for overrun
|
||||
if ((size + offset) > MetaNumBytes) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
|
||||
// Set data
|
||||
memcpy(dataOut, MetaDataPtr((struct UAVOMeta *)obj_handle) + offset, size);
|
||||
} else {
|
||||
struct UAVOData * obj;
|
||||
InstanceHandle instEntry;
|
||||
|
||||
// Cast to object info
|
||||
obj = (struct UAVOData *)obj_handle;
|
||||
|
||||
// Get instance information
|
||||
instEntry = getInstance(obj, instId);
|
||||
if (instEntry == NULL) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
|
||||
// Check for overrun
|
||||
if ((size + offset) > obj->instance_size) {
|
||||
goto unlock_exit;
|
||||
}
|
||||
|
||||
// Set data
|
||||
memcpy(dataOut, InstanceData(instEntry) + offset, size);
|
||||
}
|
||||
|
||||
rc = 0;
|
||||
|
||||
unlock_exit:
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1217,25 +1470,21 @@ int32_t UAVObjGetInstanceDataField(UAVObjHandle obj, uint16_t instId, void* data
|
||||
* \param[in] dataIn The object's metadata structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata * dataIn)
|
||||
int32_t UAVObjSetMetadata(UAVObjHandle obj_handle, const UAVObjMetadata * dataIn)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Set metadata (metadata of metaobjects can not be modified)
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Set metadata (metadata of metaobjects can not be modified)
|
||||
objEntry = (ObjectList *) obj;
|
||||
if (!OLGetIsMetaobject(objEntry)) {
|
||||
UAVObjSetData((UAVObjHandle) objEntry->linkedObj,
|
||||
dataIn);
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Unlock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
UAVObjSetData((UAVObjHandle) MetaObjectPtr((struct UAVOData *)obj_handle), dataIn);
|
||||
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1244,44 +1493,29 @@ int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata * dataIn)
|
||||
* \param[out] dataOut The object's metadata structure
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata * dataOut)
|
||||
int32_t UAVObjGetMetadata(UAVObjHandle obj_handle, UAVObjMetadata * dataOut)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Get metadata
|
||||
objEntry = (ObjectList *) obj;
|
||||
if (OLGetIsMetaobject(objEntry)) {
|
||||
memcpy(dataOut, &defMetadata, sizeof(UAVObjMetadata));
|
||||
} else {
|
||||
UAVObjGetData((UAVObjHandle) objEntry->linkedObj,
|
||||
dataOut);
|
||||
}
|
||||
// Get metadata
|
||||
if (UAVObjIsMetaobject(obj_handle)) {
|
||||
memcpy(dataOut, &defMetadata, sizeof(UAVObjMetadata));
|
||||
} else {
|
||||
UAVObjGetData((UAVObjHandle) MetaObjectPtr( (struct UAVOData *)obj_handle ),
|
||||
dataOut);
|
||||
}
|
||||
|
||||
// Unlock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
// Unlock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize a UAVObjMetadata object.
|
||||
* \param[in] metadata The metadata object
|
||||
*/
|
||||
void UAVObjMetadataInitialize(UAVObjMetadata* metadata)
|
||||
{
|
||||
metadata->flags =
|
||||
ACCESS_READWRITE << UAVOBJ_ACCESS_SHIFT |
|
||||
ACCESS_READWRITE << UAVOBJ_GCS_ACCESS_SHIFT |
|
||||
1 << UAVOBJ_TELEMETRY_ACKED_SHIFT |
|
||||
1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT |
|
||||
UPDATEMODE_ONCHANGE << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT |
|
||||
UPDATEMODE_ONCHANGE << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT;
|
||||
metadata->telemetryUpdatePeriod = 0;
|
||||
metadata->gcsTelemetryUpdatePeriod = 0;
|
||||
metadata->loggingUpdatePeriod = 0;
|
||||
}
|
||||
/*******************************
|
||||
* Object Metadata Manipulation
|
||||
******************************/
|
||||
|
||||
/**
|
||||
* Get the UAVObject metadata access member
|
||||
@ -1290,6 +1524,7 @@ void UAVObjMetadataInitialize(UAVObjMetadata* metadata)
|
||||
*/
|
||||
UAVObjAccessType UAVObjGetAccess(const UAVObjMetadata* metadata)
|
||||
{
|
||||
PIOS_Assert(metadata);
|
||||
return (metadata->flags >> UAVOBJ_ACCESS_SHIFT) & 1;
|
||||
}
|
||||
|
||||
@ -1300,6 +1535,7 @@ UAVObjAccessType UAVObjGetAccess(const UAVObjMetadata* metadata)
|
||||
*/
|
||||
void UAVObjSetAccess(UAVObjMetadata* metadata, UAVObjAccessType mode)
|
||||
{
|
||||
PIOS_Assert(metadata);
|
||||
SET_BITS(metadata->flags, UAVOBJ_ACCESS_SHIFT, mode, 1);
|
||||
}
|
||||
|
||||
@ -1310,6 +1546,7 @@ void UAVObjSetAccess(UAVObjMetadata* metadata, UAVObjAccessType mode)
|
||||
*/
|
||||
UAVObjAccessType UAVObjGetGcsAccess(const UAVObjMetadata* metadata)
|
||||
{
|
||||
PIOS_Assert(metadata);
|
||||
return (metadata->flags >> UAVOBJ_GCS_ACCESS_SHIFT) & 1;
|
||||
}
|
||||
|
||||
@ -1319,6 +1556,7 @@ UAVObjAccessType UAVObjGetGcsAccess(const UAVObjMetadata* metadata)
|
||||
* \param[in] mode The access mode
|
||||
*/
|
||||
void UAVObjSetGcsAccess(UAVObjMetadata* metadata, UAVObjAccessType mode) {
|
||||
PIOS_Assert(metadata);
|
||||
SET_BITS(metadata->flags, UAVOBJ_GCS_ACCESS_SHIFT, mode, 1);
|
||||
}
|
||||
|
||||
@ -1328,6 +1566,7 @@ void UAVObjSetGcsAccess(UAVObjMetadata* metadata, UAVObjAccessType mode) {
|
||||
* \return the telemetry acked boolean
|
||||
*/
|
||||
uint8_t UAVObjGetTelemetryAcked(const UAVObjMetadata* metadata) {
|
||||
PIOS_Assert(metadata);
|
||||
return (metadata->flags >> UAVOBJ_TELEMETRY_ACKED_SHIFT) & 1;
|
||||
}
|
||||
|
||||
@ -1337,6 +1576,7 @@ uint8_t UAVObjGetTelemetryAcked(const UAVObjMetadata* metadata) {
|
||||
* \param[in] val The telemetry acked boolean
|
||||
*/
|
||||
void UAVObjSetTelemetryAcked(UAVObjMetadata* metadata, uint8_t val) {
|
||||
PIOS_Assert(metadata);
|
||||
SET_BITS(metadata->flags, UAVOBJ_TELEMETRY_ACKED_SHIFT, val, 1);
|
||||
}
|
||||
|
||||
@ -1346,6 +1586,7 @@ void UAVObjSetTelemetryAcked(UAVObjMetadata* metadata, uint8_t val) {
|
||||
* \return the telemetry acked boolean
|
||||
*/
|
||||
uint8_t UAVObjGetGcsTelemetryAcked(const UAVObjMetadata* metadata) {
|
||||
PIOS_Assert(metadata);
|
||||
return (metadata->flags >> UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT) & 1;
|
||||
}
|
||||
|
||||
@ -1355,6 +1596,7 @@ uint8_t UAVObjGetGcsTelemetryAcked(const UAVObjMetadata* metadata) {
|
||||
* \param[in] val The GCS telemetry acked boolean
|
||||
*/
|
||||
void UAVObjSetGcsTelemetryAcked(UAVObjMetadata* metadata, uint8_t val) {
|
||||
PIOS_Assert(metadata);
|
||||
SET_BITS(metadata->flags, UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT, val, 1);
|
||||
}
|
||||
|
||||
@ -1364,6 +1606,7 @@ void UAVObjSetGcsTelemetryAcked(UAVObjMetadata* metadata, uint8_t val) {
|
||||
* \return the telemetry update mode
|
||||
*/
|
||||
UAVObjUpdateMode UAVObjGetTelemetryUpdateMode(const UAVObjMetadata* metadata) {
|
||||
PIOS_Assert(metadata);
|
||||
return (metadata->flags >> UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK;
|
||||
}
|
||||
|
||||
@ -1373,6 +1616,7 @@ UAVObjUpdateMode UAVObjGetTelemetryUpdateMode(const UAVObjMetadata* metadata) {
|
||||
* \param[in] val The telemetry update mode
|
||||
*/
|
||||
void UAVObjSetTelemetryUpdateMode(UAVObjMetadata* metadata, UAVObjUpdateMode val) {
|
||||
PIOS_Assert(metadata);
|
||||
SET_BITS(metadata->flags, UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT, val, UAVOBJ_UPDATE_MODE_MASK);
|
||||
}
|
||||
|
||||
@ -1382,6 +1626,7 @@ void UAVObjSetTelemetryUpdateMode(UAVObjMetadata* metadata, UAVObjUpdateMode val
|
||||
* \return the GCS telemetry update mode
|
||||
*/
|
||||
UAVObjUpdateMode UAVObjGetGcsTelemetryUpdateMode(const UAVObjMetadata* metadata) {
|
||||
PIOS_Assert(metadata);
|
||||
return (metadata->flags >> UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK;
|
||||
}
|
||||
|
||||
@ -1391,6 +1636,7 @@ UAVObjUpdateMode UAVObjGetGcsTelemetryUpdateMode(const UAVObjMetadata* metadata)
|
||||
* \param[in] val The GCS telemetry update mode
|
||||
*/
|
||||
void UAVObjSetGcsTelemetryUpdateMode(UAVObjMetadata* metadata, UAVObjUpdateMode val) {
|
||||
PIOS_Assert(metadata);
|
||||
SET_BITS(metadata->flags, UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT, val, UAVOBJ_UPDATE_MODE_MASK);
|
||||
}
|
||||
|
||||
@ -1403,22 +1649,13 @@ void UAVObjSetGcsTelemetryUpdateMode(UAVObjMetadata* metadata, UAVObjUpdateMode
|
||||
* \arg 1 if read only
|
||||
* \arg -1 if unable to get meta data
|
||||
*/
|
||||
int8_t UAVObjReadOnly(UAVObjHandle obj)
|
||||
int8_t UAVObjReadOnly(UAVObjHandle obj_handle)
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
UAVObjMetadata *mdata;
|
||||
|
||||
// Cast to object info
|
||||
objEntry = (ObjectList *) obj;
|
||||
|
||||
// Check access level
|
||||
if (!OLGetIsMetaobject(objEntry)) {
|
||||
mdata =
|
||||
(UAVObjMetadata *) (objEntry->linkedObj->instances.
|
||||
data);
|
||||
return UAVObjGetAccess(mdata) == ACCESS_READONLY;
|
||||
}
|
||||
return -1;
|
||||
PIOS_Assert(obj_handle);
|
||||
if (!UAVObjIsMetaobject(obj_handle)) {
|
||||
return UAVObjGetAccess(LinkedMetaDataPtr( (struct UAVOData *)obj_handle)) == ACCESS_READONLY;
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1429,14 +1666,16 @@ int8_t UAVObjReadOnly(UAVObjHandle obj)
|
||||
* \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL)
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue,
|
||||
uint8_t eventMask)
|
||||
int32_t UAVObjConnectQueue(UAVObjHandle obj_handle, xQueueHandle queue,
|
||||
uint8_t eventMask)
|
||||
{
|
||||
int32_t res;
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
res = connectObj(obj, queue, 0, eventMask);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return res;
|
||||
PIOS_Assert(obj_handle);
|
||||
PIOS_Assert(queue);
|
||||
int32_t res;
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
res = connectObj(obj_handle, queue, 0, eventMask);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1445,13 +1684,15 @@ int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue,
|
||||
* \param[in] queue The event queue
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue)
|
||||
int32_t UAVObjDisconnectQueue(UAVObjHandle obj_handle, xQueueHandle queue)
|
||||
{
|
||||
int32_t res;
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
res = disconnectObj(obj, queue, 0);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return res;
|
||||
PIOS_Assert(obj_handle);
|
||||
PIOS_Assert(queue);
|
||||
int32_t res;
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
res = disconnectObj(obj_handle, queue, 0);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1462,14 +1703,15 @@ int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue)
|
||||
* \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL)
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb,
|
||||
uint8_t eventMask)
|
||||
int32_t UAVObjConnectCallback(UAVObjHandle obj_handle, UAVObjEventCallback cb,
|
||||
uint8_t eventMask)
|
||||
{
|
||||
int32_t res;
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
res = connectObj(obj, 0, cb, eventMask);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return res;
|
||||
PIOS_Assert(obj_handle);
|
||||
int32_t res;
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
res = connectObj(obj_handle, 0, cb, eventMask);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1478,13 +1720,14 @@ int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb,
|
||||
* \param[in] cb The event callback
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
int32_t UAVObjDisconnectCallback(UAVObjHandle obj, UAVObjEventCallback cb)
|
||||
int32_t UAVObjDisconnectCallback(UAVObjHandle obj_handle, UAVObjEventCallback cb)
|
||||
{
|
||||
int32_t res;
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
res = disconnectObj(obj, 0, cb);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return res;
|
||||
PIOS_Assert(obj_handle);
|
||||
int32_t res;
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
res = disconnectObj(obj_handle, 0, cb);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1492,9 +1735,9 @@ int32_t UAVObjDisconnectCallback(UAVObjHandle obj, UAVObjEventCallback cb)
|
||||
* will be generated as soon as the object is updated.
|
||||
* \param[in] obj The object handle
|
||||
*/
|
||||
void UAVObjRequestUpdate(UAVObjHandle obj)
|
||||
void UAVObjRequestUpdate(UAVObjHandle obj_handle)
|
||||
{
|
||||
UAVObjRequestInstanceUpdate(obj, UAVOBJ_ALL_INSTANCES);
|
||||
UAVObjRequestInstanceUpdate(obj_handle, UAVOBJ_ALL_INSTANCES);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1503,20 +1746,21 @@ void UAVObjRequestUpdate(UAVObjHandle obj)
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] instId Object instance ID to update
|
||||
*/
|
||||
void UAVObjRequestInstanceUpdate(UAVObjHandle obj, uint16_t instId)
|
||||
void UAVObjRequestInstanceUpdate(UAVObjHandle obj_handle, uint16_t instId)
|
||||
{
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
sendEvent((ObjectList *) obj, instId, EV_UPDATE_REQ);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
PIOS_Assert(obj_handle);
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
sendEvent((struct UAVOBase *) obj_handle, instId, EV_UPDATE_REQ);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
}
|
||||
|
||||
/**
|
||||
* Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object).
|
||||
* \param[in] obj The object handle
|
||||
*/
|
||||
void UAVObjUpdated(UAVObjHandle obj)
|
||||
void UAVObjUpdated(UAVObjHandle obj_handle)
|
||||
{
|
||||
UAVObjInstanceUpdated(obj, UAVOBJ_ALL_INSTANCES);
|
||||
UAVObjInstanceUpdated(obj_handle, UAVOBJ_ALL_INSTANCES);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1524,11 +1768,12 @@ void UAVObjUpdated(UAVObjHandle obj)
|
||||
* \param[in] obj The object handle
|
||||
* \param[in] instId The object instance ID
|
||||
*/
|
||||
void UAVObjInstanceUpdated(UAVObjHandle obj, uint16_t instId)
|
||||
void UAVObjInstanceUpdated(UAVObjHandle obj_handle, uint16_t instId)
|
||||
{
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
sendEvent((ObjectList *) obj, instId, EV_UPDATED_MANUAL);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
PIOS_Assert(obj_handle);
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
sendEvent((struct UAVOBase *) obj_handle, instId, EV_UPDATED_MANUAL);
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1538,133 +1783,152 @@ void UAVObjInstanceUpdated(UAVObjHandle obj, uint16_t instId)
|
||||
*/
|
||||
void UAVObjIterate(void (*iterator) (UAVObjHandle obj))
|
||||
{
|
||||
ObjectList *objEntry;
|
||||
PIOS_Assert(iterator);
|
||||
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
// Get lock
|
||||
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
|
||||
|
||||
// Iterate through the list and invoke iterator for each object
|
||||
LL_FOREACH(objList, objEntry) {
|
||||
(*iterator) ((UAVObjHandle) objEntry);
|
||||
}
|
||||
// Iterate through the list and invoke iterator for each object
|
||||
struct UAVOData *obj;
|
||||
LL_FOREACH(uavo_list, obj) {
|
||||
(*iterator) ((UAVObjHandle) obj);
|
||||
(*iterator) ((UAVObjHandle) &obj->metaObj);
|
||||
}
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(mutex);
|
||||
}
|
||||
|
||||
/**
|
||||
* Send an event to all event queues registered on the object.
|
||||
* Send a triggered event to all event queues registered on the object.
|
||||
*/
|
||||
static int32_t sendEvent(ObjectList * obj, uint16_t instId,
|
||||
UAVObjEventType event)
|
||||
static int32_t sendEvent(struct UAVOBase * obj, uint16_t instId,
|
||||
UAVObjEventType triggered_event)
|
||||
{
|
||||
ObjectEventList *eventEntry;
|
||||
UAVObjEvent msg;
|
||||
/* Set up the message that will be sent to all registered listeners */
|
||||
UAVObjEvent msg = {
|
||||
.obj = (UAVObjHandle) obj,
|
||||
.event = triggered_event,
|
||||
.instId = instId,
|
||||
};
|
||||
|
||||
// Setup event
|
||||
msg.obj = (UAVObjHandle) obj;
|
||||
msg.event = event;
|
||||
msg.instId = instId;
|
||||
// Go through each object and push the event message in the queue (if event is activated for the queue)
|
||||
struct ObjectEventEntry *event;
|
||||
LL_FOREACH(obj->next_event, event) {
|
||||
if (event->eventMask == 0
|
||||
|| (event->eventMask & triggered_event) != 0) {
|
||||
// Send to queue if a valid queue is registered
|
||||
if (event->queue) {
|
||||
// will not block
|
||||
if (xQueueSend(event->queue, &msg, 0) != pdTRUE) {
|
||||
stats.lastQueueErrorID = UAVObjGetID(obj);
|
||||
++stats.eventQueueErrors;
|
||||
}
|
||||
}
|
||||
|
||||
// Go through each object and push the event message in the queue (if event is activated for the queue)
|
||||
LL_FOREACH(obj->events, eventEntry) {
|
||||
if (eventEntry->eventMask == 0
|
||||
|| (eventEntry->eventMask & event) != 0) {
|
||||
// Send to queue if a valid queue is registered
|
||||
if (eventEntry->queue != 0) {
|
||||
if (xQueueSend(eventEntry->queue, &msg, 0) != pdTRUE) // will not block
|
||||
{
|
||||
stats.lastQueueErrorID = UAVObjGetID(obj);
|
||||
++stats.eventQueueErrors;
|
||||
}
|
||||
}
|
||||
// Invoke callback (from event task) if a valid one is registered
|
||||
if (eventEntry->cb != 0) {
|
||||
if (EventCallbackDispatch(&msg, eventEntry->cb) != pdTRUE) // invoke callback from the event task, will not block
|
||||
{
|
||||
++stats.eventCallbackErrors;
|
||||
stats.lastCallbackErrorID = UAVObjGetID(obj);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
// Invoke callback (from event task) if a valid one is registered
|
||||
if (event->cb) {
|
||||
// invoke callback from the event task, will not block
|
||||
if (EventCallbackDispatch(&msg, event->cb) != pdTRUE) {
|
||||
++stats.eventCallbackErrors;
|
||||
stats.lastCallbackErrorID = UAVObjGetID(obj);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Done
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Create a new object instance, return the instance info or NULL if failure.
|
||||
*/
|
||||
static ObjectInstList *createInstance(ObjectList * obj, uint16_t instId)
|
||||
static InstanceHandle createInstance(struct UAVOData * obj, uint16_t instId)
|
||||
{
|
||||
ObjectInstList *instEntry;
|
||||
int32_t n;
|
||||
struct UAVOMultiInst *instEntry;
|
||||
|
||||
// For single instance objects, only instance zero is allowed
|
||||
if (OLGetIsSingleInstance(obj) && instId != 0) {
|
||||
return NULL;
|
||||
}
|
||||
// Make sure that the instance ID is within limits
|
||||
if (instId >= UAVOBJ_MAX_INSTANCES) {
|
||||
return NULL;
|
||||
}
|
||||
// Check if the instance already exists
|
||||
if (getInstance(obj, instId) != NULL) {
|
||||
return NULL;
|
||||
}
|
||||
// Create any missing instances (all instance IDs must be sequential)
|
||||
for (n = obj->numInstances; n < instId; ++n) {
|
||||
if (createInstance(obj, n) == NULL) {
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
/* Don't allow more than one instance for single instance objects */
|
||||
if (UAVObjIsSingleInstance(&(obj->base))) {
|
||||
PIOS_Assert(0);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
if (instId == 0) { /* Instance 0 ObjectInstList allocated with ObjectList element */
|
||||
instEntry = &obj->instances;
|
||||
instEntry->data = pvPortMalloc(obj->numBytes);
|
||||
if (instEntry->data == NULL)
|
||||
return NULL;
|
||||
memset(instEntry->data, 0, obj->numBytes);
|
||||
instEntry->instId = instId;
|
||||
} else {
|
||||
// Create the actual instance
|
||||
instEntry =
|
||||
(ObjectInstList *)
|
||||
pvPortMalloc(sizeof(ObjectInstList));
|
||||
if (instEntry == NULL)
|
||||
return NULL;
|
||||
instEntry->data = pvPortMalloc(obj->numBytes);
|
||||
if (instEntry->data == NULL)
|
||||
return NULL;
|
||||
memset(instEntry->data, 0, obj->numBytes);
|
||||
instEntry->instId = instId;
|
||||
LL_APPEND(obj->instances.next, instEntry);
|
||||
}
|
||||
++obj->numInstances;
|
||||
/* Don't create more than the allowed number of instances */
|
||||
if (instId >= UAVOBJ_MAX_INSTANCES) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// Fire event
|
||||
UAVObjInstanceUpdated((UAVObjHandle) obj, instId);
|
||||
/* Don't allow duplicate instances */
|
||||
if (instId < UAVObjGetNumInstances(&(obj->base))) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// Done
|
||||
return instEntry;
|
||||
// Create any missing instances (all instance IDs must be sequential)
|
||||
for (uint16_t n = UAVObjGetNumInstances(&(obj->base)); n < instId; ++n) {
|
||||
if (createInstance(obj, n) == NULL) {
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
/* Create the actual instance */
|
||||
instEntry = (struct UAVOMultiInst *) pvPortMalloc(sizeof(struct UAVOMultiInst)+obj->instance_size);
|
||||
if (!instEntry)
|
||||
return NULL;
|
||||
memset(InstanceDataOffset(instEntry), 0, obj->instance_size);
|
||||
LL_APPEND(( (struct UAVOMulti*)obj )->instance0.next, instEntry);
|
||||
|
||||
( (struct UAVOMulti*)obj )->num_instances++;
|
||||
|
||||
// Fire event
|
||||
UAVObjInstanceUpdated((UAVObjHandle) obj, instId);
|
||||
|
||||
// Done
|
||||
return InstanceDataOffset(instEntry);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the instance information or NULL if the instance does not exist
|
||||
*/
|
||||
static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId)
|
||||
static InstanceHandle getInstance(struct UAVOData * obj, uint16_t instId)
|
||||
{
|
||||
ObjectInstList *instEntry;
|
||||
if (UAVObjIsMetaobject(&obj->base)) {
|
||||
/* Metadata Instance */
|
||||
|
||||
// Look for specified instance ID
|
||||
LL_FOREACH(&(obj->instances), instEntry) {
|
||||
if (instEntry->instId == instId) {
|
||||
return instEntry;
|
||||
}
|
||||
}
|
||||
// If this point is reached then instance id was not found
|
||||
return NULL;
|
||||
if (instId != 0)
|
||||
return NULL;
|
||||
|
||||
/* Augment our pointer to reflect the proper type */
|
||||
struct UAVOMeta * uavo_meta = (struct UAVOMeta *) obj;
|
||||
return (&(uavo_meta->instance0));
|
||||
|
||||
} else if (UAVObjIsSingleInstance(&(obj->base))) {
|
||||
/* Single Instance */
|
||||
|
||||
if (instId != 0)
|
||||
return NULL;
|
||||
|
||||
/* Augment our pointer to reflect the proper type */
|
||||
struct UAVOSingle * uavo_single = (struct UAVOSingle *) obj;
|
||||
return (&(uavo_single->instance0));
|
||||
} else {
|
||||
/* Multi Instance */
|
||||
/* Augment our pointer to reflect the proper type */
|
||||
struct UAVOMulti * uavo_multi = (struct UAVOMulti *) obj;
|
||||
if (instId >= uavo_multi->num_instances)
|
||||
return NULL;
|
||||
|
||||
// Look for specified instance ID
|
||||
uint16_t instance = 0;
|
||||
struct UAVOMultiInst *instEntry;
|
||||
LL_FOREACH(&(uavo_multi->instance0), instEntry) {
|
||||
if (instance++ == instId) {
|
||||
/* Found it */
|
||||
return &(instEntry->instance);
|
||||
}
|
||||
}
|
||||
/* Instance was not found */
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1675,35 +1939,34 @@ static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId)
|
||||
* \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL)
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue,
|
||||
UAVObjEventCallback cb, uint8_t eventMask)
|
||||
static int32_t connectObj(UAVObjHandle obj_handle, xQueueHandle queue,
|
||||
UAVObjEventCallback cb, uint8_t eventMask)
|
||||
{
|
||||
ObjectEventList *eventEntry;
|
||||
ObjectList *objEntry;
|
||||
struct ObjectEventEntry *event;
|
||||
struct UAVOBase *obj;
|
||||
|
||||
// Check that the queue is not already connected, if it is simply update event mask
|
||||
objEntry = (ObjectList *) obj;
|
||||
LL_FOREACH(objEntry->events, eventEntry) {
|
||||
if (eventEntry->queue == queue && eventEntry->cb == cb) {
|
||||
// Already connected, update event mask and return
|
||||
eventEntry->eventMask = eventMask;
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
// Check that the queue is not already connected, if it is simply update event mask
|
||||
obj = (struct UAVOBase *) obj_handle;
|
||||
LL_FOREACH(obj->next_event, event) {
|
||||
if (event->queue == queue && event->cb == cb) {
|
||||
// Already connected, update event mask and return
|
||||
event->eventMask = eventMask;
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
// Add queue to list
|
||||
eventEntry =
|
||||
(ObjectEventList *) pvPortMalloc(sizeof(ObjectEventList));
|
||||
if (eventEntry == NULL) {
|
||||
return -1;
|
||||
}
|
||||
eventEntry->queue = queue;
|
||||
eventEntry->cb = cb;
|
||||
eventEntry->eventMask = eventMask;
|
||||
LL_APPEND(objEntry->events, eventEntry);
|
||||
// Add queue to list
|
||||
event = (struct ObjectEventEntry *) pvPortMalloc(sizeof(struct ObjectEventEntry));
|
||||
if (event == NULL) {
|
||||
return -1;
|
||||
}
|
||||
event->queue = queue;
|
||||
event->cb = cb;
|
||||
event->eventMask = eventMask;
|
||||
LL_APPEND(obj->next_event, event);
|
||||
|
||||
// Done
|
||||
return 0;
|
||||
// Done
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1713,25 +1976,25 @@ static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue,
|
||||
* \param[in] cb The event callback
|
||||
* \return 0 if success or -1 if failure
|
||||
*/
|
||||
static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue,
|
||||
UAVObjEventCallback cb)
|
||||
static int32_t disconnectObj(UAVObjHandle obj_handle, xQueueHandle queue,
|
||||
UAVObjEventCallback cb)
|
||||
{
|
||||
ObjectEventList *eventEntry;
|
||||
ObjectList *objEntry;
|
||||
struct ObjectEventEntry *event;
|
||||
struct UAVOBase *obj;
|
||||
|
||||
// Find queue and remove it
|
||||
objEntry = (ObjectList *) obj;
|
||||
LL_FOREACH(objEntry->events, eventEntry) {
|
||||
if ((eventEntry->queue == queue
|
||||
&& eventEntry->cb == cb)) {
|
||||
LL_DELETE(objEntry->events, eventEntry);
|
||||
vPortFree(eventEntry);
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
// Find queue and remove it
|
||||
obj = (struct UAVOBase *) obj_handle;
|
||||
LL_FOREACH(obj->next_event, event) {
|
||||
if ((event->queue == queue
|
||||
&& event->cb == cb)) {
|
||||
LL_DELETE(obj->next_event, event);
|
||||
vPortFree(event);
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
// If this point is reached the queue was not found
|
||||
return -1;
|
||||
// If this point is reached the queue was not found
|
||||
return -1;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_SDCARD)
|
||||
@ -1740,16 +2003,16 @@ static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue,
|
||||
*/
|
||||
static void customSPrintf(uint8_t * buffer, uint8_t * format, ...)
|
||||
{
|
||||
va_list args;
|
||||
va_start(args, format);
|
||||
vsprintf((char *)buffer, (char *)format, args);
|
||||
va_list args;
|
||||
va_start(args, format);
|
||||
vsprintf((char *)buffer, (char *)format, args);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get an 8 character (plus extension) filename for the object.
|
||||
*/
|
||||
static void objectFilename(ObjectList * obj, uint8_t * filename)
|
||||
static void objectFilename(UAVObjHandle obj_handle, uint8_t * filename)
|
||||
{
|
||||
customSPrintf(filename, (uint8_t *) "%X.obj", obj->id);
|
||||
customSPrintf(filename, (uint8_t *) "%X.obj", UAVObjGetID(obj_handle));
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SDCARD */
|
||||
|
@ -54,7 +54,7 @@ int32_t $(NAME)Initialize(void)
|
||||
return -2;
|
||||
|
||||
// Register object with the object manager
|
||||
handle = UAVObjRegister($(NAMEUC)_OBJID, $(NAMEUC)_NAME, $(NAMEUC)_METANAME, 0,
|
||||
handle = UAVObjRegister($(NAMEUC)_OBJID,
|
||||
$(NAMEUC)_ISSINGLEINST, $(NAMEUC)_ISSETTINGS, $(NAMEUC)_NUMBYTES, &$(NAME)SetDefaults);
|
||||
|
||||
// Done
|
||||
|
@ -132,16 +132,11 @@ ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent)
|
||||
|
||||
}
|
||||
|
||||
m_ccpm->PitchCurve->setMin(-1);
|
||||
|
||||
resetMixer(m_ccpm->PitchCurve, 5);
|
||||
resetMixer(m_ccpm->ThrottleCurve, 5);
|
||||
|
||||
MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager());
|
||||
Q_ASSERT(mixerSettings);
|
||||
UAVObjectField * curve2source = mixerSettings->getField("Curve2Source");
|
||||
Q_ASSERT(curve2source);
|
||||
//initialize our two mixer curves
|
||||
m_ccpm->PitchCurve->initLinearCurve(5, 1.0, -1.0);
|
||||
m_ccpm->ThrottleCurve->initLinearCurve(5, 1.0);
|
||||
|
||||
//initialize channel names
|
||||
m_ccpm->ccpmEngineChannel->addItems(channelNames);
|
||||
m_ccpm->ccpmEngineChannel->setCurrentIndex(0);
|
||||
m_ccpm->ccpmTailChannel->addItems(channelNames);
|
||||
@ -474,14 +469,6 @@ void ConfigCcpmWidget::UpdateType()
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
Resets a mixer curve
|
||||
*/
|
||||
void ConfigCcpmWidget::resetMixer(MixerCurveWidget *mixer, int numElements)
|
||||
{
|
||||
mixer->initLinearCurve(numElements,(double)1);
|
||||
}
|
||||
|
||||
void ConfigCcpmWidget::UpdateCurveWidgets()
|
||||
{
|
||||
int NumCurvePoints,i,Changed;
|
||||
@ -501,7 +488,8 @@ void ConfigCcpmWidget::UpdateCurveWidgets()
|
||||
if (ThisValue!=OldCurveValues.at(i))Changed=1;
|
||||
}
|
||||
// Setup all Throttle1 curves for all types of airframes
|
||||
if (Changed==1)m_ccpm->ThrottleCurve->setCurve(curveValues);
|
||||
if (Changed==1)
|
||||
m_ccpm->ThrottleCurve->setCurve(&curveValues);
|
||||
|
||||
curveValues.clear();
|
||||
Changed=0;
|
||||
@ -513,7 +501,8 @@ void ConfigCcpmWidget::UpdateCurveWidgets()
|
||||
if (ThisValue!=OldCurveValues.at(i))Changed=1;
|
||||
}
|
||||
// Setup all Throttle1 curves for all types of airframes
|
||||
if (Changed==1)m_ccpm->PitchCurve->setCurve(curveValues);
|
||||
if (Changed==1)
|
||||
m_ccpm->PitchCurve->setCurve(&curveValues);
|
||||
}
|
||||
|
||||
void ConfigCcpmWidget::updatePitchCurveValue(QList<double> curveValues0,double Value0)
|
||||
@ -606,50 +595,40 @@ void ConfigCcpmWidget::UpdateCurveSettings()
|
||||
m_ccpm->CurveValue2->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);
|
||||
m_ccpm->CurveValue3->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);
|
||||
|
||||
//set default visible
|
||||
m_ccpm->CurveLabel1->setVisible(true);
|
||||
m_ccpm->CurveValue1->setVisible(true);
|
||||
m_ccpm->CurveLabel2->setVisible(false);
|
||||
m_ccpm->CurveValue2->setVisible(false);
|
||||
m_ccpm->CurveLabel3->setVisible(false);
|
||||
m_ccpm->CurveValue3->setVisible(false);
|
||||
m_ccpm->ccpmGenerateCurve->setVisible(true);
|
||||
m_ccpm->CurveToGenerate->setVisible(true);
|
||||
|
||||
if ( CurveType.compare("Flat")==0)
|
||||
{
|
||||
m_ccpm->CurveLabel1->setText("Value");
|
||||
m_ccpm->CurveLabel1->setVisible(true);
|
||||
m_ccpm->CurveValue1->setVisible(true);
|
||||
m_ccpm->CurveLabel2->setVisible(false);
|
||||
m_ccpm->CurveValue2->setVisible(false);
|
||||
m_ccpm->CurveLabel3->setVisible(false);
|
||||
m_ccpm->CurveValue3->setVisible(false);
|
||||
m_ccpm->ccpmGenerateCurve->setVisible(true);
|
||||
m_ccpm->CurveToGenerate->setVisible(true);
|
||||
}
|
||||
if ( CurveType.compare("Linear")==0)
|
||||
{
|
||||
m_ccpm->CurveLabel1->setText("Min");
|
||||
m_ccpm->CurveLabel1->setVisible(true);
|
||||
m_ccpm->CurveValue1->setVisible(true);
|
||||
m_ccpm->CurveLabel2->setText("Max");
|
||||
m_ccpm->CurveLabel2->setVisible(true);
|
||||
m_ccpm->CurveValue2->setVisible(true);
|
||||
m_ccpm->CurveLabel3->setVisible(false);
|
||||
m_ccpm->CurveValue3->setVisible(false);
|
||||
m_ccpm->ccpmGenerateCurve->setVisible(true);
|
||||
m_ccpm->CurveToGenerate->setVisible(true);
|
||||
}
|
||||
if ( CurveType.compare("Step")==0)
|
||||
{
|
||||
m_ccpm->CurveLabel1->setText("Min");
|
||||
m_ccpm->CurveLabel1->setVisible(true);
|
||||
m_ccpm->CurveValue1->setVisible(true);
|
||||
m_ccpm->CurveLabel2->setText("Max");
|
||||
m_ccpm->CurveLabel2->setVisible(true);
|
||||
m_ccpm->CurveValue2->setVisible(true);
|
||||
m_ccpm->CurveLabel3->setText("Step at");
|
||||
m_ccpm->CurveLabel3->setVisible(true);
|
||||
m_ccpm->CurveValue3->setVisible(true);
|
||||
m_ccpm->ccpmGenerateCurve->setVisible(true);
|
||||
m_ccpm->CurveToGenerate->setVisible(true);
|
||||
}
|
||||
if ( CurveType.compare("Exp")==0)
|
||||
{
|
||||
m_ccpm->CurveLabel1->setText("Min");
|
||||
m_ccpm->CurveLabel1->setVisible(true);
|
||||
m_ccpm->CurveValue1->setVisible(true);
|
||||
m_ccpm->CurveLabel2->setText("Max");
|
||||
m_ccpm->CurveLabel2->setVisible(true);
|
||||
m_ccpm->CurveValue2->setVisible(true);
|
||||
@ -660,14 +639,10 @@ void ConfigCcpmWidget::UpdateCurveSettings()
|
||||
m_ccpm->CurveValue3->setMaximum(100.0);
|
||||
m_ccpm->CurveValue3->setSingleStep(1.0);
|
||||
m_ccpm->CurveValue3->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);;
|
||||
m_ccpm->ccpmGenerateCurve->setVisible(true);
|
||||
m_ccpm->CurveToGenerate->setVisible(true);
|
||||
}
|
||||
if ( CurveType.compare("Log")==0)
|
||||
{
|
||||
m_ccpm->CurveLabel1->setText("Min");
|
||||
m_ccpm->CurveLabel1->setVisible(true);
|
||||
m_ccpm->CurveValue1->setVisible(true);
|
||||
m_ccpm->CurveLabel2->setText("Max");
|
||||
m_ccpm->CurveLabel2->setVisible(true);
|
||||
m_ccpm->CurveValue2->setVisible(true);
|
||||
@ -677,22 +652,17 @@ void ConfigCcpmWidget::UpdateCurveSettings()
|
||||
m_ccpm->CurveValue3->setMinimum(1.0);
|
||||
m_ccpm->CurveValue3->setMaximum(100.0);
|
||||
m_ccpm->CurveValue3->setSingleStep(1.0);
|
||||
m_ccpm->CurveValue3->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);;
|
||||
m_ccpm->ccpmGenerateCurve->setVisible(true);
|
||||
m_ccpm->CurveToGenerate->setVisible(true);
|
||||
m_ccpm->CurveValue3->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);
|
||||
}
|
||||
if ( CurveType.compare("Custom")==0)
|
||||
{
|
||||
m_ccpm->CurveLabel1->setVisible(false);
|
||||
m_ccpm->CurveValue1->setVisible(false);
|
||||
m_ccpm->CurveLabel2->setVisible(false);
|
||||
m_ccpm->CurveValue2->setVisible(false);
|
||||
m_ccpm->CurveLabel3->setVisible(false);
|
||||
m_ccpm->CurveValue3->setVisible(false);
|
||||
m_ccpm->ccpmGenerateCurve->setVisible(false);
|
||||
m_ccpm->CurveToGenerate->setVisible(false);
|
||||
}
|
||||
UpdateCurveWidgets();
|
||||
|
||||
UpdateCurveWidgets();
|
||||
|
||||
}
|
||||
void ConfigCcpmWidget::GenerateCurve()
|
||||
@ -881,7 +851,8 @@ void ConfigCcpmWidget::UpdateMixer()
|
||||
float CollectiveConstant,PitchConstant,RollConstant,ThisAngle[6];
|
||||
QString Channel;
|
||||
|
||||
throwConfigError(QString("HeliCP"));
|
||||
if (throwConfigError(QString("HeliCP")))
|
||||
return;
|
||||
|
||||
GUIConfigDataUnion config = GetConfigData();
|
||||
|
||||
@ -1744,13 +1715,16 @@ void ConfigCcpmWidget::SwashLvlSpinBoxChanged(int value)
|
||||
/**
|
||||
This function displays text and color formatting in order to help the user understand what channels have not yet been configured.
|
||||
*/
|
||||
void ConfigCcpmWidget::throwConfigError(QString airframeType)
|
||||
bool ConfigCcpmWidget::throwConfigError(QString airframeType)
|
||||
{
|
||||
Q_UNUSED(airframeType);
|
||||
|
||||
bool error = false;
|
||||
|
||||
if((m_ccpm->ccpmServoWChannel->currentIndex()==0)&&(m_ccpm->ccpmServoWChannel->isEnabled()))
|
||||
{
|
||||
m_ccpm->ccpmServoWLabel->setText("<font color=red>Servo W</font>");
|
||||
error = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -1759,6 +1733,7 @@ void ConfigCcpmWidget::throwConfigError(QString airframeType)
|
||||
if((m_ccpm->ccpmServoXChannel->currentIndex()==0)&&(m_ccpm->ccpmServoXChannel->isEnabled()))
|
||||
{
|
||||
m_ccpm->ccpmServoXLabel->setText("<font color=red>Servo X</font>");
|
||||
error = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -1767,6 +1742,7 @@ void ConfigCcpmWidget::throwConfigError(QString airframeType)
|
||||
if((m_ccpm->ccpmServoYChannel->currentIndex()==0)&&(m_ccpm->ccpmServoYChannel->isEnabled()))
|
||||
{
|
||||
m_ccpm->ccpmServoYLabel->setText("<font color=red>Servo Y</font>");
|
||||
error = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -1775,6 +1751,7 @@ void ConfigCcpmWidget::throwConfigError(QString airframeType)
|
||||
if((m_ccpm->ccpmServoZChannel->currentIndex()==0)&&(m_ccpm->ccpmServoZChannel->isEnabled()))
|
||||
{
|
||||
m_ccpm->ccpmServoZLabel->setText("<font color=red>Servo Z</font>");
|
||||
error = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -1793,10 +1770,12 @@ void ConfigCcpmWidget::throwConfigError(QString airframeType)
|
||||
if((m_ccpm->ccpmTailChannel->currentIndex()==0)&&(m_ccpm->ccpmTailChannel->isEnabled()))
|
||||
{
|
||||
m_ccpm->ccpmTailLabel->setText("<font color=red>Tail Rotor</font>");
|
||||
error = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
m_ccpm->ccpmTailLabel->setText("<font color=black>Tail Rotor</font>");
|
||||
}
|
||||
|
||||
return error;
|
||||
}
|
||||
|
@ -95,7 +95,7 @@ private:
|
||||
virtual void setupUI(QString airframeType);
|
||||
virtual void refreshWidgetsValues(QString frameType);
|
||||
virtual QString updateConfigObjectsFromWidgets();
|
||||
virtual void throwConfigError(QString airframeType);
|
||||
virtual bool throwConfigError(QString airframeType);
|
||||
|
||||
void ccpmSwashplateUpdate();
|
||||
void ccpmSwashplateRedraw();
|
||||
@ -103,7 +103,6 @@ private:
|
||||
void GenerateCurve();
|
||||
void UpdateMixer();
|
||||
void UpdateType();
|
||||
void resetMixer(MixerCurveWidget *mixer, int numElements);
|
||||
void UpdateCurveWidgets();
|
||||
void updatePitchCurveValue(QList<double>,double);
|
||||
void updateThrottleCurveValue(QList<double>,double);
|
||||
|
@ -262,15 +262,7 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType)
|
||||
{
|
||||
// Check coherence:
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(airframeType);
|
||||
|
||||
// - At least Pitch and either Roll or Yaw
|
||||
if (m_aircraft->fwEngineChannelBox->currentText() == "None" ||
|
||||
m_aircraft->fwElevator1ChannelBox->currentText() == "None" ||
|
||||
((m_aircraft->fwAileron1ChannelBox->currentText() == "None") &&
|
||||
(m_aircraft->fwRudder1ChannelBox->currentText() == "None"))) {
|
||||
// TODO: explain the problem in the UI
|
||||
// m_aircraft->fwStatusLabel->setText("ERROR: check channel assignment");
|
||||
if (throwConfigError(airframeType)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -351,14 +343,7 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType)
|
||||
{
|
||||
// Check coherence:
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(airframeType);
|
||||
|
||||
// - At least Aileron1 and Aileron 2, and engine
|
||||
if (m_aircraft->fwEngineChannelBox->currentText() == "None" ||
|
||||
m_aircraft->fwAileron1ChannelBox->currentText() == "None" ||
|
||||
m_aircraft->fwAileron2ChannelBox->currentText() == "None") {
|
||||
// TODO: explain the problem in the UI
|
||||
// m_aircraft->fwStatusLabel->setText("ERROR: check channel assignment");
|
||||
if (throwConfigError(airframeType)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -436,14 +421,7 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType)
|
||||
{
|
||||
// Check coherence:
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(airframeType);
|
||||
|
||||
// - At least Pitch1 and Pitch2, and engine
|
||||
if (m_aircraft->fwEngineChannelBox->currentText() == "None" ||
|
||||
m_aircraft->fwElevator1ChannelBox->currentText() == "None" ||
|
||||
m_aircraft->fwElevator2ChannelBox->currentText() == "None") {
|
||||
// TODO: explain the problem in the UI
|
||||
// m_aircraft->fwStatusLabel->setText("WARNING: check channel assignment");
|
||||
if (throwConfigError(airframeType)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -526,7 +504,7 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType)
|
||||
/**
|
||||
This function displays text and color formatting in order to help the user understand what channels have not yet been configured.
|
||||
*/
|
||||
void ConfigFixedWingWidget::throwConfigError(QString airframeType)
|
||||
bool ConfigFixedWingWidget::throwConfigError(QString airframeType)
|
||||
{
|
||||
//Initialize configuration error flag
|
||||
bool error=false;
|
||||
@ -618,4 +596,6 @@ void ConfigFixedWingWidget::throwConfigError(QString airframeType)
|
||||
if (error){
|
||||
m_aircraft->fwStatusLabel->setText(QString("<font color='red'>ERROR: Assign all necessary channels</font>"));
|
||||
}
|
||||
|
||||
return error;
|
||||
}
|
||||
|
@ -63,7 +63,7 @@ private slots:
|
||||
virtual void setupUI(QString airframeType);
|
||||
virtual void refreshWidgetsValues(QString frameType);
|
||||
virtual QString updateConfigObjectsFromWidgets();
|
||||
virtual void throwConfigError(QString airframeType);
|
||||
virtual bool throwConfigError(QString airframeType);
|
||||
|
||||
|
||||
protected:
|
||||
|
@ -289,16 +289,9 @@ void ConfigGroundVehicleWidget::refreshWidgetsValues(QString frameType)
|
||||
bool ConfigGroundVehicleWidget::setupGroundVehicleMotorcycle(QString airframeType){
|
||||
// Check coherence:
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(airframeType);
|
||||
|
||||
// - Motor, steering, and balance
|
||||
if (m_aircraft->gvMotor2ChannelBox->currentText() == "None" ||
|
||||
(m_aircraft->gvSteering1ChannelBox->currentText() == "None" ||
|
||||
m_aircraft->gvSteering2ChannelBox->currentText() == "None") )
|
||||
{
|
||||
if (throwConfigError(airframeType)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Now setup the channels:
|
||||
GUIConfigDataUnion config = GetConfigData();
|
||||
@ -352,16 +345,11 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleMotorcycle(QString airframeTyp
|
||||
bool ConfigGroundVehicleWidget::setupGroundVehicleDifferential(QString airframeType){
|
||||
// Check coherence:
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(airframeType);
|
||||
|
||||
// - Left and right steering
|
||||
if ( m_aircraft->gvMotor2ChannelBox->currentText() == "None" ||
|
||||
m_aircraft->gvSteering1ChannelBox->currentText() == "None")
|
||||
{
|
||||
|
||||
if (throwConfigError(airframeType)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
// Now setup the channels:
|
||||
GUIConfigDataUnion config = GetConfigData();
|
||||
ResetActuators(&config);
|
||||
@ -411,14 +399,7 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleCar(QString airframeType)
|
||||
{
|
||||
// Check coherence:
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(airframeType);
|
||||
|
||||
// - At least one motor and one steering servo
|
||||
if ((m_aircraft->gvMotor1ChannelBox->currentText() == "None" &&
|
||||
m_aircraft->gvMotor2ChannelBox->currentText() == "None") ||
|
||||
(m_aircraft->gvSteering1ChannelBox->currentText() == "None" &&
|
||||
m_aircraft->gvSteering2ChannelBox->currentText() == "None"))
|
||||
{
|
||||
if (throwConfigError(airframeType)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -468,7 +449,7 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleCar(QString airframeType)
|
||||
/**
|
||||
This function displays text and color formatting in order to help the user understand what channels have not yet been configured.
|
||||
*/
|
||||
void ConfigGroundVehicleWidget::throwConfigError(QString airframeType)
|
||||
bool ConfigGroundVehicleWidget::throwConfigError(QString airframeType)
|
||||
{
|
||||
//Initialize configuration error flag
|
||||
bool error=false;
|
||||
@ -558,5 +539,6 @@ void ConfigGroundVehicleWidget::throwConfigError(QString airframeType)
|
||||
if (error){
|
||||
m_aircraft->gvStatusLabel->setText(QString("<font color='red'>ERROR: Assign all necessary channels</font>"));
|
||||
}
|
||||
return error;
|
||||
}
|
||||
|
||||
|
@ -63,7 +63,7 @@ private slots:
|
||||
virtual void setupUI(QString airframeType);
|
||||
virtual void refreshWidgetsValues(QString frameType);
|
||||
virtual QString updateConfigObjectsFromWidgets();
|
||||
virtual void throwConfigError(QString airframeType);
|
||||
virtual bool throwConfigError(QString airframeType);
|
||||
|
||||
|
||||
protected:
|
||||
|
@ -93,17 +93,22 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
|
||||
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
|
||||
}
|
||||
|
||||
m_aircraft->mrRollMixLevel->setValue(100);
|
||||
m_aircraft->mrPitchMixLevel->setValue(100);
|
||||
m_aircraft->mrYawMixLevel->setValue(50);
|
||||
|
||||
m_aircraft->triYawChannelBox->setEnabled(true);
|
||||
}
|
||||
else if (frameType == "QuadX" || frameType == "Quad X") {
|
||||
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X"));
|
||||
quad->setElementId("quad-X");
|
||||
quad->setElementId("quad-x");
|
||||
|
||||
//Enable all necessary motor channel boxes...
|
||||
for (i=1; i <=4; i++) {
|
||||
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
|
||||
}
|
||||
|
||||
// init mixer levels
|
||||
m_aircraft->mrRollMixLevel->setValue(50);
|
||||
m_aircraft->mrPitchMixLevel->setValue(50);
|
||||
m_aircraft->mrYawMixLevel->setValue(50);
|
||||
@ -283,20 +288,12 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
{
|
||||
QString airframeType;
|
||||
QList<QString> motorList;
|
||||
|
||||
// We can already setup the feedforward here, as it is common to all platforms
|
||||
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
UAVObjectField* field = obj->getField(QString("FeedForward"));
|
||||
field->setDouble((double)m_aircraft->feedForwardSlider->value()/100);
|
||||
field = obj->getField(QString("AccelTime"));
|
||||
field->setDouble(m_aircraft->accelTime->value());
|
||||
field = obj->getField(QString("DecelTime"));
|
||||
field->setDouble(m_aircraft->decelTime->value());
|
||||
field = obj->getField(QString("MaxAccel"));
|
||||
field->setDouble(m_aircraft->maxAccelSlider->value());
|
||||
|
||||
|
||||
UAVDataObject* mixerObj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixerObj);
|
||||
|
||||
// Curve is also common to all quads:
|
||||
setThrottleCurve(obj, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->multiThrottleCurve->getCurve() );
|
||||
setThrottleCurve(mixerObj, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->multiThrottleCurve->getCurve() );
|
||||
|
||||
if (m_aircraft->multirotorFrameType->currentText() == "Quad +") {
|
||||
airframeType = "QuadP";
|
||||
@ -314,15 +311,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
airframeType = "HexaCoax";
|
||||
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(6);
|
||||
|
||||
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox3->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox4->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox5->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox6->currentText() == "None" ) {
|
||||
|
||||
if (throwConfigError(6)) {
|
||||
return airframeType;
|
||||
}
|
||||
motorList << "VTOLMotorNW" << "VTOLMotorW" << "VTOLMotorNE" << "VTOLMotorE"
|
||||
@ -348,18 +337,9 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
airframeType = "Octo";
|
||||
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(8);
|
||||
|
||||
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox3->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox4->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox5->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox6->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox7->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox8->currentText() == "None") {
|
||||
|
||||
if (throwConfigError(8)) {
|
||||
return airframeType;
|
||||
|
||||
}
|
||||
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE"
|
||||
<< "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW";
|
||||
@ -383,17 +363,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
airframeType = "OctoV";
|
||||
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(8);
|
||||
|
||||
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox3->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox4->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox5->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox6->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox7->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox8->currentText() == "None") {
|
||||
|
||||
if (throwConfigError(8)) {
|
||||
return airframeType;
|
||||
}
|
||||
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE"
|
||||
@ -419,17 +389,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
airframeType = "OctoCoaxP";
|
||||
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(8);
|
||||
|
||||
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox3->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox4->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox5->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox6->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox7->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox8->currentText() == "None") {
|
||||
|
||||
if (throwConfigError(8)) {
|
||||
return airframeType;
|
||||
}
|
||||
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE"
|
||||
@ -454,17 +414,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
airframeType = "OctoCoaxX";
|
||||
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(8);
|
||||
|
||||
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox3->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox4->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox5->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox6->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox7->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox8->currentText() == "None") {
|
||||
|
||||
if (throwConfigError(8)) {
|
||||
return airframeType;
|
||||
}
|
||||
motorList << "VTOLMotorNW" << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE"
|
||||
@ -489,12 +439,9 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
airframeType = "Tri";
|
||||
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(3);
|
||||
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox3->currentText() == "None" ) {
|
||||
|
||||
if (throwConfigError(3)) {
|
||||
return airframeType;
|
||||
|
||||
}
|
||||
if (m_aircraft->triYawChannelBox->currentText() == "None") {
|
||||
m_aircraft->mrStatusLabel->setText("<font color='red'>Error: Assign a Yaw channel</font>");
|
||||
@ -523,8 +470,6 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
setupMultiRotorMixer(mixer);
|
||||
|
||||
//tell the mixer about tricopter yaw channel
|
||||
UAVDataObject* mixerObj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixerObj);
|
||||
|
||||
int channel = m_aircraft->triYawChannelBox->currentIndex()-1;
|
||||
if (channel > -1){
|
||||
@ -868,14 +813,7 @@ bool ConfigMultiRotorWidget::setupQuad(bool pLayout)
|
||||
// Check coherence:
|
||||
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(4);
|
||||
|
||||
// - Four engines have to be defined
|
||||
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox3->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox4->currentText() == "None") {
|
||||
|
||||
if (throwConfigError(4)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -943,19 +881,9 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout)
|
||||
{
|
||||
// Check coherence:
|
||||
//Show any config errors in GUI
|
||||
throwConfigError(6);
|
||||
|
||||
// - Four engines have to be defined
|
||||
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox3->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox4->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox5->currentText() == "None" ||
|
||||
m_aircraft->multiMotorChannelBox6->currentText() == "None") {
|
||||
|
||||
if (throwConfigError(6))
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
QList<QString> motorList;
|
||||
if (pLayout) {
|
||||
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorSE"
|
||||
@ -1069,7 +997,7 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3])
|
||||
/**
|
||||
This function displays text and color formatting in order to help the user understand what channels have not yet been configured.
|
||||
*/
|
||||
void ConfigMultiRotorWidget::throwConfigError(int numMotors)
|
||||
bool ConfigMultiRotorWidget::throwConfigError(int numMotors)
|
||||
{
|
||||
//Initialize configuration error flag
|
||||
bool error=false;
|
||||
@ -1096,6 +1024,7 @@ void ConfigMultiRotorWidget::throwConfigError(int numMotors)
|
||||
if (error){
|
||||
m_aircraft->mrStatusLabel->setText(QString("<font color='red'>ERROR: Assign all %1 motor channels</font>").arg(numMotors));
|
||||
}
|
||||
return error;
|
||||
}
|
||||
|
||||
|
||||
|
@ -71,7 +71,7 @@ private slots:
|
||||
virtual void setupUI(QString airframeType);
|
||||
virtual void refreshWidgetsValues(QString frameType);
|
||||
virtual QString updateConfigObjectsFromWidgets();
|
||||
void throwConfigError(int numMotors);
|
||||
virtual bool throwConfigError(int numMotors);
|
||||
|
||||
|
||||
protected:
|
||||
|
@ -233,6 +233,30 @@ void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, Mixer
|
||||
}
|
||||
}
|
||||
|
||||
double VehicleConfig::getMixerValue(UAVDataObject* mixer, QString elementName)
|
||||
{
|
||||
Q_ASSERT(mixer);
|
||||
|
||||
double value = 0.0;
|
||||
|
||||
QPointer<UAVObjectField> field = mixer->getField(elementName);
|
||||
if (field) {
|
||||
value = field->getDouble();
|
||||
}
|
||||
return value;
|
||||
}
|
||||
|
||||
void VehicleConfig::setMixerValue(UAVDataObject* mixer, QString elementName, double value)
|
||||
{
|
||||
Q_ASSERT(mixer);
|
||||
|
||||
QPointer<UAVObjectField> field = mixer->getField(elementName);
|
||||
if (field) {
|
||||
field->setDouble(value);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void VehicleConfig::setThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList<double> curve)
|
||||
{
|
||||
QPointer<UAVObjectField> field;
|
||||
@ -287,6 +311,36 @@ void VehicleConfig::getThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveEle
|
||||
}
|
||||
}
|
||||
|
||||
bool VehicleConfig::isValidThrottleCurve(QList<double>* curve)
|
||||
{
|
||||
Q_ASSERT(curve);
|
||||
|
||||
if (curve) {
|
||||
for (int i=0; i < curve->count(); i++) {
|
||||
if (curve->at(i) != 0)
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
double VehicleConfig::getCurveMin(QList<double>* curve)
|
||||
{
|
||||
double min = 0;
|
||||
for (int i=0; i<curve->count(); i++)
|
||||
min = std::min(min, curve->at(i));
|
||||
|
||||
return min;
|
||||
}
|
||||
|
||||
double VehicleConfig::getCurveMax(QList<double>* curve)
|
||||
{
|
||||
double max = 0;
|
||||
for (int i=0; i<curve->count(); i++)
|
||||
max = std::max(max, curve->at(i));
|
||||
|
||||
return max;
|
||||
}
|
||||
/**
|
||||
Reset the contents of a field
|
||||
*/
|
||||
|
@ -130,9 +130,13 @@ class VehicleConfig: public ConfigTaskWidget
|
||||
void resetMixerVector(UAVDataObject* mixer, int channel);
|
||||
QString getMixerType(UAVDataObject* mixer, int channel);
|
||||
void setMixerType(UAVDataObject* mixer, int channel, MixerTypeElem mixerType);
|
||||
double getMixerValue(UAVDataObject* mixer, QString elementName);
|
||||
void setMixerValue(UAVDataObject* mixer, QString elementName, double value);
|
||||
void setThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList<double> curve);
|
||||
void getThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList<double>* curve);
|
||||
|
||||
bool isValidThrottleCurve(QList<double>* curve);
|
||||
double getCurveMin(QList<double>* curve);
|
||||
double getCurveMax(QList<double>* curve);
|
||||
virtual void ResetActuators(GUIConfigDataUnion* configData);
|
||||
virtual QStringList getChannelDescriptions();
|
||||
|
||||
|
@ -7,7 +7,7 @@
|
||||
<file>images/AHRS-v1.3.png</file>
|
||||
<file>images/paper-plane.svg</file>
|
||||
<file>images/curve-bg.svg</file>
|
||||
<file>images/quad-shapes.svg</file>
|
||||
<file>images/multirotor-shapes.svg</file>
|
||||
<file>images/ccpm_setup.svg</file>
|
||||
<file>images/PipXtreme.png</file>
|
||||
<file>images/Transmitter.png</file>
|
||||
|
@ -85,6 +85,10 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum);
|
||||
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Roll,"Roll");
|
||||
@ -99,6 +103,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000);
|
||||
connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider()));
|
||||
connect( ManualControlSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(updatePositionSlider()));
|
||||
enableControls(false);
|
||||
|
||||
populateWidgets();
|
||||
@ -632,7 +637,8 @@ void ConfigInputWidget::setChannel(int newChan)
|
||||
m_config->wzText->setText(QString(tr("Please move each control once at a time according to the instructions and picture below.\n\n"
|
||||
"Move the %1 stick")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan)));
|
||||
|
||||
if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory")) {
|
||||
if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory") ||
|
||||
manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) {
|
||||
m_config->wzNext->setEnabled(true);
|
||||
m_config->wzText->setText(m_config->wzText->text() + tr(" or click next to skip this channel."));
|
||||
} else
|
||||
@ -1113,10 +1119,11 @@ void ConfigInputWidget::invertControls()
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::moveFMSlider()
|
||||
{
|
||||
ManualControlSettings::DataFields manualSettingsDataPriv = manualSettingsObj->getData();
|
||||
ManualControlCommand::DataFields manualCommandDataPriv=manualCommandObj->getData();
|
||||
ManualControlCommand::DataFields manualCommandDataPriv = manualCommandObj->getData();
|
||||
|
||||
float valueScaled;
|
||||
int chMin = manualSettingsDataPriv.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE];
|
||||
@ -1139,12 +1146,72 @@ void ConfigInputWidget::moveFMSlider()
|
||||
valueScaled = 0;
|
||||
}
|
||||
|
||||
if(valueScaled < -(1.0 / 3.0))
|
||||
m_config->fmsSlider->setValue(-100);
|
||||
else if (valueScaled > (1.0/3.0))
|
||||
m_config->fmsSlider->setValue(100);
|
||||
// Bound and scale FlightMode from [-1..+1] to [0..1] range
|
||||
if (valueScaled < -1.0)
|
||||
valueScaled = -1.0;
|
||||
else
|
||||
m_config->fmsSlider->setValue(0);
|
||||
if (valueScaled > 1.0)
|
||||
valueScaled = 1.0;
|
||||
|
||||
// Convert flightMode value into the switch position in the range [0..N-1]
|
||||
// This uses the same optimized computation as flight code to be consistent
|
||||
uint8_t pos = ((int16_t)(valueScaled * 256) + 256) * manualSettingsDataPriv.FlightModeNumber >> 9;
|
||||
if (pos >= manualSettingsDataPriv.FlightModeNumber)
|
||||
pos = manualSettingsDataPriv.FlightModeNumber - 1;
|
||||
m_config->fmsSlider->setValue(pos);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::updatePositionSlider()
|
||||
{
|
||||
ManualControlSettings::DataFields manualSettingsDataPriv = manualSettingsObj->getData();
|
||||
|
||||
switch(manualSettingsDataPriv.FlightModeNumber) {
|
||||
default:
|
||||
case 6:
|
||||
m_config->fmsModePos6->setEnabled(true);
|
||||
// pass through
|
||||
case 5:
|
||||
m_config->fmsModePos5->setEnabled(true);
|
||||
// pass through
|
||||
case 4:
|
||||
m_config->fmsModePos4->setEnabled(true);
|
||||
// pass through
|
||||
case 3:
|
||||
m_config->fmsModePos3->setEnabled(true);
|
||||
// pass through
|
||||
case 2:
|
||||
m_config->fmsModePos2->setEnabled(true);
|
||||
// pass through
|
||||
case 1:
|
||||
m_config->fmsModePos1->setEnabled(true);
|
||||
// pass through
|
||||
case 0:
|
||||
break;
|
||||
}
|
||||
|
||||
switch(manualSettingsDataPriv.FlightModeNumber) {
|
||||
case 0:
|
||||
m_config->fmsModePos1->setEnabled(false);
|
||||
// pass through
|
||||
case 1:
|
||||
m_config->fmsModePos2->setEnabled(false);
|
||||
// pass through
|
||||
case 2:
|
||||
m_config->fmsModePos3->setEnabled(false);
|
||||
// pass through
|
||||
case 3:
|
||||
m_config->fmsModePos4->setEnabled(false);
|
||||
// pass through
|
||||
case 4:
|
||||
m_config->fmsModePos5->setEnabled(false);
|
||||
// pass through
|
||||
case 5:
|
||||
m_config->fmsModePos6->setEnabled(false);
|
||||
// pass through
|
||||
case 6:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::updateCalibration()
|
||||
|
@ -146,6 +146,7 @@ private slots:
|
||||
void moveSticks();
|
||||
void dimOtherControls(bool value);
|
||||
void moveFMSlider();
|
||||
void updatePositionSlider();
|
||||
void invertControls();
|
||||
void simpleCalibration(bool state);
|
||||
void updateCalibration();
|
||||
|
@ -119,9 +119,8 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
|
||||
QStringList airframeTypes;
|
||||
airframeTypes << "Fixed Wing" << "Multirotor" << "Helicopter" << "Ground" << "Custom";
|
||||
m_aircraft->aircraftType->addItems(airframeTypes);
|
||||
|
||||
m_aircraft->aircraftType->setCurrentIndex(0); //Set default vehicle to Fixed Wing
|
||||
m_aircraft->airframesWidget->setCurrentIndex(0); // Force the tab index to match
|
||||
m_aircraft->aircraftType->setCurrentIndex(1); //Set default vehicle to MultiRotor
|
||||
m_aircraft->airframesWidget->setCurrentIndex(1); // Force the tab index to match
|
||||
|
||||
QStringList fixedWingTypes;
|
||||
fixedWingTypes << "Elevator aileron rudder" << "Elevon" << "Vtail";
|
||||
@ -138,7 +137,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
|
||||
"Hexacopter" << "Hexacopter X" << "Hexacopter Y6" <<
|
||||
"Octocopter" << "Octocopter V" << "Octo Coax +" << "Octo Coax X" ;
|
||||
m_aircraft->multirotorFrameType->addItems(multiRotorTypes);
|
||||
m_aircraft->multirotorFrameType->setCurrentIndex(1); //Set default model to "Quad +"
|
||||
m_aircraft->multirotorFrameType->setCurrentIndex(2); //Set default model to "Quad X"
|
||||
|
||||
|
||||
//NEW STYLE: Loop through the widgets looking for all widgets that have "ChannelBox" in their name
|
||||
@ -152,10 +151,10 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
|
||||
m_aircraft->quadShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
|
||||
m_aircraft->quadShape->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
|
||||
QSvgRenderer *renderer = new QSvgRenderer();
|
||||
renderer->load(QString(":/configgadget/images/quad-shapes.svg"));
|
||||
renderer->load(QString(":/configgadget/images/multirotor-shapes.svg"));
|
||||
quad = new QGraphicsSvgItem();
|
||||
quad->setSharedRenderer(renderer);
|
||||
quad->setElementId("quad-plus");
|
||||
quad->setElementId("quad-x");
|
||||
QGraphicsScene *scene = new QGraphicsScene(this);
|
||||
scene->addItem(quad);
|
||||
scene->setSceneRect(quad->boundingRect());
|
||||
@ -274,7 +273,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
|
||||
case SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON:
|
||||
case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL:
|
||||
{
|
||||
ConfigFixedWingWidget* fixedwing = new ConfigFixedWingWidget();
|
||||
QPointer<ConfigFixedWingWidget> fixedwing = new ConfigFixedWingWidget();
|
||||
channelDesc = fixedwing->getChannelDescriptions();
|
||||
}
|
||||
break;
|
||||
@ -282,7 +281,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
|
||||
// helicp
|
||||
case SystemSettings::AIRFRAMETYPE_HELICP:
|
||||
{
|
||||
ConfigCcpmWidget* heli = new ConfigCcpmWidget();
|
||||
QPointer<ConfigCcpmWidget> heli = new ConfigCcpmWidget();
|
||||
channelDesc = heli->getChannelDescriptions();
|
||||
}
|
||||
break;
|
||||
@ -300,7 +299,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
|
||||
case SystemSettings::AIRFRAMETYPE_HEXACOAX:
|
||||
case SystemSettings::AIRFRAMETYPE_HEXA:
|
||||
{
|
||||
ConfigMultiRotorWidget* multi = new ConfigMultiRotorWidget();
|
||||
QPointer<ConfigMultiRotorWidget> multi = new ConfigMultiRotorWidget();
|
||||
channelDesc = multi->getChannelDescriptions();
|
||||
}
|
||||
break;
|
||||
@ -310,7 +309,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
|
||||
case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLEDIFFERENTIAL:
|
||||
case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLEMOTORCYCLE:
|
||||
{
|
||||
ConfigGroundVehicleWidget* ground = new ConfigGroundVehicleWidget();
|
||||
QPointer<ConfigGroundVehicleWidget> ground = new ConfigGroundVehicleWidget();
|
||||
channelDesc = ground->getChannelDescriptions();
|
||||
}
|
||||
break;
|
||||
@ -444,16 +443,17 @@ void ConfigVehicleTypeWidget::enableFFTest()
|
||||
// Depending on phase, either move actuator or send FF settings:
|
||||
if (ffTuningPhase) {
|
||||
// Send FF settings to the board
|
||||
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
UAVObjectField* field = obj->getField(QString("FeedForward"));
|
||||
field->setDouble((double)m_aircraft->feedForwardSlider->value()/100);
|
||||
field = obj->getField(QString("AccelTime"));
|
||||
field->setDouble(m_aircraft->accelTime->value());
|
||||
field = obj->getField(QString("DecelTime"));
|
||||
field->setDouble(m_aircraft->decelTime->value());
|
||||
field = obj->getField(QString("MaxAccel"));
|
||||
field->setDouble(m_aircraft->maxAccelSlider->value());
|
||||
obj->updated();
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
|
||||
QPointer<VehicleConfig> vconfig = new VehicleConfig();
|
||||
|
||||
// Update feed forward settings
|
||||
vconfig->setMixerValue(mixer, "FeedForward", m_aircraft->feedForwardSlider->value() / 100.0);
|
||||
vconfig->setMixerValue(mixer, "AccelTime", m_aircraft->accelTime->value());
|
||||
vconfig->setMixerValue(mixer, "DecelTime", m_aircraft->decelTime->value());
|
||||
vconfig->setMixerValue(mixer, "MaxAccel", m_aircraft->maxAccelSlider->value());
|
||||
mixer->updated();
|
||||
} else {
|
||||
// Toggle motor state
|
||||
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ManualControlCommand")));
|
||||
@ -614,84 +614,55 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject * o)
|
||||
{
|
||||
Q_UNUSED(o);
|
||||
|
||||
if(!allObjectsUpdated())
|
||||
return;
|
||||
//if(!allObjectsUpdated())
|
||||
// return;
|
||||
|
||||
//WHAT DOES THIS DO?
|
||||
bool dirty=isDirty(); //WHY IS THIS CALLED HERE AND THEN AGAIN SEVERAL LINES LATER IN setupAirframeUI()
|
||||
|
||||
// Get the Airframe type from the system settings:
|
||||
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
|
||||
Q_ASSERT(obj);
|
||||
UAVObjectField *field = obj->getField(QString("AirframeType"));
|
||||
UAVDataObject* system = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
|
||||
Q_ASSERT(system);
|
||||
|
||||
UAVObjectField *field = system->getField(QString("AirframeType"));
|
||||
Q_ASSERT(field);
|
||||
// At this stage, we will need to have some hardcoded settings in this code, this
|
||||
// is not ideal, but here you go.
|
||||
QString frameType = field->getValue().toString();
|
||||
setupAirframeUI(frameType);
|
||||
|
||||
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(obj);
|
||||
field = obj->getField(QString("ThrottleCurve1"));
|
||||
Q_ASSERT(field);
|
||||
QList<double> curveValues;
|
||||
// If the 1st element of the curve is <= -10, then the curve
|
||||
// is a straight line (that's how the mixer works on the mainboard):
|
||||
if (field->getValue(0).toInt() <= -10) {
|
||||
m_aircraft->multiThrottleCurve->initLinearCurve(field->getNumElements(),(double)1);
|
||||
m_aircraft->fixedWingThrottle->initLinearCurve(field->getNumElements(),(double)1);
|
||||
m_aircraft->groundVehicleThrottle1->initLinearCurve(field->getNumElements(),(double)1);
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
|
||||
QPointer<VehicleConfig> vconfig = new VehicleConfig();
|
||||
|
||||
QList<double> curveValues;
|
||||
vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, &curveValues);
|
||||
|
||||
// is at least one of the curve values != 0?
|
||||
if (vconfig->isValidThrottleCurve(&curveValues)) {
|
||||
// yes, use the curve we just read from mixersettings
|
||||
m_aircraft->multiThrottleCurve->initCurve(&curveValues);
|
||||
m_aircraft->fixedWingThrottle->initCurve(&curveValues);
|
||||
m_aircraft->groundVehicleThrottle1->initCurve(&curveValues);
|
||||
}
|
||||
else {
|
||||
double temp=0;
|
||||
double value;
|
||||
for (unsigned int i=0; i < field->getNumElements(); i++) {
|
||||
value=field->getValue(i).toDouble();
|
||||
temp+=value;
|
||||
curveValues.append(value);
|
||||
}
|
||||
if(temp==0)
|
||||
{
|
||||
m_aircraft->multiThrottleCurve->initLinearCurve(field->getNumElements(),0.9);
|
||||
m_aircraft->fixedWingThrottle->initLinearCurve(field->getNumElements(),(double)1);
|
||||
m_aircraft->groundVehicleThrottle1->initLinearCurve(field->getNumElements(),(double)1);
|
||||
}
|
||||
else
|
||||
{
|
||||
m_aircraft->multiThrottleCurve->initCurve(curveValues);
|
||||
m_aircraft->fixedWingThrottle->initCurve(curveValues);
|
||||
m_aircraft->groundVehicleThrottle1->initCurve(curveValues);
|
||||
}
|
||||
// no, init a straight curve
|
||||
m_aircraft->multiThrottleCurve->initLinearCurve(curveValues.count(), 0.9);
|
||||
m_aircraft->fixedWingThrottle->initLinearCurve(curveValues.count(), 1.0);
|
||||
m_aircraft->groundVehicleThrottle1->initLinearCurve(curveValues.count(), 1.0);
|
||||
}
|
||||
|
||||
// Setup all Throttle2 curves for all types of airframes //AT THIS MOMENT, THAT MEANS ONLY GROUND VEHICLES
|
||||
Q_ASSERT(obj);
|
||||
field = obj->getField(QString("ThrottleCurve2"));
|
||||
Q_ASSERT(field);
|
||||
curveValues.clear();
|
||||
// If the 1st element of the curve is <= -10, then the curve
|
||||
// is a straight line (that's how the mixer works on the mainboard):
|
||||
if (field->getValue(0).toInt() <= -10) {
|
||||
m_aircraft->groundVehicleThrottle2->initLinearCurve(field->getNumElements(),(double)1);
|
||||
vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, &curveValues);
|
||||
|
||||
if (vconfig->isValidThrottleCurve(&curveValues)) {
|
||||
m_aircraft->groundVehicleThrottle2->initCurve(&curveValues);
|
||||
}
|
||||
else {
|
||||
double temp=0;
|
||||
double value;
|
||||
for (unsigned int i=0; i < field->getNumElements(); i++) {
|
||||
value=field->getValue(i).toDouble();
|
||||
temp+=value;
|
||||
curveValues.append(value);
|
||||
}
|
||||
if(temp==0)
|
||||
{
|
||||
m_aircraft->groundVehicleThrottle2->initLinearCurve(field->getNumElements(),(double)1);
|
||||
}
|
||||
else
|
||||
{
|
||||
m_aircraft->groundVehicleThrottle2->initCurve(curveValues);
|
||||
}
|
||||
m_aircraft->groundVehicleThrottle2->initLinearCurve(curveValues.count(), 1.0);
|
||||
}
|
||||
|
||||
|
||||
// Load the Settings for fixed wing frames:
|
||||
if (frameType.startsWith("FixedWing")) {
|
||||
|
||||
@ -716,8 +687,7 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject * o)
|
||||
|
||||
} else if (frameType == "Custom") {
|
||||
setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Custom"));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
updateCustomAirframeUI();
|
||||
setDirty(dirty);
|
||||
@ -786,39 +756,35 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI()
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
|
||||
VehicleConfig* vconfig = new VehicleConfig();
|
||||
QPointer<VehicleConfig> vconfig = new VehicleConfig();
|
||||
|
||||
QList<double> curveValues;
|
||||
vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, &curveValues);
|
||||
|
||||
// setup throttlecurve 1
|
||||
vconfig->getThrottleCurve(mixer,VehicleConfig::MIXER_THROTTLECURVE1,&curveValues);
|
||||
|
||||
int total = 0;
|
||||
for (int i=0; i<curveValues.length(); i++)
|
||||
total += curveValues.at(i);
|
||||
|
||||
if (curveValues.at(0) <= -10 || total == 0) {
|
||||
m_aircraft->customThrottle1Curve->initLinearCurve(curveValues.length(),(double)1);
|
||||
// is at least one of the curve values != 0?
|
||||
if (vconfig->isValidThrottleCurve(&curveValues)) {
|
||||
// yes, use the curve we just read from mixersettings
|
||||
m_aircraft->customThrottle1Curve->setMin(vconfig->getCurveMin(&curveValues));
|
||||
m_aircraft->customThrottle1Curve->setMax(vconfig->getCurveMax(&curveValues));
|
||||
m_aircraft->customThrottle1Curve->initCurve(&curveValues);
|
||||
}
|
||||
else {
|
||||
m_aircraft->customThrottle1Curve->initCurve(curveValues);
|
||||
// no, init a straight curve
|
||||
m_aircraft->customThrottle1Curve->initLinearCurve(curveValues.count(),(double)1);
|
||||
}
|
||||
|
||||
// setup throttlecurve 2
|
||||
vconfig->getThrottleCurve(mixer,VehicleConfig::MIXER_THROTTLECURVE2,&curveValues);
|
||||
// Setup all Throttle2 curves for all types of airframes //AT THIS MOMENT, THAT MEANS ONLY GROUND VEHICLES
|
||||
vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, &curveValues);
|
||||
|
||||
total = 0;
|
||||
for (int i=0; i<curveValues.length(); i++)
|
||||
total += curveValues.at(i);
|
||||
|
||||
if (curveValues.at(0) <= -10 || total == 0) {
|
||||
m_aircraft->customThrottle2Curve->initLinearCurve(curveValues.length(),(double)1);
|
||||
if (vconfig->isValidThrottleCurve(&curveValues)) {
|
||||
m_aircraft->customThrottle2Curve->setMin(vconfig->getCurveMin(&curveValues));
|
||||
m_aircraft->customThrottle2Curve->setMax(vconfig->getCurveMax(&curveValues));
|
||||
m_aircraft->customThrottle2Curve->initCurve(&curveValues);
|
||||
}
|
||||
else {
|
||||
m_aircraft->customThrottle2Curve->initCurve(curveValues);
|
||||
m_aircraft->customThrottle2Curve->initLinearCurve(curveValues.count(),(double)1);
|
||||
}
|
||||
|
||||
|
||||
// Update the mixer table:
|
||||
for (int channel=0; channel<8; channel++) {
|
||||
UAVObjectField* field = mixer->getField(mixerTypes.at(channel));
|
||||
@ -843,6 +809,12 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI()
|
||||
QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_YAW)));
|
||||
}
|
||||
}
|
||||
|
||||
// Update feed forward settings
|
||||
m_aircraft->feedForwardSlider->setValue(vconfig->getMixerValue(mixer,"FeedForward") * 100);
|
||||
m_aircraft->accelTime->setValue(vconfig->getMixerValue(mixer,"AccelTime"));
|
||||
m_aircraft->decelTime->setValue(vconfig->getMixerValue(mixer,"DecelTime"));
|
||||
m_aircraft->maxAccelSlider->setValue(vconfig->getMixerValue(mixer,"MaxAccel"));
|
||||
}
|
||||
|
||||
|
||||
@ -855,6 +827,17 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI()
|
||||
*/
|
||||
void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
|
||||
{
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
|
||||
QPointer<VehicleConfig> vconfig = new VehicleConfig();
|
||||
|
||||
// Update feed forward settings
|
||||
vconfig->setMixerValue(mixer, "FeedForward", m_aircraft->feedForwardSlider->value() / 100.0);
|
||||
vconfig->setMixerValue(mixer, "AccelTime", m_aircraft->accelTime->value());
|
||||
vconfig->setMixerValue(mixer, "DecelTime", m_aircraft->decelTime->value());
|
||||
vconfig->setMixerValue(mixer, "MaxAccel", m_aircraft->maxAccelSlider->value());
|
||||
|
||||
QString airframeType = "Custom"; //Sets airframe type default to "Custom"
|
||||
if (m_aircraft->aircraftType->currentText() == "Fixed Wing") {
|
||||
airframeType = m_fixedwing->updateConfigObjectsFromWidgets();
|
||||
@ -869,12 +852,6 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
|
||||
airframeType = m_groundvehicle->updateConfigObjectsFromWidgets();
|
||||
}
|
||||
else {
|
||||
|
||||
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
|
||||
VehicleConfig* vconfig = new VehicleConfig();
|
||||
|
||||
vconfig->setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->customThrottle1Curve->getCurve());
|
||||
vconfig->setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, m_aircraft->customThrottle2Curve->getCurve());
|
||||
|
||||
|
@ -3559,17 +3559,17 @@
|
||||
guidetolerance="10"
|
||||
inkscape:pageopacity="0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:window-width="1920"
|
||||
inkscape:window-height="1088"
|
||||
inkscape:window-width="1680"
|
||||
inkscape:window-height="1002"
|
||||
id="namedview4185"
|
||||
showgrid="false"
|
||||
inkscape:zoom="0.25"
|
||||
inkscape:cx="2447.9751"
|
||||
inkscape:cy="482.05665"
|
||||
inkscape:zoom="0.5"
|
||||
inkscape:cx="2129.6843"
|
||||
inkscape:cy="654.00839"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="0"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:current-layer="g4191"
|
||||
inkscape:window-maximized="0"
|
||||
inkscape:current-layer="quad-hexa-H"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
@ -3737,13 +3737,6 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path5107"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
id="g5119"
|
||||
transform="matrix(82.988968,0,0,-64.991364,969.49512,1428.5608)"><image
|
||||
width="1"
|
||||
height="1"
|
||||
transform="matrix(1,0,0,-1,0,1)"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAFMAAABBCAYAAACtrJiQAAAABHNCSVQICAgIfAhkiAAADhxJREFUeJztnGt0HOV5x38zs5fZ++rqi6z73RfJsiQjOxDbhdQ3TIAPLSTpCYXGQNKeHpKU0LRJOKXknPRDD5Rwjg9Q04T0cCnQNjUXAwZh2ZZtbMzFtizJ1gVZ1tpaSXuf3ZmdmX6QpeAaYwuvbalHvy+rM6PZeeY/z/M+z/u8MyvULVliMktGEK+1Af+fmBUzg8yKmUFmxcwgs2JmEMtUDzDN8eQvCMLk37OMM2UxYVzIz3/OMs6Uw3xWwAszZTFnQ/vCzCagDDIrZgb5SgnoWiOKIol4nHg8jtVqweX2YLFYrvkQNOM8U5IkQmOjOJxOrl+1hsrqhcRjUYLDZzBNE1G8dpc0ozxTEARGR0YoKinll48+QmlZGaGxMT49fIT/ePlV2nfvxCE78Pn96Lp+1e2bUZ5pGAaapnLnt+6kqXk5gydPomkaq9es4sknH+eBH/0IQRQ4HRhCEISrXsZJc+bMeXiqB12rWlNJJMjLn8Nd3/0zFEUhlUqh6zpjoyOkkilWr17DyhUrOHy4g96e48gOx1UdS2eMZwqCQCIRp7K6lsLCQmKx2OQ+UZRIJhW6Ojsor6jg2WefZt3GWwgOnyERjyNJ0lWxccaIOeFddXWLsdllDOPcMVEQRERRor+vl1RK5Z9+9Uv+4r7vE4tFGR0ZuSqCzpgwV1UVuyzzne98G7/XQ0JJAmCaBoIgMH/+PHLz8jEMg2AwiKqqrFu7lqKSItrb9zISHMblcl9R22eMZ8ZjMUrLK6mqrCQUDk1uFwQRn8/Lttff5LHHn2B0dJSq6moAOo8dZcOGjWzd+gwLF9dzOjBEMpm8Yl6aAc8UABNTTyMIIlzszgsCCCJ6YgRDiSBaZRAtwIWThCAIRKMR1m+8mdWrv04wGJy0IT8vj86ubh568EH272unrW0XsbjCyhUt+Hxejnd3U1RUxK23bkIzBA7s34eqqTidrownpsv3TFNHEG1YvQXoyRBaaAg9GQIjzbjQZxFEMHXSkdOoY4M4CprxLfk26cQo6WjgrKBffCPSmobT6WRp/WKSijJ+0xgPcZfHw4GDh9DTaRYsKCISCbPlySfYfN8P6OvrZ9HiJQSDZwiFw/z0oQd55NF/BNPkzOlAxj00A55pYKYVHHObKLzhYexzGtCi/aSjAfR4CDOtACbp2AimlsRZtJK5K3/O4q/fTvGyFYh5G0lGT5KODCCIX+zZsViU0rJKvnXnHSiKMlmQi6KILMu8+NLL9Pf14HA6kWUHLreb3p7jbH9zO4IksnLl17BZrfT29nLdihaamprYu28/gcAQHo/nK0p3PpcvpiCBaaIGj6JjoaZlHVU3/imuwk0IWXWYGBipMTxlaym96VFqv7aRuRXz0RQNNZxkwbIFGK4Ghg/+OxabzFgohJJQcDgck4V3JBKmsWk5N9+8kbHR0clTu9xugsFhXnzhRVQ1hc1mn9zn9XpREgnef7+VQx9/Sk1VBQsXLeHU4ElKSktZv24d+/cfpL+/F4/Hm5GQz0g2FyQLglUm/tkuTh54AYUmyprLKGlZRE5eEzkVN1O27Hqy5nhRYymSkSSmbmACkiTQ91E70RNvowk2Vq25kezcPLo7O1BTKRwOJ0oiwbr162lsXEY49Ifkk5uTw8FDH/Latm04nK5z5uWmaSI7HDidTo53dbJ9+9skVY1lDfXoaQ2Hw8natTfR2trGmdNDOF2XP4ZmtDSyOvxg6ox1vMzJj1sxLMvJKfRjEUXUhEYqlsI0zMmR0WIRSSsaPTt/TTISAIudR/7hF9x99914/T4GBgbpOdGN35/Nw7/4OQIQjUYQBBHTNMjNy2fHu63sa9+D231+uJqmiSAIeL0+kqkku9t2smvPXhobG3G5nPizsikomM87b7+NJEmX3STJaGlkGGkEuxtbdgHqaA9Hn7uFI7s+RLKKmLpxXnoRLRJKMo0eHyKVNigsLMHhcDJ8JsCdd97B009tYfP9f4nT6WTrvz0HQElp2eTNVNUUPT29F7VL13Xcbg9z582ns+MIP/27nxGPJxgdCbJsaT2L6pYSjUYu+/ozX2eaJpgGVt88JKuNwR0/JDSqYHfbz/tXTU3j8dqpumULaUOguDCfvPx8QqEwx7u6ME2Tnzz4Yx5//DH6+/u5+557eeHFF1lQWEhZeQVDp4Y43t2FLDsuwSwT0zSZM3cevT3Had3ZhtvjweFyU15RSTqdvuxLv2JFu2noSO48jFSSzzr3Y/Xaz6kkTUEAw8TilTGtEoKpU1VTg2QZL1dEUSIajdBx5DALCubz6yce47bbb+XNN95i873389GhQwwHgwSGBnE4Li7m5xEFkVgsjiiOn8vtcmXkmq9sP9M0Ea12wkefJ1m3AqtNIq3qk/sESUS0WRj85C1kSaCmZhFKLD55uCCICAKcGR5GCI5w+2238s1NN/Psb57jN797noH+PmLRKM6zyccwjEswyUSySHg8LgxDR5IsmObFj7sUrnBz2ERyZaOcOkLviR5qmxcTDUQRAJvdQkLR2P2vDxPofIfyqlpKy0oJR84fuyaK9M/6+7BYrGz+3j2MjY6yc9dutm9/i317dmG1WsnKzhk/65dkZdM0kSQJj9uNaRggfdnca2pc+bm5IIAoMnLkeXRFQ5JETMDmlRkZjRPu2IaaUiivbSAnJ5dUKnVhY0UJwzDo7+slHo/zzVs28S+P/zN/+/c/o6i4jEBgiHA4hCiKF6w4TMPAarXhcrkmi/9MTSuvvJimicWdQ7xvF4ODEXxVuTh9MoJVJDzQDqKAINmpriieHC8vhiCMh3Rfbw/B4SB33PEnPPPMFv7qrx8gOzuHoVODxGOxL5wu6oaBzWZDlmU0LT2emIyZIiYgSDZEi4UTr/+Qg6++zXAgih5XUc4cQDcF/D4fNTXVJKLRKX2vKEqoqsrxri60tM59927m6ae38N27v4dksTB0ahBVVc8t5g0Du92Oy+lA18czuDEzxsyzmAaSMxctMsDgjr/htNOHPLcBLdyLKtgoKiikvr4Ot8eLqmmEw5GzfcpLu9eiKBGLRuiKhMnOzuahhx5kw9obeWrrb9nT1ko4NIbPn4Usy+iGjs0uY7fLpPXMiDjB1WsOmwaiRUZy+AADbeQ4iCIWu4O0pnLg4EecGjpFTlYW5RUVeDxeVFVF09RLOt/4PF5EURSCw2dYUFjIhvXrWNrQgI5E97GjhCNhTMMkJyePTZvWI4giTqeL9r37OfzJRzgvs0S6+ku9poEg2ZDcuQDYJYlUKsXune/R1rqDl+YXsKz5Ola2NNPc3Ex5ZSWJWIzh4DBpLX1Rb50opwKBAKIoUV+3hOXLl9O+YS2//d3zvLdjOwWFheTlzyEwFBhPPhlKQNd83VzXdSRJIjcvH4BIOMy2/3qFN1/7PZWVNTQub2bFdc001Nfj9nkZDQYJhyMYhv6lwo7P300GBwcRRYmm5mYaGhrY9voaykqKz37HeJhnqs6cdmtAssOB3WZHSSQYHBzgw4Mf8H5rK4c+OUJobAyvx01xSQnZubmIgoCqqmeF/WKbJraHQmMkUwqNjcuQZZmxsTEkScLr89G+dx+HP/3kssN82okZjUQoLi3n/h98H5fbh9VqIxwK0dV5lLa2nezZs5cjHZ2EQiHsNgvFxcXk5OWhaSqapk0usJ1vs4hpmEQjUVRVnSybvD4fe/d9wOFPPp6BY+aXMLE2Xrd0Kfdu3syG9Ws5fTpAT08fe/d9wMEPDnBqcIB3tr/Bu29tx5+VxeK6paxZs4rGZfWUlJaiqilGgiMkk8olVwP/d9n4qzKtxEyn08iyTN2SWgYG+hk6NYTskFmxooXVq1cTj0Z54Mc/4dCBffizskkmk7S17mDX++9RVFJKY1MzK1uaqa+vZ35BAbFImODI6JeOr4ahMzYWyki0TSsxlUSCgsJiaqtrCIVCmKaJklBIxOO4PV4MQyc0OorFYgVAlmUcDgeGYRAYGuSVl46z7b9fpbyyhutaWlh1w0pqF9Zis9kZCQaJRqPn1K9Ol5NwOEJfTw82+/ktwqkyrcRMJhVqFi5ifkEBJwcGJrdPrI3v2PEu/X0ncH2uqz7RTfd4vPh8fjRNo7vzKEcPf8x/vvISi+saWLniOpoal1FeUQHAyMgIaU2jqrqWrVu30t11jOycnMu2f1qJCVBdVX72Yas/eJBpGthsdjqOdZNKpfD5s76wOWEYBpIkTXaPkskku3e+x+6d7zFvfgH1DY20tDRTv2QJebm5vLbtf3hqyxZsdhuiKF52w2PaiKlpKm6Pl4rycuJn13kmsNmshMZGOXL4MBaL9aIXPbHfbrcj58/BNE3CoRBvvPZ73tn+OkXFZfj8fjo7jmAYBllZ2RnptE8bMePxOLULF1NdVUU4cm7Dw+320tPTQ39fz5TLlwlhnS4XLrcbXdcZGjrJZ5/14nK5xufoGRASptGzRpqq8o1v3ERVTS3JpHLOrMTldtPT1084FMJms33lc0w8pu1yufH7s7BabZfUnb9UpoWYpmnicDjZt/8Ae3a1UVVdy7x58xAEAcPQsVgsnBoKkNbT0/qlrmkR5oIg4PP7ad+9k48OfsCmW2/jj2/6I5bU1WEYOkoizrGOY4iXWIRfK4Sp/qzERClyJZAkiXgsRjQaweVy03L9Ddy/+R5cLjd33fXnJOJx5CmuRF5NppWYE4jieF8yEg6Rm5dPWUUVJ7o7r+lrKZfCtBRzAlEUSSQSJJMKfn/WtH8te1qMmRfCMAxkWUaWZWD6vwQ7veNmhjErZgaZFTODzIqZQWbFzCBfKZtP96x6rZiymNN5bnytmQ3zDDIrZgaZFTOD/C9uew7sSK2nLAAAAABJRU5ErkJggg=="
|
||||
id="image5121" /></g><g
|
||||
transform="matrix(1,0,0,-1,0,2792.2535)"
|
||||
id="g5149"><g
|
||||
clip-path="url(#clipPath5135)"
|
||||
@ -3984,13 +3977,6 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path5525"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
id="g5537"
|
||||
transform="matrix(82.988968,0,0,64.991364,1584.0928,1351.8216)"><image
|
||||
width="1"
|
||||
height="1"
|
||||
transform="matrix(1,0,0,-1,0,1)"
|
||||
xlink:href="data:image/png;base64,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"
|
||||
id="image5539" /></g><g
|
||||
id="g5567"><g
|
||||
clip-path="url(#clipPath5553)"
|
||||
id="g5569"
|
||||
@ -4599,7 +4585,7 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path6575"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
transform="matrix(1,0,0,-1,0,2590.6553)"
|
||||
transform="matrix(1,0,0,-1,-1.6,2590.6553)"
|
||||
id="g6595"><g
|
||||
clip-path="url(#clipPath6581)"
|
||||
id="g6597"
|
||||
@ -4612,7 +4598,7 @@
|
||||
style="fill:url(#radialGradient22758);fill-opacity:1;stroke:none"
|
||||
id="path6607"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g></g></g><g
|
||||
transform="matrix(1,0,0,-1,0,2590.6553)"
|
||||
transform="matrix(1,0,0,-1,-1.6,2590.6553)"
|
||||
id="g6627"><g
|
||||
clip-path="url(#clipPath6613)"
|
||||
id="g6629"
|
||||
@ -4689,7 +4675,7 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path6751"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
transform="matrix(1,0,0,-1,0,2590.6553)"
|
||||
transform="matrix(1,0,0,-1,-1.6,2590.6553)"
|
||||
id="g6771"><g
|
||||
clip-path="url(#clipPath6757)"
|
||||
id="g6773"
|
||||
@ -4930,7 +4916,8 @@
|
||||
style="fill:url(#radialGradient28751);stroke:none"
|
||||
id="path4727"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g></g></g><g
|
||||
id="g4747"><g
|
||||
id="g4747"
|
||||
transform="matrix(1,0,0,-1,0,1873.22)"><g
|
||||
clip-path="url(#clipPath4733)"
|
||||
id="g4749"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -4964,7 +4951,8 @@
|
||||
style="fill:url(#radialGradient28755);stroke:none"
|
||||
id="path4807"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g></g></g><g
|
||||
id="g4827"><g
|
||||
id="g4827"
|
||||
transform="matrix(1,0,0,-1,0,1400.973)"><g
|
||||
clip-path="url(#clipPath4813)"
|
||||
id="g4829"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -4986,7 +4974,8 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path4855"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
id="g4875"><g
|
||||
id="g4875"
|
||||
transform="translate(-3.2,0)"><g
|
||||
clip-path="url(#clipPath4861)"
|
||||
id="g4877"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -5015,13 +5004,6 @@
|
||||
style="fill:url(#linearGradient28763);stroke:none"
|
||||
id="path7717"
|
||||
inkscape:connector-curvature="0" /></g><g
|
||||
id="g7729"
|
||||
transform="matrix(82.988968,0,0,64.991364,958.15723,800.27719)"><image
|
||||
width="1"
|
||||
height="1"
|
||||
transform="matrix(1,0,0,-1,0,1)"
|
||||
xlink:href="data:image/png;base64,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"
|
||||
id="image7731" /></g><g
|
||||
id="g7749"><g
|
||||
clip-path="url(#clipPath7745)"
|
||||
id="g7751"
|
||||
@ -5046,7 +5028,8 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path8093"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
id="g8113"><g
|
||||
id="g8113"
|
||||
transform="matrix(-1,0,0,1,2217.919,0)"><g
|
||||
clip-path="url(#clipPath8099)"
|
||||
id="g8115"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -5058,7 +5041,8 @@
|
||||
style="fill:url(#radialGradient28765);fill-opacity:1;stroke:none"
|
||||
id="path8125"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g></g></g><g
|
||||
id="g8145"><g
|
||||
id="g8145"
|
||||
transform="matrix(-1,0,0,1,2217.919,-2.1498952e-6)"><g
|
||||
clip-path="url(#clipPath8131)"
|
||||
id="g8147"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -5086,7 +5070,8 @@
|
||||
style="fill:none;stroke:#2e2d2d;stroke-width:8.50399971;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path8173"
|
||||
inkscape:connector-curvature="0" /><g
|
||||
id="g8193"><g
|
||||
id="g8193"
|
||||
transform="translate(1.6,0)"><g
|
||||
clip-path="url(#clipPath8179)"
|
||||
id="g8195"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -5136,7 +5121,8 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path8269"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
id="g8289"><g
|
||||
id="g8289"
|
||||
transform="translate(1.6,0)"><g
|
||||
clip-path="url(#clipPath8275)"
|
||||
id="g8291"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -5182,7 +5168,8 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path8361"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
id="g8381"><g
|
||||
id="g8381"
|
||||
transform="matrix(-1,0,0,1,1742.416,0)"><g
|
||||
clip-path="url(#clipPath8367)"
|
||||
id="g8383"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -5194,7 +5181,8 @@
|
||||
style="fill:url(#radialGradient28777);fill-opacity:1;stroke:none"
|
||||
id="path8393"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g></g></g><g
|
||||
id="g8413"><g
|
||||
id="g8413"
|
||||
transform="matrix(-1,0,0,1,1742.416,0)"><g
|
||||
clip-path="url(#clipPath8399)"
|
||||
id="g8415"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -5277,14 +5265,7 @@
|
||||
d="m 1744.1094,831.5313 c 3.205,0 5.801,2.059 5.799,4.599 0,2.539 -2.596,4.598 -5.799,4.598 l -287.732,0 c -3.206,0 -5.801,-2.058 -5.799,-4.599 0,-2.539 2.595,-4.598 5.797,-4.598 l 287.734,0 z"
|
||||
style="fill:none;stroke:#2e2d2d;stroke-width:8.50399971;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path7815"
|
||||
inkscape:connector-curvature="0" /><g
|
||||
id="g7827"
|
||||
transform="matrix(82.988968,0,0,64.991364,1560.6924,803.83481)"><image
|
||||
width="1"
|
||||
height="1"
|
||||
transform="matrix(1,0,0,-1,0,1)"
|
||||
xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAFMAAABBCAYAAACtrJiQAAAABHNCSVQICAgIfAhkiAAADhxJREFUeJztnGt0HOV5x38zs5fZ++rqi6z73RfJsiQjOxDbhdQ3TIAPLSTpCYXGQNKeHpKU0LRJOKXknPRDD5Rwjg9Q04T0cCnQNjUXAwZh2ZZtbMzFtizJ1gVZ1tpaSXuf3ZmdmX6QpeAaYwuvbalHvy+rM6PZeeY/z/M+z/u8MyvULVliMktGEK+1Af+fmBUzg8yKmUFmxcwgs2JmEMtUDzDN8eQvCMLk37OMM2UxYVzIz3/OMs6Uw3xWwAszZTFnQ/vCzCagDDIrZgb5SgnoWiOKIol4nHg8jtVqweX2YLFYrvkQNOM8U5IkQmOjOJxOrl+1hsrqhcRjUYLDZzBNE1G8dpc0ozxTEARGR0YoKinll48+QmlZGaGxMT49fIT/ePlV2nfvxCE78Pn96Lp+1e2bUZ5pGAaapnLnt+6kqXk5gydPomkaq9es4sknH+eBH/0IQRQ4HRhCEISrXsZJc+bMeXiqB12rWlNJJMjLn8Nd3/0zFEUhlUqh6zpjoyOkkilWr17DyhUrOHy4g96e48gOx1UdS2eMZwqCQCIRp7K6lsLCQmKx2OQ+UZRIJhW6Ojsor6jg2WefZt3GWwgOnyERjyNJ0lWxccaIOeFddXWLsdllDOPcMVEQRERRor+vl1RK5Z9+9Uv+4r7vE4tFGR0ZuSqCzpgwV1UVuyzzne98G7/XQ0JJAmCaBoIgMH/+PHLz8jEMg2AwiKqqrFu7lqKSItrb9zISHMblcl9R22eMZ8ZjMUrLK6mqrCQUDk1uFwQRn8/Lttff5LHHn2B0dJSq6moAOo8dZcOGjWzd+gwLF9dzOjBEMpm8Yl6aAc8UABNTTyMIIlzszgsCCCJ6YgRDiSBaZRAtwIWThCAIRKMR1m+8mdWrv04wGJy0IT8vj86ubh568EH272unrW0XsbjCyhUt+Hxejnd3U1RUxK23bkIzBA7s34eqqTidrownpsv3TFNHEG1YvQXoyRBaaAg9GQIjzbjQZxFEMHXSkdOoY4M4CprxLfk26cQo6WjgrKBffCPSmobT6WRp/WKSijJ+0xgPcZfHw4GDh9DTaRYsKCISCbPlySfYfN8P6OvrZ9HiJQSDZwiFw/z0oQd55NF/BNPkzOlAxj00A55pYKYVHHObKLzhYexzGtCi/aSjAfR4CDOtACbp2AimlsRZtJK5K3/O4q/fTvGyFYh5G0lGT5KODCCIX+zZsViU0rJKvnXnHSiKMlmQi6KILMu8+NLL9Pf14HA6kWUHLreb3p7jbH9zO4IksnLl17BZrfT29nLdihaamprYu28/gcAQHo/nK0p3PpcvpiCBaaIGj6JjoaZlHVU3/imuwk0IWXWYGBipMTxlaym96VFqv7aRuRXz0RQNNZxkwbIFGK4Ghg/+OxabzFgohJJQcDgck4V3JBKmsWk5N9+8kbHR0clTu9xugsFhXnzhRVQ1hc1mn9zn9XpREgnef7+VQx9/Sk1VBQsXLeHU4ElKSktZv24d+/cfpL+/F4/Hm5GQz0g2FyQLglUm/tkuTh54AYUmyprLKGlZRE5eEzkVN1O27Hqy5nhRYymSkSSmbmACkiTQ91E70RNvowk2Vq25kezcPLo7O1BTKRwOJ0oiwbr162lsXEY49Ifkk5uTw8FDH/Latm04nK5z5uWmaSI7HDidTo53dbJ9+9skVY1lDfXoaQ2Hw8natTfR2trGmdNDOF2XP4ZmtDSyOvxg6ox1vMzJj1sxLMvJKfRjEUXUhEYqlsI0zMmR0WIRSSsaPTt/TTISAIudR/7hF9x99914/T4GBgbpOdGN35/Nw7/4OQIQjUYQBBHTNMjNy2fHu63sa9+D231+uJqmiSAIeL0+kqkku9t2smvPXhobG3G5nPizsikomM87b7+NJEmX3STJaGlkGGkEuxtbdgHqaA9Hn7uFI7s+RLKKmLpxXnoRLRJKMo0eHyKVNigsLMHhcDJ8JsCdd97B009tYfP9f4nT6WTrvz0HQElp2eTNVNUUPT29F7VL13Xcbg9z582ns+MIP/27nxGPJxgdCbJsaT2L6pYSjUYu+/ozX2eaJpgGVt88JKuNwR0/JDSqYHfbz/tXTU3j8dqpumULaUOguDCfvPx8QqEwx7u6ME2Tnzz4Yx5//DH6+/u5+557eeHFF1lQWEhZeQVDp4Y43t2FLDsuwSwT0zSZM3cevT3Had3ZhtvjweFyU15RSTqdvuxLv2JFu2noSO48jFSSzzr3Y/Xaz6kkTUEAw8TilTGtEoKpU1VTg2QZL1dEUSIajdBx5DALCubz6yce47bbb+XNN95i873389GhQwwHgwSGBnE4Li7m5xEFkVgsjiiOn8vtcmXkmq9sP9M0Ea12wkefJ1m3AqtNIq3qk/sESUS0WRj85C1kSaCmZhFKLD55uCCICAKcGR5GCI5w+2238s1NN/Psb57jN797noH+PmLRKM6zyccwjEswyUSySHg8LgxDR5IsmObFj7sUrnBz2ERyZaOcOkLviR5qmxcTDUQRAJvdQkLR2P2vDxPofIfyqlpKy0oJR84fuyaK9M/6+7BYrGz+3j2MjY6yc9dutm9/i317dmG1WsnKzhk/65dkZdM0kSQJj9uNaRggfdnca2pc+bm5IIAoMnLkeXRFQ5JETMDmlRkZjRPu2IaaUiivbSAnJ5dUKnVhY0UJwzDo7+slHo/zzVs28S+P/zN/+/c/o6i4jEBgiHA4hCiKF6w4TMPAarXhcrkmi/9MTSuvvJimicWdQ7xvF4ODEXxVuTh9MoJVJDzQDqKAINmpriieHC8vhiCMh3Rfbw/B4SB33PEnPPPMFv7qrx8gOzuHoVODxGOxL5wu6oaBzWZDlmU0LT2emIyZIiYgSDZEi4UTr/+Qg6++zXAgih5XUc4cQDcF/D4fNTXVJKLRKX2vKEqoqsrxri60tM59927m6ae38N27v4dksTB0ahBVVc8t5g0Du92Oy+lA18czuDEzxsyzmAaSMxctMsDgjr/htNOHPLcBLdyLKtgoKiikvr4Ot8eLqmmEw5GzfcpLu9eiKBGLRuiKhMnOzuahhx5kw9obeWrrb9nT1ko4NIbPn4Usy+iGjs0uY7fLpPXMiDjB1WsOmwaiRUZy+AADbeQ4iCIWu4O0pnLg4EecGjpFTlYW5RUVeDxeVFVF09RLOt/4PF5EURSCw2dYUFjIhvXrWNrQgI5E97GjhCNhTMMkJyePTZvWI4giTqeL9r37OfzJRzgvs0S6+ku9poEg2ZDcuQDYJYlUKsXune/R1rqDl+YXsKz5Ola2NNPc3Ex5ZSWJWIzh4DBpLX1Rb50opwKBAKIoUV+3hOXLl9O+YS2//d3zvLdjOwWFheTlzyEwFBhPPhlKQNd83VzXdSRJIjcvH4BIOMy2/3qFN1/7PZWVNTQub2bFdc001Nfj9nkZDQYJhyMYhv6lwo7P300GBwcRRYmm5mYaGhrY9voaykqKz37HeJhnqs6cdmtAssOB3WZHSSQYHBzgw4Mf8H5rK4c+OUJobAyvx01xSQnZubmIgoCqqmeF/WKbJraHQmMkUwqNjcuQZZmxsTEkScLr89G+dx+HP/3kssN82okZjUQoLi3n/h98H5fbh9VqIxwK0dV5lLa2nezZs5cjHZ2EQiHsNgvFxcXk5OWhaSqapk0usJ1vs4hpmEQjUVRVnSybvD4fe/d9wOFPPp6BY+aXMLE2Xrd0Kfdu3syG9Ws5fTpAT08fe/d9wMEPDnBqcIB3tr/Bu29tx5+VxeK6paxZs4rGZfWUlJaiqilGgiMkk8olVwP/d9n4qzKtxEyn08iyTN2SWgYG+hk6NYTskFmxooXVq1cTj0Z54Mc/4dCBffizskkmk7S17mDX++9RVFJKY1MzK1uaqa+vZ35BAbFImODI6JeOr4ahMzYWyki0TSsxlUSCgsJiaqtrCIVCmKaJklBIxOO4PV4MQyc0OorFYgVAlmUcDgeGYRAYGuSVl46z7b9fpbyyhutaWlh1w0pqF9Zis9kZCQaJRqPn1K9Ol5NwOEJfTw82+/ktwqkyrcRMJhVqFi5ifkEBJwcGJrdPrI3v2PEu/X0ncH2uqz7RTfd4vPh8fjRNo7vzKEcPf8x/vvISi+saWLniOpoal1FeUQHAyMgIaU2jqrqWrVu30t11jOycnMu2f1qJCVBdVX72Yas/eJBpGthsdjqOdZNKpfD5s76wOWEYBpIkTXaPkskku3e+x+6d7zFvfgH1DY20tDRTv2QJebm5vLbtf3hqyxZsdhuiKF52w2PaiKlpKm6Pl4rycuJn13kmsNmshMZGOXL4MBaL9aIXPbHfbrcj58/BNE3CoRBvvPZ73tn+OkXFZfj8fjo7jmAYBllZ2RnptE8bMePxOLULF1NdVUU4cm7Dw+320tPTQ39fz5TLlwlhnS4XLrcbXdcZGjrJZ5/14nK5xufoGRASptGzRpqq8o1v3ERVTS3JpHLOrMTldtPT1084FMJms33lc0w8pu1yufH7s7BabZfUnb9UpoWYpmnicDjZt/8Ae3a1UVVdy7x58xAEAcPQsVgsnBoKkNbT0/qlrmkR5oIg4PP7ad+9k48OfsCmW2/jj2/6I5bU1WEYOkoizrGOY4iXWIRfK4Sp/qzERClyJZAkiXgsRjQaweVy03L9Ddy/+R5cLjd33fXnJOJx5CmuRF5NppWYE4jieF8yEg6Rm5dPWUUVJ7o7r+lrKZfCtBRzAlEUSSQSJJMKfn/WtH8te1qMmRfCMAxkWUaWZWD6vwQ7veNmhjErZgaZFTODzIqZQWbFzCBfKZtP96x6rZiymNN5bnytmQ3zDDIrZgaZFTOD/C9uew7sSK2nLAAAAABJRU5ErkJggg=="
|
||||
id="image7829" /></g><path
|
||||
inkscape:connector-curvature="0" /><path
|
||||
d="m 1572.6621,870.1445 62.131,0 c 1.629,0 2.953,-1.32 2.953,-2.95 l 0,-62.127 c 0,-1.63 -1.324,-2.954 -2.953,-2.954 l -62.131,0 c -1.631,0 -2.947,1.324 -2.947,2.954 l 0,62.127 c 0,1.63 1.316,2.95 2.947,2.95"
|
||||
style="fill:#2f2d2e;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path7841"
|
||||
@ -5309,7 +5290,8 @@
|
||||
id="path8557"
|
||||
inkscape:connector-curvature="0" /></g><g
|
||||
style="opacity:0.69999701"
|
||||
id="g8581"><g
|
||||
id="g8581"
|
||||
transform="translate(-3.2,0)"><g
|
||||
id="g8583"><g
|
||||
id="g8585"><g
|
||||
id="g8587"><path
|
||||
@ -5384,7 +5366,8 @@
|
||||
id="path8765"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g><g
|
||||
style="opacity:0.69999701"
|
||||
id="g8789"><g
|
||||
id="g8789"
|
||||
transform="matrix(1,0,0,-1,0,1636.441)"><g
|
||||
id="g8791"><g
|
||||
id="g8793"><g
|
||||
id="g8795"><path
|
||||
@ -5404,7 +5387,8 @@
|
||||
id="path8817"
|
||||
inkscape:connector-curvature="0" /></g><g
|
||||
style="opacity:0.69999701"
|
||||
id="g8841"><g
|
||||
id="g8841"
|
||||
transform="matrix(-1,0,0,1,2889.862,0)"><g
|
||||
id="g8843"><g
|
||||
id="g8845"><g
|
||||
id="g8847"><path
|
||||
@ -5413,7 +5397,8 @@
|
||||
id="path8849"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g><g
|
||||
style="opacity:0.69999701"
|
||||
id="g8873"><g
|
||||
id="g8873"
|
||||
transform="matrix(-1,0,0,1,2889.862,0)"><g
|
||||
id="g8875"><g
|
||||
id="g8877"><g
|
||||
id="g8879"><path
|
||||
@ -5450,7 +5435,8 @@
|
||||
id="path8941"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g><g
|
||||
style="opacity:0.69999701"
|
||||
id="g8965"><g
|
||||
id="g8965"
|
||||
transform="matrix(1,0,0,-1,0,1652.875)"><g
|
||||
id="g8967"><g
|
||||
id="g8969"><g
|
||||
id="g8971"><path
|
||||
@ -5470,7 +5456,8 @@
|
||||
id="path8993"
|
||||
inkscape:connector-curvature="0" /></g><g
|
||||
style="opacity:0.69999701"
|
||||
id="g9017"><g
|
||||
id="g9017"
|
||||
transform="matrix(-1,0,0,1,3526.988,0)"><g
|
||||
id="g9019"><g
|
||||
id="g9021"><g
|
||||
id="g9023"><path
|
||||
@ -5480,7 +5467,8 @@
|
||||
inkscape:connector-curvature="0" /></g></g></g></g><g
|
||||
style="opacity:0.69999701"
|
||||
id="g9049"><g
|
||||
id="g9051"><g
|
||||
id="g9051"
|
||||
transform="matrix(-1,0,0,1,3526.988,0)"><g
|
||||
id="g9053"><g
|
||||
id="g9055"><path
|
||||
d="m 1691.348,852.575 c 1.295,31.435 27.177,56.539 58.929,56.526 23.84,0.005 44.364,-14.143 53.666,-34.5 L 1786.5,857.157 c -3.242,9.352 -12.109,16.07 -22.572,16.068 -12.092,0.007 -22.065,-8.991 -23.662,-20.65 l 11.105,0 -10.303,-10.302 -17.845,-17.844 -7.455,-7.456 -35.602,35.602 11.182,0 z"
|
||||
@ -5507,7 +5495,8 @@
|
||||
id="path9085"
|
||||
inkscape:connector-curvature="0" /></g><g
|
||||
style="opacity:0.69999701"
|
||||
id="g9109"><g
|
||||
id="g9109"
|
||||
transform="translate(-3.2,0)"><g
|
||||
id="g9111"><g
|
||||
id="g9113"><g
|
||||
id="g9115"><path
|
||||
@ -5597,13 +5586,6 @@
|
||||
style="fill:none;stroke:#2e2d2d;stroke-width:8.50399971;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="path7131"
|
||||
inkscape:connector-curvature="0" /><g
|
||||
id="g7143"
|
||||
transform="matrix(82.988968,0,0,64.991364,2254.6221,743.15219)"><image
|
||||
width="1"
|
||||
height="1"
|
||||
transform="matrix(1,0,0,-1,0,1)"
|
||||
xlink:href="data:image/png;base64,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"
|
||||
id="image7145" /></g><g
|
||||
id="g7163"><g
|
||||
clip-path="url(#clipPath7159)"
|
||||
id="g7165"
|
||||
@ -5774,7 +5756,8 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path7513"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
id="g7533"><g
|
||||
id="g7533"
|
||||
transform="translate(-3.2,0)"><g
|
||||
clip-path="url(#clipPath7519)"
|
||||
id="g7535"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -5786,7 +5769,8 @@
|
||||
style="fill:url(#radialGradient25755);fill-opacity:1;stroke:none"
|
||||
id="path7545"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g></g></g><g
|
||||
id="g7565"><g
|
||||
id="g7565"
|
||||
transform="translate(-1.6,0)"><g
|
||||
clip-path="url(#clipPath7551)"
|
||||
id="g7567"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -5936,13 +5920,6 @@
|
||||
style="fill:url(#linearGradient27799);stroke:none"
|
||||
id="path9269"
|
||||
inkscape:connector-curvature="0" /></g><g
|
||||
id="g9281"
|
||||
transform="matrix(82.988968,0,0,64.991364,2988.165,565.90805)"><image
|
||||
width="1"
|
||||
height="1"
|
||||
transform="matrix(1,0,0,-1,0,1)"
|
||||
xlink:href="data:image/png;base64,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"
|
||||
id="image9283" /></g><g
|
||||
id="g9301"><g
|
||||
clip-path="url(#clipPath9297)"
|
||||
id="g9303"
|
||||
@ -6079,7 +6056,8 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path9571"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
id="g9591"><g
|
||||
id="g9591"
|
||||
transform="translate(-3.2,0)"><g
|
||||
clip-path="url(#clipPath9577)"
|
||||
id="g9593"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -6091,7 +6069,8 @@
|
||||
style="fill:url(#radialGradient27813);fill-opacity:1;stroke:none"
|
||||
id="path9603"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g></g></g><g
|
||||
id="g9623"><g
|
||||
id="g9623"
|
||||
transform="translate(-1.6,0)"><g
|
||||
clip-path="url(#clipPath9609)"
|
||||
id="g9625"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -6155,7 +6134,8 @@
|
||||
style="fill:#b1c7eb;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
||||
id="path9739"
|
||||
inkscape:connector-curvature="0" /></g></g></g><g
|
||||
id="g9759"><g
|
||||
id="g9759"
|
||||
transform="translate(-3.2,0)"><g
|
||||
clip-path="url(#clipPath9745)"
|
||||
id="g9761"
|
||||
style="opacity:0.69999701"><g
|
||||
@ -6167,7 +6147,8 @@
|
||||
style="fill:url(#radialGradient27821);fill-opacity:1;stroke:none"
|
||||
id="path9771"
|
||||
inkscape:connector-curvature="0" /></g></g></g></g></g></g><g
|
||||
id="g9791"><g
|
||||
id="g9791"
|
||||
transform="translate(-1.6,0)"><g
|
||||
clip-path="url(#clipPath9777)"
|
||||
id="g9793"
|
||||
style="opacity:0.69999701"><g
|
Before Width: | Height: | Size: 436 KiB After Width: | Height: | Size: 407 KiB |
@ -204,31 +204,12 @@
|
||||
<attribute name="title">
|
||||
<string>Flight Mode Switch Settings</string>
|
||||
</attribute>
|
||||
<widget class="QLabel" name="label_16">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>310</x>
|
||||
<y>30</y>
|
||||
<width>201</width>
|
||||
<height>17</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>for multirotors!</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>30</x>
|
||||
<y>160</y>
|
||||
<width>451</width>
|
||||
<y>260</y>
|
||||
<width>541</width>
|
||||
<height>161</height>
|
||||
</rect>
|
||||
</property>
|
||||
@ -401,25 +382,177 @@ margin:1px;</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<spacer name="verticalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<widget class="QGroupBox" name="groupBox_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>30</x>
|
||||
<y>30</y>
|
||||
<width>451</width>
|
||||
<height>121</height>
|
||||
<y>20</y>
|
||||
<width>541</width>
|
||||
<height>211</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>FlightMode Switch Positions</string>
|
||||
</property>
|
||||
<widget class="QComboBox" name="fmsModePos5">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>100</x>
|
||||
<y>140</y>
|
||||
<width>151</width>
|
||||
<height>26</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QComboBox" name="fmsModePos4">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>100</x>
|
||||
<y>110</y>
|
||||
<width>151</width>
|
||||
<height>26</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Select the stabilization mode on this position (manual/stabilized/auto)</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_pos4">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>10</x>
|
||||
<y>115</y>
|
||||
<width>62</width>
|
||||
<height>17</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pos. 4</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QComboBox" name="fmsModePos6">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>100</x>
|
||||
<y>170</y>
|
||||
<width>151</width>
|
||||
<height>26</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_pos5">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>10</x>
|
||||
<y>145</y>
|
||||
<width>62</width>
|
||||
<height>17</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pos. 5</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_pos6">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>10</x>
|
||||
<y>175</y>
|
||||
<width>62</width>
|
||||
<height>17</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pos. 6</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QSlider" name="fmsSlider">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>70</x>
|
||||
<y>28</y>
|
||||
<width>20</width>
|
||||
<height>160</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>This slider moves when you move the flight mode switch
|
||||
on your remote. It shows currently active flight mode.
|
||||
|
||||
Setup the flight mode channel on the RC Input tab if you have not done so already.</string>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>5</number>
|
||||
</property>
|
||||
<property name="pageStep">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="invertedAppearance">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>1</number>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QComboBox" name="fmsModePos2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>100</x>
|
||||
<y>55</y>
|
||||
<y>50</y>
|
||||
<width>151</width>
|
||||
<height>26</height>
|
||||
</rect>
|
||||
@ -432,7 +565,20 @@ margin:1px;</string>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>100</x>
|
||||
<y>25</y>
|
||||
<y>80</y>
|
||||
<width>151</width>
|
||||
<height>26</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QComboBox" name="fmsModePos1">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>100</x>
|
||||
<y>20</y>
|
||||
<width>151</width>
|
||||
<height>26</height>
|
||||
</rect>
|
||||
@ -444,37 +590,11 @@ margin:1px;</string>
|
||||
<string>Select the stabilization mode on this position (manual/stabilized/auto)</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_11">
|
||||
<widget class="QLabel" name="label_pos2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>10</x>
|
||||
<y>30</y>
|
||||
<width>62</width>
|
||||
<height>17</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pos. 3</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QComboBox" name="fmsModePos1">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>100</x>
|
||||
<y>85</y>
|
||||
<width>151</width>
|
||||
<height>26</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_12">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>10</x>
|
||||
<y>60</y>
|
||||
<x>11</x>
|
||||
<y>55</y>
|
||||
<width>62</width>
|
||||
<height>17</height>
|
||||
</rect>
|
||||
@ -483,11 +603,11 @@ margin:1px;</string>
|
||||
<string>Pos. 2</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_13">
|
||||
<widget class="QLabel" name="label_pos1">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>10</x>
|
||||
<y>90</y>
|
||||
<x>11</x>
|
||||
<y>25</y>
|
||||
<width>62</width>
|
||||
<height>17</height>
|
||||
</rect>
|
||||
@ -496,55 +616,68 @@ margin:1px;</string>
|
||||
<string>Pos. 1</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QSlider" name="fmsSlider">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<widget class="QLabel" name="label_pos3">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>70</x>
|
||||
<y>30</y>
|
||||
<width>20</width>
|
||||
<height>81</height>
|
||||
<x>11</x>
|
||||
<y>85</y>
|
||||
<width>62</width>
|
||||
<height>17</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
<property name="text">
|
||||
<string>Pos. 3</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QSpinBox" name="fmsPosNum">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>458</x>
|
||||
<y>20</y>
|
||||
<width>61</width>
|
||||
<height>20</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>This slider moves when you move the flight mode switch
|
||||
on your remote. Setup the flightmode channel on the RC Input tab
|
||||
if you have not done so already.</string>
|
||||
<string>Number of positions your FlightMode switch has.
|
||||
|
||||
Default is 3.
|
||||
|
||||
It will be 2 or 3 for most of setups, but it also can be up to 6.
|
||||
In that case you have to configure your radio mixers so the whole range
|
||||
from min to max is split into N equal intervals, and you may set arbitrary
|
||||
channel value for each flight mode.</string>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>-100</number>
|
||||
<number>1</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="pageStep">
|
||||
<number>10</number>
|
||||
<property name="value">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>-100</number>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>277</x>
|
||||
<y>22</y>
|
||||
<width>171</width>
|
||||
<height>16</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>100</number>
|
||||
<property name="text">
|
||||
<string>Number of flight modes:</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_15">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>270</x>
|
||||
<y>30</y>
|
||||
<width>141</width>
|
||||
<height>31</height>
|
||||
<x>310</x>
|
||||
<y>120</y>
|
||||
<width>191</width>
|
||||
<height>30</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
@ -554,13 +687,15 @@ if you have not done so already.</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Warning: avoid "Manual"</string>
|
||||
<string>Avoid "Manual" for multirotors!</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<zorder>groupBox_2</zorder>
|
||||
<zorder>groupBox</zorder>
|
||||
</widget>
|
||||
<widget class="QWidget" name="tab_4">
|
||||
<attribute name="title">
|
||||
@ -750,9 +885,6 @@ Applies and Saves all settings to SD</string>
|
||||
</widget>
|
||||
<tabstops>
|
||||
<tabstop>fmsSlider</tabstop>
|
||||
<tabstop>fmsModePos3</tabstop>
|
||||
<tabstop>fmsModePos2</tabstop>
|
||||
<tabstop>fmsModePos1</tabstop>
|
||||
<tabstop>fmsSsPos1Roll</tabstop>
|
||||
<tabstop>fmsSsPos1Pitch</tabstop>
|
||||
<tabstop>fmsSsPos1Yaw</tabstop>
|
||||
|
@ -1,8 +1,22 @@
|
||||
<gcs>
|
||||
<General>
|
||||
<OverrideLanguage>en_AU</OverrideLanguage>
|
||||
<AutoConnect>true</AutoConnect>
|
||||
<AutoSelect>true</AutoSelect>
|
||||
<LastPreferenceCategory>LineardialGadget</LastPreferenceCategory>
|
||||
<LastPreferencePage>Mainboard CPU</LastPreferencePage>
|
||||
<SaveSettingsOnExit>true</SaveSettingsOnExit>
|
||||
<SettingsWindowHeight>476</SettingsWindowHeight>
|
||||
<SettingsWindowWidth>697</SettingsWindowWidth>
|
||||
</General>
|
||||
<IPconnection>
|
||||
<Current>
|
||||
<arr_1>
|
||||
<Port>1</Port>
|
||||
<UseTCP>0</UseTCP>
|
||||
</arr_1>
|
||||
<size>1</size>
|
||||
</Current>
|
||||
</IPconnection>
|
||||
<KeyBindings>
|
||||
<size>0</size>
|
||||
</KeyBindings>
|
||||
@ -11,37 +25,17 @@
|
||||
<FullScreen>false</FullScreen>
|
||||
<Maximized>true</Maximized>
|
||||
</MainWindow>
|
||||
<Plugins>
|
||||
<SoundNotifyPlugin>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>1.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<Current>
|
||||
<arr_1>
|
||||
<CurrentLanguage></CurrentLanguage>
|
||||
<DataObject></DataObject>
|
||||
<ExpireTimeout>0</ExpireTimeout>
|
||||
<ObjectField></ObjectField>
|
||||
<Repeat></Repeat>
|
||||
<SayOrder></SayOrder>
|
||||
<Sound1></Sound1>
|
||||
<Sound2></Sound2>
|
||||
<Sound3></Sound3>
|
||||
<SoundCollectionPath></SoundCollectionPath>
|
||||
<Value></Value>
|
||||
<ValueSpinBox>0</ValueSpinBox>
|
||||
</arr_1>
|
||||
<size>1</size>
|
||||
</Current>
|
||||
<EnableSound>false</EnableSound>
|
||||
<listNotifies>
|
||||
<size>0</size>
|
||||
</listNotifies>
|
||||
</data>
|
||||
</SoundNotifyPlugin>
|
||||
</Plugins>
|
||||
<ModePriorities>
|
||||
<Mode1>91</Mode1>
|
||||
<Mode2>90</Mode2>
|
||||
<Mode3>89</Mode3>
|
||||
<Mode4>88</Mode4>
|
||||
<Mode5>87</Mode5>
|
||||
<Welcome>100</Welcome>
|
||||
</ModePriorities>
|
||||
<SerialConnection>
|
||||
<speed>57600</speed>
|
||||
</SerialConnection>
|
||||
<UAVGadgetConfigurations>
|
||||
<ConfigGadget>
|
||||
<default>
|
||||
@ -65,7 +59,7 @@
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeActual</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
@ -100,7 +94,7 @@
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroAltitude</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>10</needle1MaxValue>
|
||||
@ -131,11 +125,8 @@
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/barometer.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroAltitude</needle1DataObject>
|
||||
<needle1Factor>10</needle1Factor>
|
||||
<needle1MaxValue>1120</needle1MaxValue>
|
||||
@ -166,11 +157,8 @@
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/vsi.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>VelocityActual</needle1DataObject>
|
||||
<needle1Factor>0.01</needle1Factor>
|
||||
<needle1MaxValue>12</needle1MaxValue>
|
||||
@ -203,9 +191,7 @@
|
||||
<dialFile>%%DATAPATH%%dials/default/compass.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeActual</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
@ -240,7 +226,7 @@
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeActual</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
@ -275,7 +261,7 @@
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroAltitude</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>10</needle1MaxValue>
|
||||
@ -308,9 +294,7 @@
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/barometer.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroAltitude</needle1DataObject>
|
||||
<needle1Factor>10</needle1Factor>
|
||||
<needle1MaxValue>1120</needle1MaxValue>
|
||||
@ -343,9 +327,7 @@
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/vsi.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>VelocityActual</needle1DataObject>
|
||||
<needle1Factor>0.01</needle1Factor>
|
||||
<needle1MaxValue>11.2</needle1MaxValue>
|
||||
@ -378,9 +360,7 @@
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/compass.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeActual</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
@ -413,9 +393,7 @@
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/speed.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>GPSPosition</needle1DataObject>
|
||||
<needle1Factor>3.6</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
@ -450,7 +428,7 @@
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroAltitude</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
@ -485,7 +463,7 @@
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle2</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeActual</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
@ -516,11 +494,8 @@
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/speed.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>GPSPosition</needle1DataObject>
|
||||
<needle1Factor>3.6</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
@ -555,7 +530,7 @@
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeActual</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
@ -590,7 +565,7 @@
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroAltitude</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>10</needle1MaxValue>
|
||||
@ -621,11 +596,8 @@
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/barometer.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroAltitude</needle1DataObject>
|
||||
<needle1Factor>10</needle1Factor>
|
||||
<needle1MaxValue>1120</needle1MaxValue>
|
||||
@ -656,11 +628,8 @@
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/vsi.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>VelocityActual</needle1DataObject>
|
||||
<needle1Factor>0.01</needle1Factor>
|
||||
<needle1MaxValue>12</needle1MaxValue>
|
||||
@ -693,9 +662,7 @@
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/compass.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeActual</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
@ -726,11 +693,8 @@
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/speed.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>GPSPosition</needle1DataObject>
|
||||
<needle1Factor>3.6</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
@ -761,11 +725,10 @@
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/thermometer.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroAltitude</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
@ -796,11 +759,10 @@
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/thermometer.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>ManualControlCommand</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>2000</needle1MaxValue>
|
||||
@ -831,11 +793,10 @@
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/thermometer.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Ubuntu,11,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroAltitude</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
@ -916,7 +877,7 @@
|
||||
<defaultDataBits>3</defaultDataBits>
|
||||
<defaultFlow>0</defaultFlow>
|
||||
<defaultParity>0</defaultParity>
|
||||
<defaultPort>Serial port 0</defaultPort>
|
||||
<defaultPort>Communications Port (COM1)</defaultPort>
|
||||
<defaultSpeed>11</defaultSpeed>
|
||||
<defaultStopBits>0</defaultStopBits>
|
||||
</data>
|
||||
@ -931,7 +892,7 @@
|
||||
<defaultDataBits>3</defaultDataBits>
|
||||
<defaultFlow>0</defaultFlow>
|
||||
<defaultParity>0</defaultParity>
|
||||
<defaultPort>Serial port 0</defaultPort>
|
||||
<defaultPort>Communications Port (COM1)</defaultPort>
|
||||
<defaultSpeed>17</defaultSpeed>
|
||||
<defaultStopBits>0</defaultStopBits>
|
||||
</data>
|
||||
@ -948,8 +909,6 @@
|
||||
<dataPath>\usr\share\games\FlightGear</dataPath>
|
||||
<hostAddress>127.0.0.1</hostAddress>
|
||||
<inPort>9009</inPort>
|
||||
<latitude></latitude>
|
||||
<longitude></longitude>
|
||||
<manual>false</manual>
|
||||
<outPort>9010</outPort>
|
||||
<remoteHostAddress>127.0.0.1</remoteHostAddress>
|
||||
@ -967,8 +926,6 @@
|
||||
<dataPath>\usr\share\games\FlightGear</dataPath>
|
||||
<hostAddress>127.0.0.3</hostAddress>
|
||||
<inPort>6756</inPort>
|
||||
<latitude></latitude>
|
||||
<longitude></longitude>
|
||||
<manual>false</manual>
|
||||
<outPort>49000</outPort>
|
||||
<remoteHostAddress>127.0.0.1</remoteHostAddress>
|
||||
@ -977,17 +934,39 @@
|
||||
</data>
|
||||
</XPlane__PCT__20HITL>
|
||||
</HITL>
|
||||
<ImportExportGadget>
|
||||
<HITLv2>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>1.0.1</version>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<iniFile>gcs.ini</iniFile>
|
||||
<attActCalc>false</attActCalc>
|
||||
<attActHW>false</attActHW>
|
||||
<attActSim>true</attActSim>
|
||||
<attActual>true</attActual>
|
||||
<attRaw>true</attRaw>
|
||||
<attRawRate>20</attRawRate>
|
||||
<gcsReciever>true</gcsReciever>
|
||||
<gpsPosRate>200</gpsPosRate>
|
||||
<gpsPosition>true</gpsPosition>
|
||||
<homeLocRate>0</homeLocRate>
|
||||
<homeLocation>true</homeLocation>
|
||||
<hostAddress>127.0.0.1</hostAddress>
|
||||
<inPort>40100</inPort>
|
||||
<inputCommand>true</inputCommand>
|
||||
<manualControl>false</manualControl>
|
||||
<manualOutput>false</manualOutput>
|
||||
<outPort>40200</outPort>
|
||||
<outputRate>20</outputRate>
|
||||
<remoteAddress>127.0.0.1</remoteAddress>
|
||||
<simulatorId>ASimRC</simulatorId>
|
||||
<sonarAltRate>50</sonarAltRate>
|
||||
<sonarAltitude>false</sonarAltitude>
|
||||
<sonarMaxAlt>@Variant(AAAAh0CgAAA=)</sonarMaxAlt>
|
||||
</data>
|
||||
</default>
|
||||
</ImportExportGadget>
|
||||
</HITLv2>
|
||||
<LineardialGadget>
|
||||
<Accel__PCT__20Horizontal__PCT__20X>
|
||||
<configInfo>
|
||||
@ -1183,17 +1162,17 @@
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>50</greenMax>
|
||||
<greenMax>90</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>100</redMax>
|
||||
<redMin>80</redMin>
|
||||
<redMin>95</redMin>
|
||||
<sourceDataObject>SystemStats</sourceDataObject>
|
||||
<sourceObjectField>CPULoad</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>80</yellowMax>
|
||||
<yellowMin>50</yellowMin>
|
||||
<yellowMax>95</yellowMax>
|
||||
<yellowMin>90</yellowMin>
|
||||
</data>
|
||||
</Mainboard__PCT__20CPU>
|
||||
<Pitch__PCT__20Desired>
|
||||
@ -1439,6 +1418,17 @@
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Aeroquad__PCT__20__PCT__2B>
|
||||
<CopterControl>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/boards/CopterControl/CopterControl.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</CopterControl>
|
||||
<Easyquad__PCT__20X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
@ -1571,6 +1561,17 @@
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Quadcopter>
|
||||
<Ricoo>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/ricoo/ricoo.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Ricoo>
|
||||
<Scorpion__PCT__20Tricopter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
@ -1604,28 +1605,6 @@
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Test__PCT__20Quad__PCT__20X>
|
||||
<Ricoo>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/ricoo/ricoo.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Ricoo>
|
||||
<CopterControl>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/boards/CopterControl/CopterControl.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</CopterControl>
|
||||
</ModelViewGadget>
|
||||
<OPMapGadget>
|
||||
<Google__PCT__20Sat>
|
||||
@ -1712,14 +1691,18 @@
|
||||
</data>
|
||||
</smooth>
|
||||
</PFDGadget>
|
||||
<PipXtreme>
|
||||
<QmlViewGadget>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dialFile>Unknown</dialFile>
|
||||
<useOpenGLFlag>true</useOpenGLFlag>
|
||||
</data>
|
||||
</default>
|
||||
</PipXtreme>
|
||||
</QmlViewGadget>
|
||||
<ScopeGadget>
|
||||
<Accel>
|
||||
<configInfo>
|
||||
@ -1738,6 +1721,7 @@
|
||||
<uavField>x</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
@ -1747,6 +1731,7 @@
|
||||
<uavField>y</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
@ -1756,6 +1741,7 @@
|
||||
<uavField>z</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
@ -1781,6 +1767,7 @@
|
||||
<uavField>Channel-4</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
@ -1790,6 +1777,7 @@
|
||||
<uavField>Channel-5</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
@ -1799,6 +1787,7 @@
|
||||
<uavField>Channel-6</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
@ -1808,6 +1797,7 @@
|
||||
<uavField>Channel-7</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
@ -1833,6 +1823,7 @@
|
||||
<uavField>Roll</uavField>
|
||||
<uavObject>AttitudeActual</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
@ -1842,6 +1833,7 @@
|
||||
<uavField>Yaw</uavField>
|
||||
<uavObject>AttitudeActual</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
@ -1851,6 +1843,7 @@
|
||||
<uavField>Pitch</uavField>
|
||||
<uavObject>AttitudeActual</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
@ -1876,6 +1869,7 @@
|
||||
<uavField>Pressure</uavField>
|
||||
<uavObject>BaroAltitude</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
@ -1901,6 +1895,7 @@
|
||||
<uavField>Channel-1</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
@ -1910,6 +1905,7 @@
|
||||
<uavField>Channel-4</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
@ -1919,6 +1915,7 @@
|
||||
<uavField>Channel-5</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
@ -1928,6 +1925,7 @@
|
||||
<uavField>Channel-6</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
@ -1937,6 +1935,7 @@
|
||||
<uavField>Channel-7</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve4>
|
||||
@ -1946,6 +1945,7 @@
|
||||
<uavField>Channel-2</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve5>
|
||||
@ -1955,6 +1955,7 @@
|
||||
<uavField>Channel-3</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve6>
|
||||
@ -1964,6 +1965,7 @@
|
||||
<uavField>Channel-0</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve7>
|
||||
@ -1989,6 +1991,7 @@
|
||||
<uavField>x</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
@ -1998,6 +2001,7 @@
|
||||
<uavField>y</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
@ -2007,6 +2011,7 @@
|
||||
<uavField>z</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
@ -2032,6 +2037,7 @@
|
||||
<uavField>z</uavField>
|
||||
<uavObject>Gyros</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
@ -2041,6 +2047,7 @@
|
||||
<uavField>y</uavField>
|
||||
<uavObject>Gyros</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
@ -2050,6 +2057,7 @@
|
||||
<uavField>x</uavField>
|
||||
<uavObject>Gyros</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
@ -2075,6 +2083,7 @@
|
||||
<uavField>X</uavField>
|
||||
<uavObject>Magnetometer</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
@ -2084,6 +2093,7 @@
|
||||
<uavField>Y</uavField>
|
||||
<uavObject>Magnetometer</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
@ -2093,6 +2103,7 @@
|
||||
<uavField>Z</uavField>
|
||||
<uavObject>Magnetometer</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
@ -2118,6 +2129,7 @@
|
||||
<uavField>StackRemaining-System</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
@ -2127,6 +2139,7 @@
|
||||
<uavField>StackRemaining-Actuator</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
@ -2136,6 +2149,7 @@
|
||||
<uavField>StackRemaining-Guidance</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve10>
|
||||
@ -2145,6 +2159,7 @@
|
||||
<uavField>StackRemaining-Watchdog</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve11>
|
||||
@ -2154,6 +2169,7 @@
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
@ -2163,6 +2179,7 @@
|
||||
<uavField>StackRemaining-TelemetryTxPri</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
@ -2172,6 +2189,7 @@
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve4>
|
||||
@ -2181,6 +2199,7 @@
|
||||
<uavField>StackRemaining-GPS</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve5>
|
||||
@ -2190,6 +2209,7 @@
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve6>
|
||||
@ -2199,6 +2219,7 @@
|
||||
<uavField>StackRemaining-Altitude</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve7>
|
||||
@ -2208,6 +2229,7 @@
|
||||
<uavField>StackRemaining-AHRSComms</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve8>
|
||||
@ -2217,6 +2239,7 @@
|
||||
<uavField>StackRemaining-Stabilization</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve9>
|
||||
@ -2242,6 +2265,7 @@
|
||||
<uavField>TxFailures</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
@ -2251,6 +2275,7 @@
|
||||
<uavField>RxFailures</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
@ -2260,6 +2285,7 @@
|
||||
<uavField>TxRetries</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
@ -2285,9 +2311,20 @@
|
||||
<uavField>FlightTime</uavField>
|
||||
<uavObject>SystemStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>0</color>
|
||||
<mathFunction></mathFunction>
|
||||
<uavField></uavField>
|
||||
<uavObject></uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurveCount>2</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>800</refreshInterval>
|
||||
@ -2417,26 +2454,14 @@
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Mainboard CPU</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>AHRS CPU</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAABA)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Mainboard CPU</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABIwAAAAIAAACN)</splitterSizes>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAACB)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
@ -2837,9 +2862,10 @@
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode5>
|
||||
</UAVGadgetManager>
|
||||
<ViewGroup_Default>@ByteArray(AAAA/wAAAAD9AAAAAAAABQAAAALCAAAABAAAAAQAAAABAAAACPwAAAAA)</ViewGroup_Default>
|
||||
<Workspace>
|
||||
<Icon1>:/core/images/ah.png</Icon1>
|
||||
<AllowTabBarMovement>false</AllowTabBarMovement>
|
||||
<Icon1>:\core\images\ah.png</Icon1>
|
||||
<Icon10>:/core/images/openpilot_logo_64.png</Icon10>
|
||||
<Icon2>:/core/images/config.png</Icon2>
|
||||
<Icon3>:/core/images/scopes.png</Icon3>
|
||||
<Icon4>:/core/images/joystick.png</Icon4>
|
||||
@ -2848,9 +2874,10 @@
|
||||
<Icon7>:/core/images/openpilot_logo_64.png</Icon7>
|
||||
<Icon8>:/core/images/openpilot_logo_64.png</Icon8>
|
||||
<Icon9>:/core/images/openpilot_logo_64.png</Icon9>
|
||||
<Icon10>:/core/images/openpilot_logo_64.png</Icon10>
|
||||
<NumberOfWorkspaces>5</NumberOfWorkspaces>
|
||||
<TabBarPlacementIndex>1</TabBarPlacementIndex>
|
||||
<Workspace1>Flight data</Workspace1>
|
||||
<Workspace10>Workspace10</Workspace10>
|
||||
<Workspace2>Configuration</Workspace2>
|
||||
<Workspace3>Scopes</Workspace3>
|
||||
<Workspace4>HITL</Workspace4>
|
||||
@ -2859,6 +2886,5 @@
|
||||
<Workspace7>Workspace7</Workspace7>
|
||||
<Workspace8>Workspace8</Workspace8>
|
||||
<Workspace9>Workspace9</Workspace9>
|
||||
<Workspace10>Workspace10</Workspace10>
|
||||
</Workspace>
|
||||
</gcs>
|
||||
|
@ -41,7 +41,7 @@ class IConnection;
|
||||
static const int READ_TIMEOUT = 200;
|
||||
static const int READ_SIZE = 64;
|
||||
|
||||
static const int WRITE_TIMEOUT = 200;
|
||||
static const int WRITE_TIMEOUT = 1000;
|
||||
static const int WRITE_SIZE = 64;
|
||||
|
||||
|
||||
|
@ -0,0 +1,17 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Servo Output: Critical</h1>
|
||||
<p>
|
||||
One of the following conditions may be present:
|
||||
<ul>
|
||||
<li>System is in failsafe mode.</li>
|
||||
<li>One or more servos outputs failed to update.</li>
|
||||
</ul>
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Alarm: OK</h1>
|
||||
<p>
|
||||
There are no problems with this alarm.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Attitude: Critical</h1>
|
||||
<p>
|
||||
This alarm will remain set until data is received from the accelerometer.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Attitude: Error</h1>
|
||||
<p>
|
||||
Failed to get an update from the accelerometer or gyros.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Battery: Critical</h1>
|
||||
<p>
|
||||
Battery voltage has fallen below the <b>alarm</b> threshold.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Battery: Error</h1>
|
||||
<p>
|
||||
Both battery current and voltage are at or below zero.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Battery: Warning</h1>
|
||||
<p>
|
||||
Battery voltage has fallen below the <b>warning</b> threshold.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Boot Fault: Critical</h1>
|
||||
<p>
|
||||
System has failed to boot more than three times: system defaults have been set.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>CPU: Critical</h1>
|
||||
<p>
|
||||
CPU load has exceeded 95%
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>CPU: Warning</h1>
|
||||
<p>
|
||||
CPU load has exceeded 80%
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Event System: Warning</h1>
|
||||
<p>
|
||||
There were problems with UAVObject events or callbacks
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Flight Time: Critical</h1>
|
||||
<p>
|
||||
Estimated flight time based on battery usage is less than 30s.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Flight Time: Error</h1>
|
||||
<p>
|
||||
Estimated flight time cannot be determined as battery voltage and current are at or below 0.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Flight Time: Warning</h1>
|
||||
<p>
|
||||
Estimated flight time based on battery usage is less than 60s.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>GPS: Critical</h1>
|
||||
<p>
|
||||
The GPS is receiving data but there is no position fix.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>GPS: Error</h1>
|
||||
<p>
|
||||
The GPS has timed out; either there is no GPS plugged in, the GPS has locked up or there is some other hardware fault.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>GPS: Warning</h1>
|
||||
<p>
|
||||
The GPS has a fix and navigation can be used. However, the position quality is very low (the indication is <7 satellites)
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Guidance: Warning</h1>
|
||||
<p>
|
||||
Timed out waiting for an attitude update.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,24 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>RC Input: Critical</h1>
|
||||
<p>
|
||||
One of the following conditions may be present:
|
||||
<ul>
|
||||
<li>
|
||||
<p>One or more of the r/c input channel types is not set.</p>
|
||||
<p>On the GCS configuration page, make sure all inputs have a Type set.</p>
|
||||
</li>
|
||||
<li>One or more of the r/c input channel mappings are invalid.</li>
|
||||
<li>The driver is uninitialized for one or more of the r/c input channels.</li>
|
||||
<li>Current flight mode is undefined: this indicates a bug in the code.</li>
|
||||
<li>Current flight mode set to guidance but flight status flight mode is reported as something other than altitude hold.</li>
|
||||
<li>During update of desired stabilization mode, flight status is reported as something other than stabilized 1, 2 or 3.</li>
|
||||
</ul>
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,17 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>RC Input: Warning</h1>
|
||||
<p>
|
||||
One of the following conditions may be present:
|
||||
<ul>
|
||||
<li>System is in failsafe mode.</li>
|
||||
<li>Failed to update one or more of the accessory channels.</li>
|
||||
</ul>
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Memory: Critical</h1>
|
||||
<p>
|
||||
Either the remaining heap space or the IRQ stack has fallen below the <b>critical</b> limit (1000 bytes heap, 80 entries IRQ stack).
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,16 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Memory: Warning</h1>
|
||||
<p>
|
||||
Either the remaining heap space or the IRQ stack has fallen below the <b>warning</b> limit (4000 bytes heap, 150 entries IRQ stack).
|
||||
</p>
|
||||
<p>
|
||||
<b>Note:</b> if this is an original CC board (not CC3D or Revo), this condition is normal.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,18 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Sensors: Critical</h1>
|
||||
<p>
|
||||
One of the following conditions may be present:
|
||||
<ul>
|
||||
<li>Either the accelerometer, gyro or magnetometer tests failed.</li>
|
||||
<li>Timed out waiting for data from the accelerometer or gyro.</li>
|
||||
</ul>
|
||||
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Stabilization: Warning</h1>
|
||||
<p>
|
||||
Timed out waiting for an attitude update.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Stack: Critical</h1>
|
||||
<p>
|
||||
Stack overflow
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,13 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Telemetry: Error</h1>
|
||||
<p>
|
||||
Telemetry system is disconnected.
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -1,20 +1,23 @@
|
||||
TEMPLATE = lib
|
||||
TARGET = SystemHealthGadget
|
||||
QT += svg
|
||||
include(../../openpilotgcsplugin.pri)
|
||||
include(../../plugins/coreplugin/coreplugin.pri)
|
||||
include(systemhealth_dependencies.pri)
|
||||
HEADERS += systemhealthplugin.h
|
||||
HEADERS += systemhealthgadget.h
|
||||
HEADERS += systemhealthgadgetwidget.h
|
||||
HEADERS += systemhealthgadgetfactory.h
|
||||
HEADERS += systemhealthgadgetconfiguration.h
|
||||
HEADERS += systemhealthgadgetoptionspage.h
|
||||
SOURCES += systemhealthplugin.cpp
|
||||
SOURCES += systemhealthgadget.cpp
|
||||
SOURCES += systemhealthgadgetfactory.cpp
|
||||
SOURCES += systemhealthgadgetwidget.cpp
|
||||
SOURCES += systemhealthgadgetconfiguration.cpp
|
||||
SOURCES += systemhealthgadgetoptionspage.cpp
|
||||
OTHER_FILES += SystemHealthGadget.pluginspec
|
||||
FORMS += systemhealthgadgetoptionspage.ui
|
||||
TEMPLATE = lib
|
||||
TARGET = SystemHealthGadget
|
||||
QT += svg
|
||||
include(../../openpilotgcsplugin.pri)
|
||||
include(../../plugins/coreplugin/coreplugin.pri)
|
||||
include(systemhealth_dependencies.pri)
|
||||
HEADERS += systemhealthplugin.h
|
||||
HEADERS += systemhealthgadget.h
|
||||
HEADERS += systemhealthgadgetwidget.h
|
||||
HEADERS += systemhealthgadgetfactory.h
|
||||
HEADERS += systemhealthgadgetconfiguration.h
|
||||
HEADERS += systemhealthgadgetoptionspage.h
|
||||
SOURCES += systemhealthplugin.cpp
|
||||
SOURCES += systemhealthgadget.cpp
|
||||
SOURCES += systemhealthgadgetfactory.cpp
|
||||
SOURCES += systemhealthgadgetwidget.cpp
|
||||
SOURCES += systemhealthgadgetconfiguration.cpp
|
||||
SOURCES += systemhealthgadgetoptionspage.cpp
|
||||
OTHER_FILES += SystemHealthGadget.pluginspec
|
||||
FORMS += systemhealthgadgetoptionspage.ui
|
||||
|
||||
RESOURCES += \
|
||||
systemhealth.qrc
|
||||
|
@ -0,0 +1,30 @@
|
||||
<RCC>
|
||||
<qresource prefix="/systemhealth">
|
||||
<file>html/Actuator-Critical.html</file>
|
||||
<file>html/ManualControl-Critical.html</file>
|
||||
<file>html/ManualControl-Warning.html</file>
|
||||
<file>html/CPU-Critical.html</file>
|
||||
<file>html/CPU-Warning.html</file>
|
||||
<file>html/FlightTime-Error.html</file>
|
||||
<file>html/Battery-Warning.html</file>
|
||||
<file>html/BootFault-Critical.html</file>
|
||||
<file>html/EventSystem-Warning.html</file>
|
||||
<file>html/FlightTime-Critical.html</file>
|
||||
<file>html/AlarmOK.html</file>
|
||||
<file>html/Attitude-Critical.html</file>
|
||||
<file>html/Attitude-Error.html</file>
|
||||
<file>html/Battery-Critical.html</file>
|
||||
<file>html/Battery-Error.html</file>
|
||||
<file>html/FlightTime-Warning.html</file>
|
||||
<file>html/GPS-Critical.html</file>
|
||||
<file>html/GPS-Error.html</file>
|
||||
<file>html/GPS-Warning.html</file>
|
||||
<file>html/Guidance-Warning.html</file>
|
||||
<file>html/Memory-Critical.html</file>
|
||||
<file>html/Memory-Warning.html</file>
|
||||
<file>html/Sensors-Critical.html</file>
|
||||
<file>html/Stabilization-Warning.html</file>
|
||||
<file>html/Stack-Critical.html</file>
|
||||
<file>html/Telemetry-Error.html</file>
|
||||
</qresource>
|
||||
</RCC>
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file systemhealthgadgetwidget.cpp
|
||||
* @author Edouard Lafargue Copyright (C) 2010.
|
||||
* @author OpenPilot Team & Edouard Lafargue Copyright (C) 2012.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup SystemHealthPlugin System Health Plugin
|
||||
@ -32,6 +32,7 @@
|
||||
#include "systemalarms.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QWhatsThis>
|
||||
|
||||
/*
|
||||
* Initialize the widget
|
||||
@ -62,6 +63,7 @@ SystemHealthGadgetWidget::SystemHealthGadgetWidget(QWidget *parent) : QGraphicsV
|
||||
connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()));
|
||||
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()));
|
||||
|
||||
setToolTip(tr("Displays flight system errors. Click on an alarm for more information."));
|
||||
}
|
||||
|
||||
/**
|
||||
@ -195,3 +197,73 @@ void SystemHealthGadgetWidget::resizeEvent(QResizeEvent *event)
|
||||
Q_UNUSED(event);
|
||||
fitInView(background, Qt::KeepAspectRatio );
|
||||
}
|
||||
|
||||
void SystemHealthGadgetWidget::mousePressEvent ( QMouseEvent * event )
|
||||
{
|
||||
QGraphicsScene *graphicsScene = scene();
|
||||
if(graphicsScene){
|
||||
QPoint point = event->pos();
|
||||
bool haveAlarmItem = false;
|
||||
foreach(QGraphicsItem* sceneItem, items(point)){
|
||||
QGraphicsSvgItem *clickedItem = dynamic_cast<QGraphicsSvgItem*>(sceneItem);
|
||||
|
||||
if(clickedItem){
|
||||
if((clickedItem != foreground) && (clickedItem != background)){
|
||||
// Clicked an actual alarm. We need to set haveAlarmItem to true
|
||||
// as two of the items in this loop will always be foreground and
|
||||
// background. Without this flag, at some point in the loop we
|
||||
// would always call showAllAlarmDescriptions...
|
||||
haveAlarmItem = true;
|
||||
QString itemId = clickedItem->elementId();
|
||||
if(itemId.contains("OK")){
|
||||
// No alarm set for this item
|
||||
showAlarmDescriptionForItemId("AlarmOK", event->globalPos());
|
||||
}else{
|
||||
// Warning, error or critical alarm
|
||||
showAlarmDescriptionForItemId(itemId, event->globalPos());
|
||||
}
|
||||
}else if(!haveAlarmItem){
|
||||
// Clicked foreground or background
|
||||
showAllAlarmDescriptions(event->globalPos());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void SystemHealthGadgetWidget::showAlarmDescriptionForItemId(const QString itemId, const QPoint& location){
|
||||
QFile alarmDescription(":/systemhealth/html/" + itemId + ".html");
|
||||
if(alarmDescription.open(QIODevice::ReadOnly | QIODevice::Text)){
|
||||
QTextStream textStream(&alarmDescription);
|
||||
QWhatsThis::showText(location, textStream.readAll());
|
||||
}
|
||||
}
|
||||
|
||||
void SystemHealthGadgetWidget::showAllAlarmDescriptions(const QPoint& location){
|
||||
QGraphicsScene *graphicsScene = scene();
|
||||
if(graphicsScene){
|
||||
QString alarmsText;
|
||||
|
||||
// Loop through all items in the scene looking for svg items that represent alarms
|
||||
foreach(QGraphicsItem* curItem, graphicsScene->items()){
|
||||
QGraphicsSvgItem* curSvgItem = dynamic_cast<QGraphicsSvgItem*>(curItem);
|
||||
if(curSvgItem && (curSvgItem != foreground) && (curSvgItem != background)){
|
||||
QString elementId = curSvgItem->elementId();
|
||||
if(!elementId.contains("OK")){
|
||||
// Found an alarm, get its corresponding alarm html file contents
|
||||
// and append to the cumulative string for all alarms.
|
||||
QFile alarmDescription(":/systemhealth/html/" + elementId + ".html");
|
||||
if(alarmDescription.open(QIODevice::ReadOnly | QIODevice::Text)){
|
||||
QTextStream textStream(&alarmDescription);
|
||||
alarmsText.append(textStream.readAll());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Show alarms text if we have any
|
||||
if(alarmsText.length() > 0){
|
||||
QWhatsThis::showText(location, alarmsText);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file systemhealthgadgetwidget.h
|
||||
* @author Edouard Lafargue Copyright (C) 2010.
|
||||
* @author OpenPilot Team & Edouard Lafargue Copyright (C) 2012.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup SystemHealthPlugin System Health Plugin
|
||||
@ -34,6 +34,7 @@
|
||||
#include <QGraphicsView>
|
||||
#include <QtSvg/QSvgRenderer>
|
||||
#include <QtSvg/QGraphicsSvgItem>
|
||||
#include <QMouseEvent>
|
||||
|
||||
#include <QFile>
|
||||
#include <QTimer>
|
||||
@ -52,6 +53,7 @@ public:
|
||||
protected:
|
||||
void paintEvent(QPaintEvent *event);
|
||||
void resizeEvent(QResizeEvent *event);
|
||||
void mousePressEvent ( QMouseEvent * event );
|
||||
|
||||
private slots:
|
||||
void updateAlarms(UAVObject *systemAlarm); // Called by the systemalarms UAVObject
|
||||
@ -67,5 +69,8 @@ private:
|
||||
// Simple flag to skip rendering if the
|
||||
bool fgenabled; // layer does not exist.
|
||||
|
||||
void showAlarmDescriptionForItemId(const QString itemId, const QPoint& location);
|
||||
void showAllAlarmDescriptions(const QPoint &location);
|
||||
|
||||
};
|
||||
#endif /* SYSTEMHEALTHGADGETWIDGET_H_ */
|
||||
|
@ -129,21 +129,23 @@ void TreeItem::appendChild(TreeItem *child)
|
||||
child->setParentTree(this);
|
||||
}
|
||||
|
||||
void TreeItem::insert(int index, TreeItem *child)
|
||||
void TreeItem::insertChild(TreeItem *child)
|
||||
{
|
||||
int index = nameIndex(child->data(0).toString());
|
||||
m_children.insert(index, child);
|
||||
child->setParentTree(this);
|
||||
}
|
||||
|
||||
TreeItem *TreeItem::child(int row)
|
||||
TreeItem *TreeItem::getChild(int index)
|
||||
{
|
||||
return m_children.value(row);
|
||||
return m_children.value(index);
|
||||
}
|
||||
|
||||
int TreeItem::childCount() const
|
||||
{
|
||||
return m_children.count();
|
||||
}
|
||||
|
||||
int TreeItem::row() const
|
||||
{
|
||||
if (m_parent)
|
||||
@ -224,3 +226,8 @@ QTime TreeItem::getHiglightExpires()
|
||||
{
|
||||
return m_highlightExpires;
|
||||
}
|
||||
|
||||
QList<MetaObjectTreeItem *> TopTreeItem::getMetaObjectItems()
|
||||
{
|
||||
return m_metaObjectTreeItemsPerObjectIds.values();
|
||||
}
|
||||
|
@ -33,6 +33,7 @@
|
||||
#include "uavobjectfield.h"
|
||||
#include <QtCore/QList>
|
||||
#include <QtCore/QLinkedList>
|
||||
#include <QtCore/QMap>
|
||||
#include <QtCore/QVariant>
|
||||
#include <QtCore/QTime>
|
||||
#include <QtCore/QTimer>
|
||||
@ -94,9 +95,9 @@ public:
|
||||
virtual ~TreeItem();
|
||||
|
||||
void appendChild(TreeItem *child);
|
||||
void insert(int index, TreeItem *child);
|
||||
void insertChild(TreeItem *child);
|
||||
|
||||
TreeItem *child(int row);
|
||||
TreeItem *getChild(int index);
|
||||
inline QList<TreeItem*> treeChildren() const { return m_children; }
|
||||
int childCount() const;
|
||||
int columnCount() const;
|
||||
@ -131,6 +132,24 @@ public:
|
||||
|
||||
virtual void removeHighlight();
|
||||
|
||||
int nameIndex(QString name) {
|
||||
for (int i = 0; i < childCount(); ++i) {
|
||||
if (name < getChild(i)->data(0).toString())
|
||||
return i;
|
||||
}
|
||||
return childCount();
|
||||
}
|
||||
|
||||
TreeItem* findChildByName(QString name)
|
||||
{
|
||||
foreach (TreeItem* child, m_children) {
|
||||
if (name == child->data(0).toString()) {
|
||||
return child;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
signals:
|
||||
void updateHighlight(TreeItem*);
|
||||
|
||||
@ -152,6 +171,9 @@ private:
|
||||
static int m_highlightTimeMs;
|
||||
};
|
||||
|
||||
class DataObjectTreeItem;
|
||||
class MetaObjectTreeItem;
|
||||
|
||||
class TopTreeItem : public TreeItem
|
||||
{
|
||||
Q_OBJECT
|
||||
@ -159,19 +181,27 @@ public:
|
||||
TopTreeItem(const QList<QVariant> &data, TreeItem *parent = 0) : TreeItem(data, parent) { }
|
||||
TopTreeItem(const QVariant &data, TreeItem *parent = 0) : TreeItem(data, parent) { }
|
||||
|
||||
QList<quint32> objIds() { return m_objIds; }
|
||||
void addObjId(quint32 objId) { m_objIds.append(objId); }
|
||||
void insertObjId(int index, quint32 objId) { m_objIds.insert(index, objId); }
|
||||
int nameIndex(QString name) {
|
||||
for (int i = 0; i < childCount(); ++i) {
|
||||
if (name < child(i)->data(0).toString())
|
||||
return i;
|
||||
}
|
||||
return childCount();
|
||||
void addObjectTreeItem(quint32 objectId, DataObjectTreeItem* oti) {
|
||||
m_objectTreeItemsPerObjectIds[objectId] = oti;
|
||||
}
|
||||
|
||||
DataObjectTreeItem* findDataObjectTreeItemByObjectId(quint32 objectId) {
|
||||
return m_objectTreeItemsPerObjectIds.contains(objectId) ? m_objectTreeItemsPerObjectIds[objectId] : 0;
|
||||
}
|
||||
|
||||
void addMetaObjectTreeItem(quint32 objectId, MetaObjectTreeItem* oti) {
|
||||
m_metaObjectTreeItemsPerObjectIds[objectId] = oti;
|
||||
}
|
||||
|
||||
MetaObjectTreeItem* findMetaObjectTreeItemByObjectId(quint32 objectId) {
|
||||
return m_metaObjectTreeItemsPerObjectIds.contains(objectId) ? m_metaObjectTreeItemsPerObjectIds[objectId] : 0;
|
||||
}
|
||||
|
||||
QList<MetaObjectTreeItem*> getMetaObjectItems();
|
||||
|
||||
private:
|
||||
QList<quint32> m_objIds;
|
||||
QMap<quint32, DataObjectTreeItem*> m_objectTreeItemsPerObjectIds;
|
||||
QMap<quint32, MetaObjectTreeItem*> m_metaObjectTreeItemsPerObjectIds;
|
||||
};
|
||||
|
||||
class ObjectTreeItem : public TreeItem
|
||||
|
@ -45,5 +45,6 @@ void UAVObjectBrowser::loadConfiguration(IUAVGadgetConfiguration* config)
|
||||
m_widget->setRecentlyUpdatedColor(m->recentlyUpdatedColor());
|
||||
m_widget->setManuallyChangedColor(m->manuallyChangedColor());
|
||||
m_widget->setRecentlyUpdatedTimeout(m->recentlyUpdatedTimeout());
|
||||
m_widget->setOnlyHilightChangedValues(m->onlyHighlightChangedValues());
|
||||
}
|
||||
|
||||
|
@ -202,6 +202,19 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="categorizeCheckbox">
|
||||
<property name="toolTip">
|
||||
<string>Select to sort objects in to categories.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Categorize Objects</string>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
|
@ -31,17 +31,20 @@ UAVObjectBrowserConfiguration::UAVObjectBrowserConfiguration(QString classId, QS
|
||||
IUAVGadgetConfiguration(classId, parent),
|
||||
m_recentlyUpdatedColor(QColor(255, 230, 230)),
|
||||
m_manuallyChangedColor(QColor(230, 230, 255)),
|
||||
m_recentlyUpdatedTimeout(500)
|
||||
m_recentlyUpdatedTimeout(500),
|
||||
m_onlyHilightChangedValues(false)
|
||||
{
|
||||
//if a saved configuration exists load it
|
||||
if(qSettings != 0) {
|
||||
QColor recent = qSettings->value("recentlyUpdatedColor").value<QColor>();
|
||||
QColor manual = qSettings->value("manuallyChangedColor").value<QColor>();
|
||||
int timeout = qSettings->value("recentlyUpdatedTimeout").toInt();
|
||||
bool hilight = qSettings->value("onlyHilightChangedValues").toBool();
|
||||
|
||||
m_recentlyUpdatedColor = recent;
|
||||
m_manuallyChangedColor = manual;
|
||||
m_recentlyUpdatedTimeout = timeout;
|
||||
m_onlyHilightChangedValues = hilight;
|
||||
}
|
||||
}
|
||||
|
||||
@ -51,6 +54,7 @@ IUAVGadgetConfiguration *UAVObjectBrowserConfiguration::clone()
|
||||
m->m_recentlyUpdatedColor = m_recentlyUpdatedColor;
|
||||
m->m_manuallyChangedColor = m_manuallyChangedColor;
|
||||
m->m_recentlyUpdatedTimeout = m_recentlyUpdatedTimeout;
|
||||
m->m_onlyHilightChangedValues = m_onlyHilightChangedValues;
|
||||
return m;
|
||||
}
|
||||
|
||||
@ -62,4 +66,5 @@ void UAVObjectBrowserConfiguration::saveConfig(QSettings* qSettings) const {
|
||||
qSettings->setValue("recentlyUpdatedColor", m_recentlyUpdatedColor);
|
||||
qSettings->setValue("manuallyChangedColor", m_manuallyChangedColor);
|
||||
qSettings->setValue("recentlyUpdatedTimeout", m_recentlyUpdatedTimeout);
|
||||
qSettings->setValue("onlyHilightChangedValues", m_onlyHilightChangedValues);
|
||||
}
|
||||
|
@ -39,6 +39,7 @@ Q_OBJECT
|
||||
Q_PROPERTY(QColor m_recentlyUpdatedColor READ recentlyUpdatedColor WRITE setRecentlyUpdatedColor)
|
||||
Q_PROPERTY(QColor m_manuallyChangedColor READ manuallyChangedColor WRITE setManuallyChangedColor)
|
||||
Q_PROPERTY(int m_recentlyUpdatedTimeout READ recentlyUpdatedTimeout WRITE setRecentlyUpdatedTimeout)
|
||||
Q_PROPERTY(bool m_onlyHilightChangedValues READ onlyHighlightChangedValues WRITE setOnlyHighlightChangedValues)
|
||||
public:
|
||||
explicit UAVObjectBrowserConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0);
|
||||
|
||||
@ -48,6 +49,7 @@ public:
|
||||
QColor recentlyUpdatedColor() const { return m_recentlyUpdatedColor; }
|
||||
QColor manuallyChangedColor() const { return m_manuallyChangedColor; }
|
||||
int recentlyUpdatedTimeout() const { return m_recentlyUpdatedTimeout; }
|
||||
bool onlyHighlightChangedValues() const {return m_onlyHilightChangedValues;}
|
||||
|
||||
signals:
|
||||
|
||||
@ -55,11 +57,13 @@ public slots:
|
||||
void setRecentlyUpdatedColor(QColor color) { m_recentlyUpdatedColor = color; }
|
||||
void setManuallyChangedColor(QColor color) { m_manuallyChangedColor = color; }
|
||||
void setRecentlyUpdatedTimeout(int timeout) { m_recentlyUpdatedTimeout = timeout; }
|
||||
void setOnlyHighlightChangedValues(bool hilight) { m_onlyHilightChangedValues = hilight; }
|
||||
|
||||
private:
|
||||
QColor m_recentlyUpdatedColor;
|
||||
QColor m_manuallyChangedColor;
|
||||
int m_recentlyUpdatedTimeout;
|
||||
bool m_onlyHilightChangedValues;
|
||||
};
|
||||
|
||||
#endif // UAVOBJECTBROWSERCONFIGURATION_H
|
||||
|
@ -52,6 +52,7 @@ QWidget *UAVObjectBrowserOptionsPage::createPage(QWidget *parent)
|
||||
m_page->recentlyUpdatedButton->setColor(m_config->recentlyUpdatedColor());
|
||||
m_page->manuallyChangedButton->setColor(m_config->manuallyChangedColor());
|
||||
m_page->recentlyUpdatedTimeoutSpinBox->setValue(m_config->recentlyUpdatedTimeout());
|
||||
m_page->hilightBox->setChecked(m_config->onlyHighlightChangedValues());
|
||||
|
||||
return w;
|
||||
|
||||
@ -62,6 +63,7 @@ void UAVObjectBrowserOptionsPage::apply()
|
||||
m_config->setRecentlyUpdatedColor(m_page->recentlyUpdatedButton->color());
|
||||
m_config->setManuallyChangedColor(m_page->manuallyChangedButton->color());
|
||||
m_config->setRecentlyUpdatedTimeout(m_page->recentlyUpdatedTimeoutSpinBox->value());
|
||||
m_config->setOnlyHighlightChangedValues(m_page->hilightBox->isChecked());
|
||||
}
|
||||
|
||||
void UAVObjectBrowserOptionsPage::finish()
|
||||
|
@ -48,7 +48,7 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="4" column="3">
|
||||
<item row="5" column="3">
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
@ -115,6 +115,13 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QCheckBox" name="hilightBox">
|
||||
<property name="text">
|
||||
<string>Only hilight nodes when value actually changes</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<customwidgets>
|
||||
|
@ -54,6 +54,7 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent
|
||||
showMetaData(m_browser->metaCheckBox->isChecked());
|
||||
connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex,QModelIndex)), this, SLOT(currentChanged(QModelIndex,QModelIndex)));
|
||||
connect(m_browser->metaCheckBox, SIGNAL(toggled(bool)), this, SLOT(showMetaData(bool)));
|
||||
connect(m_browser->categorizeCheckbox, SIGNAL(toggled(bool)), this, SLOT(categorize(bool)));
|
||||
connect(m_browser->saveSDButton, SIGNAL(clicked()), this, SLOT(saveObject()));
|
||||
connect(m_browser->readSDButton, SIGNAL(clicked()), this, SLOT(loadObject()));
|
||||
connect(m_browser->eraseSDButton, SIGNAL(clicked()), this, SLOT(eraseObject()));
|
||||
@ -69,16 +70,32 @@ UAVObjectBrowserWidget::~UAVObjectBrowserWidget()
|
||||
|
||||
void UAVObjectBrowserWidget::showMetaData(bool show)
|
||||
{
|
||||
int topRowCount = m_model->rowCount(QModelIndex());
|
||||
for (int i = 0; i < topRowCount; ++i) {
|
||||
QModelIndex index = m_model->index(i, 0, QModelIndex());
|
||||
int subRowCount = m_model->rowCount(index);
|
||||
for (int j = 0; j < subRowCount; ++j) {
|
||||
m_browser->treeView->setRowHidden(0, index.child(j,0), !show);
|
||||
}
|
||||
QList<QModelIndex> metaIndexes = m_model->getMetaDataIndexes();
|
||||
foreach(QModelIndex index , metaIndexes)
|
||||
{
|
||||
m_browser->treeView->setRowHidden(index.row(), index.parent(), !show);
|
||||
}
|
||||
}
|
||||
|
||||
void UAVObjectBrowserWidget::categorize(bool categorize)
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
Q_ASSERT(pm);
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(objManager);
|
||||
|
||||
UAVObjectTreeModel* tmpModel = m_model;
|
||||
m_model = new UAVObjectTreeModel(0, categorize);
|
||||
m_model->setRecentlyUpdatedColor(m_recentlyUpdatedColor);
|
||||
m_model->setManuallyChangedColor(m_manuallyChangedColor);
|
||||
m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout);
|
||||
m_model->setOnlyHilightChangedValues(m_onlyHilightChangedValues);
|
||||
m_browser->treeView->setModel(m_model);
|
||||
showMetaData(m_browser->metaCheckBox->isChecked());
|
||||
|
||||
delete tmpModel;
|
||||
}
|
||||
|
||||
void UAVObjectBrowserWidget::sendUpdate()
|
||||
{
|
||||
ObjectTreeItem *objItem = findCurrentObjectTreeItem();
|
||||
|
@ -45,12 +45,15 @@ class UAVObjectBrowserWidget : public QWidget
|
||||
public:
|
||||
UAVObjectBrowserWidget(QWidget *parent = 0);
|
||||
~UAVObjectBrowserWidget();
|
||||
void setRecentlyUpdatedColor(QColor color) { m_model->setRecentlyUpdatedColor(color); }
|
||||
void setManuallyChangedColor(QColor color) { m_model->setManuallyChangedColor(color); }
|
||||
void setRecentlyUpdatedTimeout(int timeout) { m_model->setRecentlyUpdatedTimeout(timeout); }
|
||||
void setRecentlyUpdatedColor(QColor color) { m_recentlyUpdatedColor = color; m_model->setRecentlyUpdatedColor(color); }
|
||||
void setManuallyChangedColor(QColor color) { m_manuallyChangedColor = color; m_model->setManuallyChangedColor(color); }
|
||||
void setRecentlyUpdatedTimeout(int timeout) { m_recentlyUpdatedTimeout = timeout; m_model->setRecentlyUpdatedTimeout(timeout); }
|
||||
void setOnlyHilightChangedValues(bool hilight) { m_onlyHilightChangedValues = hilight; m_model->setOnlyHilightChangedValues(hilight); }
|
||||
|
||||
|
||||
public slots:
|
||||
void showMetaData(bool show);
|
||||
void categorize(bool categorize);
|
||||
|
||||
private slots:
|
||||
void sendUpdate();
|
||||
@ -66,6 +69,11 @@ private:
|
||||
Ui_UAVObjectBrowser *m_browser;
|
||||
UAVObjectTreeModel *m_model;
|
||||
|
||||
int m_recentlyUpdatedTimeout;
|
||||
QColor m_recentlyUpdatedColor;
|
||||
QColor m_manuallyChangedColor;
|
||||
bool m_onlyHilightChangedValues;
|
||||
|
||||
void updateObjectPersistance(ObjectPersistence::OperationOptions op, UAVObject *obj);
|
||||
void enableSendRequest(bool enable);
|
||||
ObjectTreeItem *findCurrentObjectTreeItem();
|
||||
|
@ -38,7 +38,7 @@
|
||||
#include <QtCore/QSignalMapper>
|
||||
#include <QtCore/QDebug>
|
||||
|
||||
UAVObjectTreeModel::UAVObjectTreeModel(QObject *parent) :
|
||||
UAVObjectTreeModel::UAVObjectTreeModel(QObject *parent, bool categorize) :
|
||||
QAbstractItemModel(parent),
|
||||
m_recentlyUpdatedTimeout(500), // ms
|
||||
m_recentlyUpdatedColor(QColor(255, 230, 230)),
|
||||
@ -53,7 +53,7 @@ UAVObjectTreeModel::UAVObjectTreeModel(QObject *parent) :
|
||||
connect(objManager, SIGNAL(newInstance(UAVObject*)), this, SLOT(newObject(UAVObject*)));
|
||||
|
||||
TreeItem::setHighlightTime(m_recentlyUpdatedTimeout);
|
||||
setupModelData(objManager);
|
||||
setupModelData(objManager, categorize);
|
||||
}
|
||||
|
||||
UAVObjectTreeModel::~UAVObjectTreeModel()
|
||||
@ -62,7 +62,7 @@ UAVObjectTreeModel::~UAVObjectTreeModel()
|
||||
delete m_rootItem;
|
||||
}
|
||||
|
||||
void UAVObjectTreeModel::setupModelData(UAVObjectManager *objManager)
|
||||
void UAVObjectTreeModel::setupModelData(UAVObjectManager *objManager, bool categorize)
|
||||
{
|
||||
// root
|
||||
QList<QVariant> rootData;
|
||||
@ -82,7 +82,7 @@ void UAVObjectTreeModel::setupModelData(UAVObjectManager *objManager)
|
||||
QList< QList<UAVDataObject*> > objList = objManager->getDataObjects();
|
||||
foreach (QList<UAVDataObject*> list, objList) {
|
||||
foreach (UAVDataObject* obj, list) {
|
||||
addDataObject(obj);
|
||||
addDataObject(obj, categorize);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -90,33 +90,62 @@ void UAVObjectTreeModel::setupModelData(UAVObjectManager *objManager)
|
||||
void UAVObjectTreeModel::newObject(UAVObject *obj)
|
||||
{
|
||||
UAVDataObject *dobj = qobject_cast<UAVDataObject*>(obj);
|
||||
if (dobj)
|
||||
if (dobj) {
|
||||
addDataObject(dobj);
|
||||
}
|
||||
|
||||
void UAVObjectTreeModel::addDataObject(UAVDataObject *obj)
|
||||
{
|
||||
TopTreeItem *root = obj->isSettings() ? m_settingsTree : m_nonSettingsTree;
|
||||
if (root->objIds().contains(obj->getObjID())) {
|
||||
int index = root->objIds().indexOf(obj->getObjID());
|
||||
addInstance(obj, root->child(index));
|
||||
} else {
|
||||
DataObjectTreeItem *data = new DataObjectTreeItem(obj->getName() + " (" + QString::number(obj->getNumBytes()) + " bytes)");
|
||||
data->setHighlightManager(m_highlightManager);
|
||||
connect(data, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
|
||||
int index = root->nameIndex(obj->getName());
|
||||
root->insert(index, data);
|
||||
root->insertObjId(index, obj->getObjID());
|
||||
UAVMetaObject *meta = obj->getMetaObject();
|
||||
addMetaObject(meta, data);
|
||||
addInstance(obj, data);
|
||||
}
|
||||
}
|
||||
|
||||
void UAVObjectTreeModel::addMetaObject(UAVMetaObject *obj, TreeItem *parent)
|
||||
void UAVObjectTreeModel::addDataObject(UAVDataObject *obj, bool categorize)
|
||||
{
|
||||
TopTreeItem *root = obj->isSettings() ? m_settingsTree : m_nonSettingsTree;
|
||||
|
||||
TreeItem* parent = root;
|
||||
|
||||
if(categorize && obj->getCategory() != 0 && !obj->getCategory().isEmpty()) {
|
||||
QStringList categoryPath = obj->getCategory().split('/');
|
||||
parent = createCategoryItems(categoryPath, root);
|
||||
}
|
||||
|
||||
ObjectTreeItem* existing = root->findDataObjectTreeItemByObjectId(obj->getObjID());
|
||||
if (existing) {
|
||||
addInstance(obj, existing);
|
||||
} else {
|
||||
DataObjectTreeItem *dataTreeItem = new DataObjectTreeItem(obj->getName() + " (" + QString::number(obj->getNumBytes()) + " bytes)");
|
||||
dataTreeItem->setHighlightManager(m_highlightManager);
|
||||
connect(dataTreeItem, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
|
||||
parent->insertChild(dataTreeItem);
|
||||
root->addObjectTreeItem(obj->getObjID(), dataTreeItem);
|
||||
UAVMetaObject *meta = obj->getMetaObject();
|
||||
MetaObjectTreeItem* metaTreeItem = addMetaObject(meta, dataTreeItem);
|
||||
root->addMetaObjectTreeItem(meta->getObjID(), metaTreeItem);
|
||||
addInstance(obj, dataTreeItem);
|
||||
}
|
||||
}
|
||||
|
||||
TreeItem* UAVObjectTreeModel::createCategoryItems(QStringList categoryPath, TreeItem* root)
|
||||
{
|
||||
TreeItem* parent = root;
|
||||
foreach(QString category, categoryPath) {
|
||||
TreeItem* existing = parent->findChildByName(category);
|
||||
if(!existing) {
|
||||
TreeItem* categoryItem = new TreeItem(category);
|
||||
connect(categoryItem, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
|
||||
categoryItem->setHighlightManager(m_highlightManager);
|
||||
parent->insertChild(categoryItem);
|
||||
parent = categoryItem;
|
||||
}
|
||||
else {
|
||||
parent = existing;
|
||||
}
|
||||
}
|
||||
return parent;
|
||||
}
|
||||
|
||||
MetaObjectTreeItem* UAVObjectTreeModel::addMetaObject(UAVMetaObject *obj, TreeItem *parent)
|
||||
{
|
||||
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(highlightUpdatedObject(UAVObject*)));
|
||||
MetaObjectTreeItem *meta = new MetaObjectTreeItem(obj, tr("Meta Data"));
|
||||
|
||||
meta->setHighlightManager(m_highlightManager);
|
||||
connect(meta, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
|
||||
foreach (UAVObjectField *field, obj->getFields()) {
|
||||
@ -127,6 +156,7 @@ void UAVObjectTreeModel::addMetaObject(UAVMetaObject *obj, TreeItem *parent)
|
||||
}
|
||||
}
|
||||
parent->appendChild(meta);
|
||||
return meta;
|
||||
}
|
||||
|
||||
void UAVObjectTreeModel::addInstance(UAVObject *obj, TreeItem *parent)
|
||||
@ -153,7 +183,6 @@ void UAVObjectTreeModel::addInstance(UAVObject *obj, TreeItem *parent)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void UAVObjectTreeModel::addArrayField(UAVObjectField *field, TreeItem *parent)
|
||||
{
|
||||
TreeItem *item = new ArrayFieldTreeItem(field->getName());
|
||||
@ -221,7 +250,7 @@ QModelIndex UAVObjectTreeModel::index(int row, int column, const QModelIndex &pa
|
||||
else
|
||||
parentItem = static_cast<TreeItem*>(parent.internalPointer());
|
||||
|
||||
TreeItem *childItem = parentItem->child(row);
|
||||
TreeItem *childItem = parentItem->getChild(row);
|
||||
if (childItem)
|
||||
return createIndex(row, column, childItem);
|
||||
else
|
||||
@ -281,15 +310,31 @@ int UAVObjectTreeModel::columnCount(const QModelIndex &parent) const
|
||||
return m_rootItem->columnCount();
|
||||
}
|
||||
|
||||
QList<QModelIndex> UAVObjectTreeModel::getMetaDataIndexes()
|
||||
{
|
||||
QList<QModelIndex> metaIndexes;
|
||||
foreach(MetaObjectTreeItem *metaItem , m_settingsTree->getMetaObjectItems())
|
||||
{
|
||||
metaIndexes.append(index(metaItem));
|
||||
}
|
||||
|
||||
foreach(MetaObjectTreeItem *metaItem , m_nonSettingsTree->getMetaObjectItems())
|
||||
{
|
||||
metaIndexes.append(index(metaItem));
|
||||
}
|
||||
return metaIndexes;
|
||||
}
|
||||
|
||||
QVariant UAVObjectTreeModel::data(const QModelIndex &index, int role) const
|
||||
{
|
||||
if (!index.isValid())
|
||||
return QVariant();
|
||||
return QVariant();
|
||||
|
||||
if (index.column() == TreeItem::dataColumn && role == Qt::EditRole) {
|
||||
TreeItem *item = static_cast<TreeItem*>(index.internalPointer());
|
||||
return item->data(index.column());
|
||||
}
|
||||
|
||||
// if (role == Qt::DecorationRole)
|
||||
// return QIcon(":/core/images/openpilot_logo_128.png");
|
||||
|
||||
@ -301,16 +346,17 @@ QVariant UAVObjectTreeModel::data(const QModelIndex &index, int role) const
|
||||
TreeItem *item = static_cast<TreeItem*>(index.internalPointer());
|
||||
|
||||
if (index.column() == 0 && role == Qt::BackgroundRole) {
|
||||
ObjectTreeItem *objItem = dynamic_cast<ObjectTreeItem*>(item);
|
||||
if (objItem && objItem->highlighted())
|
||||
if (!dynamic_cast<TopTreeItem*>(item) && item->highlighted())
|
||||
return QVariant(m_recentlyUpdatedColor);
|
||||
}
|
||||
|
||||
if (index.column() == TreeItem::dataColumn && role == Qt::BackgroundRole) {
|
||||
FieldTreeItem *fieldItem = dynamic_cast<FieldTreeItem*>(item);
|
||||
if (fieldItem && fieldItem->highlighted())
|
||||
return QVariant(m_recentlyUpdatedColor);
|
||||
|
||||
if (fieldItem && fieldItem->changed())
|
||||
return QVariant(m_manuallyChangedColor);
|
||||
return QVariant(m_manuallyChangedColor);
|
||||
}
|
||||
|
||||
if (role != Qt::DisplayRole)
|
||||
@ -364,58 +410,42 @@ void UAVObjectTreeModel::highlightUpdatedObject(UAVObject *obj)
|
||||
Q_ASSERT(obj);
|
||||
ObjectTreeItem *item = findObjectTreeItem(obj);
|
||||
Q_ASSERT(item);
|
||||
if(!m_onlyHilightChangedValues){
|
||||
item->setHighlight(true);
|
||||
}
|
||||
item->update();
|
||||
QModelIndex itemIndex = index(item);
|
||||
Q_ASSERT(itemIndex != QModelIndex());
|
||||
emit dataChanged(itemIndex, itemIndex);
|
||||
if(!m_onlyHilightChangedValues){
|
||||
QModelIndex itemIndex = index(item);
|
||||
Q_ASSERT(itemIndex != QModelIndex());
|
||||
emit dataChanged(itemIndex, itemIndex);
|
||||
}
|
||||
}
|
||||
|
||||
ObjectTreeItem *UAVObjectTreeModel::findObjectTreeItem(UAVObject *object)
|
||||
{
|
||||
UAVDataObject *dobj = qobject_cast<UAVDataObject*>(object);
|
||||
UAVMetaObject *mobj = qobject_cast<UAVMetaObject*>(object);
|
||||
Q_ASSERT(dobj || mobj);
|
||||
if (dobj) {
|
||||
return findDataObjectTreeItem(dobj);
|
||||
UAVDataObject *dataObject = qobject_cast<UAVDataObject*>(object);
|
||||
UAVMetaObject *metaObject = qobject_cast<UAVMetaObject*>(object);
|
||||
Q_ASSERT(dataObject || metaObject);
|
||||
if (dataObject) {
|
||||
return findDataObjectTreeItem(dataObject);
|
||||
} else {
|
||||
dobj = qobject_cast<UAVDataObject*>(mobj->getParentObject());
|
||||
Q_ASSERT(dobj);
|
||||
ObjectTreeItem *dItem = findDataObjectTreeItem(dobj);
|
||||
Q_ASSERT(dItem);
|
||||
Q_ASSERT(dItem->object());
|
||||
if (!dItem->object()->isSingleInstance())
|
||||
dItem = dynamic_cast<ObjectTreeItem*>(dItem->parent());
|
||||
foreach (TreeItem *child, dItem->treeChildren()) {
|
||||
MetaObjectTreeItem *mItem = dynamic_cast<MetaObjectTreeItem*>(child);
|
||||
if (mItem && mItem->object()) {
|
||||
Q_ASSERT(mItem->object() == mobj);
|
||||
return mItem;
|
||||
}
|
||||
}
|
||||
return findMetaObjectTreeItem(metaObject);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
DataObjectTreeItem *UAVObjectTreeModel::findDataObjectTreeItem(UAVDataObject *object)
|
||||
DataObjectTreeItem* UAVObjectTreeModel::findDataObjectTreeItem(UAVDataObject *obj)
|
||||
{
|
||||
Q_ASSERT(object);
|
||||
TopTreeItem *root = object->isSettings() ? m_settingsTree : m_nonSettingsTree;
|
||||
foreach (TreeItem *child, root->treeChildren()) {
|
||||
DataObjectTreeItem *dItem = dynamic_cast<DataObjectTreeItem*>(child);
|
||||
if (dItem && dItem->object() && dItem->object()->isSingleInstance()) {
|
||||
if(dItem->object() == object) {
|
||||
return dItem;
|
||||
}
|
||||
} else {
|
||||
foreach (TreeItem *c, dItem->treeChildren()) {
|
||||
DataObjectTreeItem *d = dynamic_cast<DataObjectTreeItem*>(c);
|
||||
if (d && d->object() == object)
|
||||
return d;
|
||||
}
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
TopTreeItem *root = obj->isSettings() ? m_settingsTree : m_nonSettingsTree;
|
||||
return root->findDataObjectTreeItemByObjectId(obj->getObjID());
|
||||
}
|
||||
|
||||
MetaObjectTreeItem* UAVObjectTreeModel::findMetaObjectTreeItem(UAVMetaObject *obj)
|
||||
{
|
||||
UAVDataObject *dataObject = qobject_cast<UAVDataObject*>(obj->getParentObject());
|
||||
Q_ASSERT(dataObject);
|
||||
TopTreeItem *root = dataObject->isSettings() ? m_settingsTree : m_nonSettingsTree;
|
||||
return root->findMetaObjectTreeItemByObjectId(obj->getObjID());
|
||||
}
|
||||
|
||||
void UAVObjectTreeModel::updateHighlight(TreeItem *item)
|
||||
|
@ -31,6 +31,7 @@
|
||||
#include "treeitem.h"
|
||||
#include <QAbstractItemModel>
|
||||
#include <QtCore/QMap>
|
||||
#include <QtCore/QList>
|
||||
#include <QtGui/QColor>
|
||||
|
||||
class TopTreeItem;
|
||||
@ -48,7 +49,7 @@ class UAVObjectTreeModel : public QAbstractItemModel
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
explicit UAVObjectTreeModel(QObject *parent = 0);
|
||||
explicit UAVObjectTreeModel(QObject *parent = 0, bool categorize=true);
|
||||
~UAVObjectTreeModel();
|
||||
|
||||
QVariant data(const QModelIndex &index, int role) const;
|
||||
@ -68,6 +69,9 @@ public:
|
||||
m_recentlyUpdatedTimeout = timeout;
|
||||
TreeItem::setHighlightTime(timeout);
|
||||
}
|
||||
void setOnlyHilightChangedValues(bool hilight) {m_onlyHilightChangedValues = hilight; }
|
||||
|
||||
QList<QModelIndex> getMetaDataIndexes();
|
||||
|
||||
signals:
|
||||
|
||||
@ -79,17 +83,20 @@ private slots:
|
||||
void updateHighlight(TreeItem*);
|
||||
|
||||
private:
|
||||
void setupModelData(UAVObjectManager *objManager, bool categorize = true);
|
||||
QModelIndex index(TreeItem *item);
|
||||
void addDataObject(UAVDataObject *obj);
|
||||
void addMetaObject(UAVMetaObject *obj, TreeItem *parent);
|
||||
void addDataObject(UAVDataObject *obj, bool categorize = true);
|
||||
MetaObjectTreeItem *addMetaObject(UAVMetaObject *obj, TreeItem *parent);
|
||||
void addArrayField(UAVObjectField *field, TreeItem *parent);
|
||||
|
||||
void addSingleField(int index, UAVObjectField *field, TreeItem *parent);
|
||||
void addInstance(UAVObject *obj, TreeItem *parent);
|
||||
|
||||
TreeItem *createCategoryItems(QStringList categoryPath, TreeItem *root);
|
||||
|
||||
QString updateMode(quint8 updateMode);
|
||||
void setupModelData(UAVObjectManager *objManager);
|
||||
ObjectTreeItem *findObjectTreeItem(UAVObject *obj);
|
||||
DataObjectTreeItem *findDataObjectTreeItem(UAVDataObject *obj);
|
||||
MetaObjectTreeItem *findMetaObjectTreeItem(UAVMetaObject *obj);
|
||||
|
||||
TreeItem *m_rootItem;
|
||||
TopTreeItem *m_settingsTree;
|
||||
@ -97,6 +104,7 @@ private:
|
||||
int m_recentlyUpdatedTimeout;
|
||||
QColor m_recentlyUpdatedColor;
|
||||
QColor m_manuallyChangedColor;
|
||||
bool m_onlyHilightChangedValues;
|
||||
|
||||
// Highlight manager to handle highlighting of tree items.
|
||||
HighLightManager *m_highlightManager;
|
||||
|
@ -31,7 +31,7 @@
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
UAVMetaObject::UAVMetaObject(quint32 objID, const QString& name, UAVObject* parent):
|
||||
UAVMetaObject::UAVMetaObject(quint32 objID, const QString& name, UAVObject *parent):
|
||||
UAVObject(objID, true, name)
|
||||
{
|
||||
this->parent = parent;
|
||||
|
@ -145,6 +145,22 @@ void UAVObject::setDescription(const QString& description)
|
||||
this->description = description;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the category of the object
|
||||
*/
|
||||
QString UAVObject::getCategory()
|
||||
{
|
||||
return category;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the category of the object
|
||||
*/
|
||||
void UAVObject::setCategory(const QString& category)
|
||||
{
|
||||
this->category = category;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Get the total number of bytes of the object's data
|
||||
|
@ -103,6 +103,7 @@ public:
|
||||
quint32 getInstID();
|
||||
bool isSingleInstance();
|
||||
QString getName();
|
||||
QString getCategory();
|
||||
QString getDescription();
|
||||
quint32 getNumBytes();
|
||||
qint32 pack(quint8* dataOut);
|
||||
@ -163,6 +164,7 @@ protected:
|
||||
bool isSingleInst;
|
||||
QString name;
|
||||
QString description;
|
||||
QString category;
|
||||
quint32 numBytes;
|
||||
QMutex* mutex;
|
||||
quint8* data;
|
||||
@ -170,6 +172,7 @@ protected:
|
||||
|
||||
void initializeFields(QList<UAVObjectField*>& fields, quint8* data, quint32 numBytes);
|
||||
void setDescription(const QString& description);
|
||||
void setCategory(const QString& category);
|
||||
};
|
||||
|
||||
#endif // UAVOBJECT_H
|
||||
|
@ -8,26 +8,26 @@
|
||||
* @{
|
||||
* @addtogroup UAVObjectsPlugin UAVObjects Plugin
|
||||
* @{
|
||||
*
|
||||
* @note Object definition file: $(XMLFILE).
|
||||
*
|
||||
* @note Object definition file: $(XMLFILE).
|
||||
* This is an automatically generated file.
|
||||
* DO NOT modify manually.
|
||||
*
|
||||
* @brief The UAVUObjects GCS plugin
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
/*
|
||||
* 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
|
||||
*
|
||||
* 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.,
|
||||
*
|
||||
* 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 "$(NAMELC).h"
|
||||
@ -35,6 +35,7 @@
|
||||
|
||||
const QString $(NAME)::NAME = QString("$(NAME)");
|
||||
const QString $(NAME)::DESCRIPTION = QString("$(DESCRIPTION)");
|
||||
const QString $(NAME)::CATEGORY = QString("$(CATEGORY)");
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
@ -51,6 +52,9 @@ $(FIELDSINIT)
|
||||
// Set the object description
|
||||
setDescription(DESCRIPTION);
|
||||
|
||||
// Set the Category of this object type
|
||||
setCategory(CATEGORY);
|
||||
|
||||
connect(this, SIGNAL(objectUpdated(UAVObject*)),
|
||||
SLOT(emitNotifications()));
|
||||
}
|
||||
|
@ -54,6 +54,7 @@ $(DATAFIELDINFO)
|
||||
static const quint32 OBJID = $(OBJIDHEX);
|
||||
static const QString NAME;
|
||||
static const QString DESCRIPTION;
|
||||
static const QString CATEGORY;
|
||||
static const bool ISSINGLEINST = $(ISSINGLEINST);
|
||||
static const bool ISSETTINGS = $(ISSETTINGS);
|
||||
static const quint32 NUMBYTES = sizeof(DataFields);
|
||||
|
@ -43,7 +43,6 @@ Node::Node(MixerCurveWidget *graphWidget)
|
||||
setCacheMode(DeviceCoordinateCache);
|
||||
setZValue(-1);
|
||||
vertical = false;
|
||||
value = 0;
|
||||
}
|
||||
|
||||
void Node::addEdge(Edge *edge)
|
||||
@ -61,14 +60,14 @@ QList<Edge *> Node::edges() const
|
||||
QRectF Node::boundingRect() const
|
||||
{
|
||||
qreal adjust = 2;
|
||||
return QRectF(-10 - adjust, -10 - adjust,
|
||||
23 + adjust, 23 + adjust);
|
||||
return QRectF(-12 - adjust, -12 - adjust,
|
||||
28 + adjust, 28 + adjust);
|
||||
}
|
||||
|
||||
QPainterPath Node::shape() const
|
||||
{
|
||||
QPainterPath path;
|
||||
path.addEllipse(-10, -10, 20, 20);
|
||||
path.addEllipse(-12, -12, 25, 25);
|
||||
return path;
|
||||
}
|
||||
|
||||
@ -92,59 +91,60 @@ void Node::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWid
|
||||
}
|
||||
painter->setBrush(gradient);
|
||||
painter->setPen(QPen(Qt::black, 0));
|
||||
painter->drawEllipse(-10, -10, 20, 20);
|
||||
painter->drawEllipse(-12, -12, 25, 25);
|
||||
|
||||
painter->setPen(QPen(Qt::white, 0));
|
||||
painter->drawText(-10, 3, QString().sprintf("%.2f", value()));
|
||||
}
|
||||
|
||||
void Node::verticalMove(bool flag){
|
||||
vertical = flag;
|
||||
}
|
||||
|
||||
double Node::getValue() {
|
||||
return value;
|
||||
}
|
||||
|
||||
void Node::setValue(double val) {
|
||||
value = val;
|
||||
}
|
||||
|
||||
|
||||
QVariant Node::itemChange(GraphicsItemChange change, const QVariant &value)
|
||||
{
|
||||
|
||||
QPointF newPos = value.toPointF();
|
||||
double Node::value() {
|
||||
double h = graph->sceneRect().height();
|
||||
double ratio = (h - pos().y()) / h;
|
||||
return ((graph->getMax() - graph->getMin()) * ratio ) + graph->getMin();
|
||||
}
|
||||
|
||||
|
||||
QVariant Node::itemChange(GraphicsItemChange change, const QVariant &val)
|
||||
{
|
||||
QPointF newPos = val.toPointF();
|
||||
double h = graph->sceneRect().height();
|
||||
|
||||
switch (change) {
|
||||
case ItemPositionChange: {
|
||||
if (!vertical)
|
||||
break;
|
||||
// Force node to move vertically
|
||||
newPos.setX(pos().x());
|
||||
// Stay inside graph
|
||||
if (newPos.y() < 0)
|
||||
newPos.setY(0);
|
||||
//qDebug() << h << " - " << newPos.y();
|
||||
if (newPos.y() > h)
|
||||
newPos.setY(h);
|
||||
return newPos;
|
||||
|
||||
if (!vertical)
|
||||
break;
|
||||
|
||||
// Force node to move vertically
|
||||
newPos.setX(pos().x());
|
||||
|
||||
// Stay inside graph
|
||||
if (newPos.y() < 0)
|
||||
newPos.setY(0);
|
||||
//qDebug() << h << " - " << newPos.y();
|
||||
if (newPos.y() > h)
|
||||
newPos.setY(h);
|
||||
|
||||
return newPos;
|
||||
}
|
||||
case ItemPositionHasChanged: {
|
||||
foreach (Edge *edge, edgeList)
|
||||
edge->adjust();
|
||||
|
||||
double min = graph->getMin();
|
||||
double range = graph->getMax() - min;
|
||||
double ratio = (h - newPos.y()) / h;
|
||||
double val = (range * ratio ) + min;
|
||||
setValue(val);
|
||||
update();
|
||||
|
||||
graph->itemMoved(val);
|
||||
graph->itemMoved(value());
|
||||
break;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
};
|
||||
|
||||
return QGraphicsItem::itemChange(change, value);
|
||||
return QGraphicsItem::itemChange(change, val);
|
||||
}
|
||||
|
||||
void Node::mousePressEvent(QGraphicsSceneMouseEvent *event)
|
||||
|
@ -55,22 +55,21 @@ public:
|
||||
QPainterPath shape() const;
|
||||
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget);
|
||||
|
||||
void setValue(double val);
|
||||
double getValue();
|
||||
double value();
|
||||
|
||||
protected:
|
||||
QVariant itemChange(GraphicsItemChange change, const QVariant &value);
|
||||
QVariant itemChange(GraphicsItemChange change, const QVariant &val);
|
||||
|
||||
void mousePressEvent(QGraphicsSceneMouseEvent *event);
|
||||
void mouseReleaseEvent(QGraphicsSceneMouseEvent *event);
|
||||
|
||||
private:
|
||||
|
||||
double value;
|
||||
QList<Edge *> edgeList;
|
||||
QPointF newPos;
|
||||
MixerCurveWidget *graph;
|
||||
bool vertical;
|
||||
|
||||
};
|
||||
|
||||
#endif // MIXERCURVEPOINT_H
|
||||
|
@ -69,6 +69,7 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent)
|
||||
//plot->setElementId("map");
|
||||
scene->addItem(plot);
|
||||
plot->setZValue(-1);
|
||||
|
||||
scene->setSceneRect(plot->boundingRect());
|
||||
setScene(scene);
|
||||
|
||||
@ -77,11 +78,11 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent)
|
||||
|
||||
MixerCurveWidget::~MixerCurveWidget()
|
||||
{
|
||||
for (int i=0; i<nodePool.count(); i++)
|
||||
delete nodePool.at(i);
|
||||
while (!nodePool.isEmpty())
|
||||
delete nodePool.takeFirst();
|
||||
|
||||
for (int i=0; i<edgePool.count(); i++)
|
||||
delete edgePool.at(i);
|
||||
while (!edgePool.isEmpty())
|
||||
delete edgePool.takeFirst();
|
||||
}
|
||||
|
||||
Node* MixerCurveWidget::getNode(int index)
|
||||
@ -122,14 +123,11 @@ Edge* MixerCurveWidget::getEdge(int index, Node* sourceNode, Node* destNode)
|
||||
If a curve exists already, resets it.
|
||||
Points should be between 0 and 1.
|
||||
*/
|
||||
void MixerCurveWidget::initCurve(QList<double> points)
|
||||
void MixerCurveWidget::initCurve(const QList<double>* points)
|
||||
{
|
||||
if (points.length() < 2)
|
||||
if (points->length() < 2)
|
||||
return; // We need at least 2 points on a curve!
|
||||
|
||||
if (nodeList.count() != points.count())
|
||||
initNodes(points.count());
|
||||
|
||||
// finally, set node positions
|
||||
setCurve(points);
|
||||
}
|
||||
@ -139,12 +137,8 @@ void MixerCurveWidget::initNodes(int numPoints)
|
||||
// First of all, clear any existing list
|
||||
if (nodeList.count()) {
|
||||
foreach (Node *node, nodeList ) {
|
||||
QList<Edge*> edges = node->edges();
|
||||
foreach(Edge *edge, edges) {
|
||||
if (edge->destNode() == node) {
|
||||
delete edge;
|
||||
}
|
||||
else {
|
||||
foreach(Edge *edge, node->edges()) {
|
||||
if (edge->sourceNode() == node) {
|
||||
scene()->removeItem(edge);
|
||||
}
|
||||
}
|
||||
@ -163,6 +157,8 @@ void MixerCurveWidget::initNodes(int numPoints)
|
||||
nodeList.append(node);
|
||||
scene()->addItem(node);
|
||||
|
||||
node->setPos(0,0);
|
||||
|
||||
if (prevNode) {
|
||||
scene()->addItem(getEdge(i, prevNode, node));
|
||||
}
|
||||
@ -179,7 +175,7 @@ QList<double> MixerCurveWidget::getCurve() {
|
||||
QList<double> list;
|
||||
|
||||
foreach(Node *node, nodeList) {
|
||||
list.append(node->getValue());
|
||||
list.append(node->value());
|
||||
}
|
||||
|
||||
return list;
|
||||
@ -187,51 +183,48 @@ QList<double> MixerCurveWidget::getCurve() {
|
||||
/**
|
||||
Sets a linear graph
|
||||
*/
|
||||
void MixerCurveWidget::initLinearCurve(quint32 numPoints, double maxValue, double minValue)
|
||||
void MixerCurveWidget::initLinearCurve(int numPoints, double maxValue, double minValue)
|
||||
{
|
||||
Q_UNUSED(maxValue);
|
||||
Q_UNUSED(minValue);
|
||||
double range = setRange(minValue, maxValue);
|
||||
|
||||
QList<double> points;
|
||||
for (double i=0; i<numPoints;i++) {
|
||||
double val = ((curveMax - curveMin) * (i/(numPoints-1))) + curveMin;
|
||||
for (double i=0; i < (double)numPoints; i++) {
|
||||
double val = (range * ( i / (double)(numPoints-1) ) ) + minValue;
|
||||
points.append(val);
|
||||
}
|
||||
initCurve(points);
|
||||
initCurve(&points);
|
||||
}
|
||||
/**
|
||||
Setd the current curve settings
|
||||
*/
|
||||
void MixerCurveWidget::setCurve(QList<double> points)
|
||||
void MixerCurveWidget::setCurve(const QList<double>* points)
|
||||
{
|
||||
curveUpdating = true;
|
||||
|
||||
if (nodeList.count() != points.count())
|
||||
initNodes(points.count());
|
||||
int ptCnt = points->count();
|
||||
if (nodeList.count() != ptCnt)
|
||||
initNodes(ptCnt);
|
||||
|
||||
double min = curveMin + 10;
|
||||
double max = curveMax + 10;
|
||||
double range = curveMax - curveMin;
|
||||
|
||||
qreal w = plot->boundingRect().width()/(points.count()-1);
|
||||
qreal w = plot->boundingRect().width()/(ptCnt-1);
|
||||
qreal h = plot->boundingRect().height();
|
||||
for (int i=0; i<points.count(); i++) {
|
||||
for (int i=0; i<ptCnt; i++) {
|
||||
|
||||
double val = points.at(i);
|
||||
if (val < curveMin)
|
||||
val = curveMin;
|
||||
if (val > curveMax)
|
||||
val = curveMax;
|
||||
double val = (points->at(i) < curveMin) ? curveMin : (points->at(i) > curveMax) ? curveMax : points->at(i);
|
||||
|
||||
val += 10;
|
||||
val -= min;
|
||||
val /= (max - min);
|
||||
val += range;
|
||||
val -= (curveMin + range);
|
||||
val /= range;
|
||||
|
||||
nodeList.at(i)->setPos(w*i, h - (val*h));
|
||||
nodeList.at(i)->verticalMove(true);
|
||||
Node* node = nodeList.at(i);
|
||||
node->setPos(w*i, h - (val*h));
|
||||
node->verticalMove(true);
|
||||
}
|
||||
|
||||
curveUpdating = false;
|
||||
|
||||
update();
|
||||
|
||||
emit curveUpdated(points, (double)0);
|
||||
}
|
||||
|
||||
@ -252,13 +245,11 @@ void MixerCurveWidget::resizeEvent(QResizeEvent* event)
|
||||
fitInView(plot, Qt::KeepAspectRatio);
|
||||
}
|
||||
|
||||
|
||||
|
||||
void MixerCurveWidget::itemMoved(double itemValue)
|
||||
{
|
||||
if (!curveUpdating) {
|
||||
QList<double> list = getCurve();
|
||||
emit curveUpdated(list, itemValue);
|
||||
QList<double> curve = getCurve();
|
||||
emit curveUpdated(&curve, itemValue);
|
||||
}
|
||||
}
|
||||
|
||||
@ -278,8 +269,9 @@ double MixerCurveWidget::getMax()
|
||||
{
|
||||
return curveMax;
|
||||
}
|
||||
void MixerCurveWidget::setRange(double min, double max)
|
||||
double MixerCurveWidget::setRange(double min, double max)
|
||||
{
|
||||
curveMin = min;
|
||||
curveMax = max;
|
||||
return curveMax - curveMin;
|
||||
}
|
||||
|
@ -44,20 +44,20 @@ public:
|
||||
MixerCurveWidget(QWidget *parent = 0);
|
||||
~MixerCurveWidget();
|
||||
void itemMoved(double itemValue); // Callback when a point is moved, to be updated
|
||||
void initCurve (QList<double> points);
|
||||
void initCurve (const QList<double>* points);
|
||||
QList<double> getCurve();
|
||||
void initLinearCurve(quint32 numPoints, double maxValue = 1, double minValue = 0);
|
||||
void setCurve(QList<double>);
|
||||
void initLinearCurve(int numPoints, double maxValue = 1, double minValue = 0);
|
||||
void setCurve(const QList<double>* points);
|
||||
void setMin(double value);
|
||||
double getMin();
|
||||
void setMax(double value);
|
||||
double getMax();
|
||||
void setRange(double min, double max);
|
||||
double setRange(double min, double max);
|
||||
|
||||
static const int NODE_NUMELEM = 5;
|
||||
|
||||
signals:
|
||||
void curveUpdated(QList<double>, double );
|
||||
void curveUpdated(const QList<double>* points, const double value);
|
||||
|
||||
private slots:
|
||||
|
||||
|
@ -55,11 +55,6 @@ Telemetry::Telemetry(UAVTalk* utalk, UAVObjectManager* objMngr)
|
||||
connect(utalk, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(transactionCompleted(UAVObject*,bool)));
|
||||
// Get GCS stats object
|
||||
gcsStatsObj = GCSTelemetryStats::GetInstance(objMngr);
|
||||
// Setup transaction timer
|
||||
transPending = false;
|
||||
transTimer = new QTimer(this);
|
||||
transTimer->stop();
|
||||
connect(transTimer, SIGNAL(timeout()), this, SLOT(transactionTimeout()));
|
||||
// Setup and start the periodic timer
|
||||
timeToNextUpdateMs = 0;
|
||||
updateTimer = new QTimer(this);
|
||||
@ -70,6 +65,12 @@ Telemetry::Telemetry(UAVTalk* utalk, UAVObjectManager* objMngr)
|
||||
txRetries = 0;
|
||||
}
|
||||
|
||||
Telemetry::~Telemetry()
|
||||
{
|
||||
for (QMap<quint32, ObjectTransactionInfo*>::iterator itr = transMap.begin(); itr != transMap.end(); ++itr)
|
||||
delete itr.value();
|
||||
}
|
||||
|
||||
/**
|
||||
* Register a new object for periodic updates (if enabled)
|
||||
*/
|
||||
@ -231,84 +232,81 @@ void Telemetry::updateObject(UAVObject* obj, quint32 eventType)
|
||||
*/
|
||||
void Telemetry::transactionCompleted(UAVObject* obj, bool success)
|
||||
{
|
||||
// Check if there is a pending transaction and the objects match
|
||||
if ( transPending && transInfo.obj->getObjID() == obj->getObjID() )
|
||||
// Lookup the transaction in the transaction map.
|
||||
quint32 objId = obj->getObjID();
|
||||
QMap<quint32, ObjectTransactionInfo*>::iterator itr = transMap.find(objId);
|
||||
if ( itr != transMap.end() )
|
||||
{
|
||||
// qDebug() << QString("Telemetry: transaction completed for %1").arg(obj->getName());
|
||||
// Complete transaction
|
||||
transTimer->stop();
|
||||
transPending = false;
|
||||
ObjectTransactionInfo *transInfo = itr.value();
|
||||
// Remove this transaction as it's complete.
|
||||
transInfo->timer->stop();
|
||||
transMap.remove(objId);
|
||||
delete transInfo;
|
||||
// Send signal
|
||||
obj->emitTransactionCompleted(success);
|
||||
// Process new object updates from queue
|
||||
processObjectQueue();
|
||||
} else
|
||||
{
|
||||
// qDebug() << "Error: received a transaction completed when did not expect it.";
|
||||
qDebug() << "Error: received a transaction completed when did not expect it.";
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Called when a transaction is not completed within the timeout period (timer event)
|
||||
*/
|
||||
void Telemetry::transactionTimeout()
|
||||
void Telemetry::transactionTimeout(ObjectTransactionInfo *transInfo)
|
||||
{
|
||||
// qDebug() << "Telemetry: transaction timeout.";
|
||||
transTimer->stop();
|
||||
// Proceed only if there is a pending transaction
|
||||
if ( transPending )
|
||||
transInfo->timer->stop();
|
||||
// Check if more retries are pending
|
||||
if (transInfo->retriesRemaining > 0)
|
||||
{
|
||||
// Check if more retries are pending
|
||||
if (transInfo.retriesRemaining > 0)
|
||||
{
|
||||
--transInfo.retriesRemaining;
|
||||
processObjectTransaction();
|
||||
++txRetries;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Terminate transaction
|
||||
utalk->cancelTransaction();
|
||||
transPending = false;
|
||||
// Send signal
|
||||
transInfo.obj->emitTransactionCompleted(false);
|
||||
// Process new object updates from queue
|
||||
processObjectQueue();
|
||||
++txErrors;
|
||||
}
|
||||
--transInfo->retriesRemaining;
|
||||
processObjectTransaction(transInfo);
|
||||
++txRetries;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Stop the timer.
|
||||
transInfo->timer->stop();
|
||||
// Terminate transaction
|
||||
utalk->cancelTransaction(transInfo->obj);
|
||||
// Send signal
|
||||
transInfo->obj->emitTransactionCompleted(false);
|
||||
// Remove this transaction as it's complete.
|
||||
transMap.remove(transInfo->obj->getObjID());
|
||||
delete transInfo;
|
||||
// Process new object updates from queue
|
||||
processObjectQueue();
|
||||
++txErrors;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Start an object transaction with UAVTalk, all information is stored in transInfo
|
||||
*/
|
||||
void Telemetry::processObjectTransaction()
|
||||
void Telemetry::processObjectTransaction(ObjectTransactionInfo *transInfo)
|
||||
{
|
||||
if (transPending)
|
||||
|
||||
// Initiate transaction
|
||||
if (transInfo->objRequest)
|
||||
{
|
||||
// qDebug() << tr("Process Object transaction for %1").arg(transInfo.obj->getName());
|
||||
// Initiate transaction
|
||||
if (transInfo.objRequest)
|
||||
{
|
||||
utalk->sendObjectRequest(transInfo.obj, transInfo.allInstances);
|
||||
}
|
||||
else
|
||||
{
|
||||
utalk->sendObject(transInfo.obj, transInfo.acked, transInfo.allInstances);
|
||||
}
|
||||
// Start timer if a response is expected
|
||||
if ( transInfo.objRequest || transInfo.acked )
|
||||
{
|
||||
transTimer->start(REQ_TIMEOUT_MS);
|
||||
}
|
||||
else
|
||||
{
|
||||
transTimer->stop();
|
||||
transPending = false;
|
||||
}
|
||||
} else
|
||||
utalk->sendObjectRequest(transInfo->obj, transInfo->allInstances);
|
||||
}
|
||||
else
|
||||
{
|
||||
// qDebug() << "Error: inside of processObjectTransaction with no transPending";
|
||||
utalk->sendObject(transInfo->obj, transInfo->acked, transInfo->allInstances);
|
||||
}
|
||||
// Start timer if a response is expected
|
||||
if ( transInfo->objRequest || transInfo->acked )
|
||||
{
|
||||
transInfo->timer->start(REQ_TIMEOUT_MS);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Otherwise, remove this transaction as it's complete.
|
||||
transMap.remove(transInfo->obj->getObjID());
|
||||
delete transInfo;
|
||||
}
|
||||
}
|
||||
|
||||
@ -318,7 +316,6 @@ void Telemetry::processObjectTransaction()
|
||||
void Telemetry::processObjectUpdates(UAVObject* obj, EventMask event, bool allInstances, bool priority)
|
||||
{
|
||||
// Push event into queue
|
||||
// qDebug() << "Push event into queue for obj " << QString("%1 event %2").arg(obj->getName()).arg(event);
|
||||
ObjectQueueInfo objInfo;
|
||||
objInfo.obj = obj;
|
||||
objInfo.event = event;
|
||||
@ -349,15 +346,8 @@ void Telemetry::processObjectUpdates(UAVObject* obj, EventMask event, bool allIn
|
||||
}
|
||||
}
|
||||
|
||||
// If there is no transaction in progress then process event
|
||||
if (!transPending)
|
||||
{
|
||||
// qDebug() << "No transaction pending, process object queue...";
|
||||
processObjectQueue();
|
||||
} else
|
||||
{
|
||||
// qDebug() << "Transaction pending, DO NOT process object queue...";
|
||||
}
|
||||
// Process the transaction
|
||||
processObjectQueue();
|
||||
}
|
||||
|
||||
/**
|
||||
@ -365,15 +355,6 @@ void Telemetry::processObjectUpdates(UAVObject* obj, EventMask event, bool allIn
|
||||
*/
|
||||
void Telemetry::processObjectQueue()
|
||||
{
|
||||
// qDebug() << "Process object queue " << tr("- Depth (%1 %2)").arg(objQueue.length()).arg(objPriorityQueue.length());
|
||||
|
||||
// Do nothing if a transaction is already in progress (should not happen)
|
||||
// but it does a lot
|
||||
if (transPending)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
// Get object information from queue (first the priority and then the regular queue)
|
||||
ObjectQueueInfo objInfo;
|
||||
if ( !objPriorityQueue.isEmpty() )
|
||||
@ -408,24 +389,23 @@ void Telemetry::processObjectQueue()
|
||||
if ( ( objInfo.event != EV_UNPACKED ) && ( ( objInfo.event != EV_UPDATED_PERIODIC ) || ( updateMode != UAVObject::UPDATEMODE_THROTTLED ) ) )
|
||||
{
|
||||
UAVObject::Metadata metadata = objInfo.obj->getMetadata();
|
||||
transInfo.obj = objInfo.obj;
|
||||
transInfo.allInstances = objInfo.allInstances;
|
||||
transInfo.retriesRemaining = MAX_RETRIES;
|
||||
transInfo.acked = UAVObject::GetGcsTelemetryAcked(metadata);
|
||||
ObjectTransactionInfo *transInfo = new ObjectTransactionInfo(this);
|
||||
transInfo->obj = objInfo.obj;
|
||||
transInfo->allInstances = objInfo.allInstances;
|
||||
transInfo->retriesRemaining = MAX_RETRIES;
|
||||
transInfo->acked = UAVObject::GetGcsTelemetryAcked(metadata);
|
||||
if ( objInfo.event == EV_UPDATED || objInfo.event == EV_UPDATED_MANUAL || objInfo.event == EV_UPDATED_PERIODIC )
|
||||
{
|
||||
transInfo.objRequest = false;
|
||||
transInfo->objRequest = false;
|
||||
}
|
||||
else if ( objInfo.event == EV_UPDATE_REQ )
|
||||
{
|
||||
transInfo.objRequest = true;
|
||||
transInfo->objRequest = true;
|
||||
}
|
||||
// Start transaction
|
||||
transPending = true;
|
||||
processObjectTransaction();
|
||||
} else
|
||||
{
|
||||
// qDebug() << QString("Process object queue: this is an unpack event for %1").arg(objInfo.obj->getName());
|
||||
transInfo->telem = this;
|
||||
// Insert the transaction into the transaction map.
|
||||
transMap.insert(objInfo.obj->getObjID(), transInfo);
|
||||
processObjectTransaction(transInfo);
|
||||
}
|
||||
|
||||
// If this is a metaobject then make necessary telemetry updates
|
||||
@ -579,6 +559,29 @@ void Telemetry::newInstance(UAVObject* obj)
|
||||
registerObject(obj);
|
||||
}
|
||||
|
||||
ObjectTransactionInfo::ObjectTransactionInfo(QObject* parent):QObject(parent)
|
||||
{
|
||||
obj = 0;
|
||||
allInstances = false;
|
||||
objRequest = false;
|
||||
retriesRemaining = 0;
|
||||
acked = false;
|
||||
telem = 0;
|
||||
// Setup transaction timer
|
||||
timer = new QTimer(this);
|
||||
timer->stop();
|
||||
connect(timer, SIGNAL(timeout()), this, SLOT(timeout()));
|
||||
}
|
||||
|
||||
ObjectTransactionInfo::~ObjectTransactionInfo()
|
||||
{
|
||||
telem = 0;
|
||||
timer->stop();
|
||||
delete timer;
|
||||
}
|
||||
|
||||
|
||||
void ObjectTransactionInfo::timeout()
|
||||
{
|
||||
if (!telem.isNull())
|
||||
telem->transactionTimeout(this);
|
||||
}
|
||||
|
@ -35,6 +35,24 @@
|
||||
#include <QMutexLocker>
|
||||
#include <QTimer>
|
||||
#include <QQueue>
|
||||
#include <QMap>
|
||||
|
||||
class ObjectTransactionInfo: public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
ObjectTransactionInfo(QObject * parent);
|
||||
~ObjectTransactionInfo();
|
||||
UAVObject* obj;
|
||||
bool allInstances;
|
||||
bool objRequest;
|
||||
qint32 retriesRemaining;
|
||||
bool acked;
|
||||
QPointer<class Telemetry>telem;
|
||||
QTimer* timer;
|
||||
private slots:
|
||||
void timeout();
|
||||
};
|
||||
|
||||
class Telemetry: public QObject
|
||||
{
|
||||
@ -54,24 +72,13 @@ public:
|
||||
} TelemetryStats;
|
||||
|
||||
Telemetry(UAVTalk* utalk, UAVObjectManager* objMngr);
|
||||
~Telemetry();
|
||||
TelemetryStats getStats();
|
||||
void resetStats();
|
||||
|
||||
void transactionTimeout(ObjectTransactionInfo *info);
|
||||
|
||||
signals:
|
||||
|
||||
private slots:
|
||||
void objectUpdatedAuto(UAVObject* obj);
|
||||
void objectUpdatedManual(UAVObject* obj);
|
||||
void objectUpdatedPeriodic(UAVObject* obj);
|
||||
void objectUnpacked(UAVObject* obj);
|
||||
void updateRequested(UAVObject* obj);
|
||||
void newObject(UAVObject* obj);
|
||||
void newInstance(UAVObject* obj);
|
||||
void processPeriodicUpdates();
|
||||
void transactionCompleted(UAVObject* obj, bool success);
|
||||
void transactionTimeout();
|
||||
|
||||
private:
|
||||
// Constants
|
||||
static const int REQ_TIMEOUT_MS = 250;
|
||||
@ -105,14 +112,6 @@ private:
|
||||
bool allInstances;
|
||||
} ObjectQueueInfo;
|
||||
|
||||
typedef struct {
|
||||
UAVObject* obj;
|
||||
bool allInstances;
|
||||
bool objRequest;
|
||||
qint32 retriesRemaining;
|
||||
bool acked;
|
||||
} ObjectTransactionInfo;
|
||||
|
||||
// Variables
|
||||
UAVObjectManager* objMngr;
|
||||
UAVTalk* utalk;
|
||||
@ -120,11 +119,9 @@ private:
|
||||
QList<ObjectTimeInfo> objList;
|
||||
QQueue<ObjectQueueInfo> objQueue;
|
||||
QQueue<ObjectQueueInfo> objPriorityQueue;
|
||||
ObjectTransactionInfo transInfo;
|
||||
bool transPending;
|
||||
QMap<quint32, ObjectTransactionInfo*>transMap;
|
||||
QMutex* mutex;
|
||||
QTimer* updateTimer;
|
||||
QTimer* transTimer;
|
||||
QTimer* statsTimer;
|
||||
qint32 timeToNextUpdateMs;
|
||||
quint32 txErrors;
|
||||
@ -137,9 +134,19 @@ private:
|
||||
void connectToObjectInstances(UAVObject* obj, quint32 eventMask);
|
||||
void updateObject(UAVObject* obj, quint32 eventMask);
|
||||
void processObjectUpdates(UAVObject* obj, EventMask event, bool allInstances, bool priority);
|
||||
void processObjectTransaction();
|
||||
void processObjectTransaction(ObjectTransactionInfo *transInfo);
|
||||
void processObjectQueue();
|
||||
|
||||
private slots:
|
||||
void objectUpdatedAuto(UAVObject* obj);
|
||||
void objectUpdatedManual(UAVObject* obj);
|
||||
void objectUpdatedPeriodic(UAVObject* obj);
|
||||
void objectUnpacked(UAVObject* obj);
|
||||
void updateRequested(UAVObject* obj);
|
||||
void newObject(UAVObject* obj);
|
||||
void newInstance(UAVObject* obj);
|
||||
void processPeriodicUpdates();
|
||||
void transactionCompleted(UAVObject* obj, bool success);
|
||||
|
||||
};
|
||||
|
||||
|
@ -72,8 +72,6 @@ UAVTalk::UAVTalk(QIODevice* iodev, UAVObjectManager* objMngr)
|
||||
|
||||
mutex = new QMutex(QMutex::Recursive);
|
||||
|
||||
respObj = NULL;
|
||||
|
||||
memset(&stats, 0, sizeof(ComStats));
|
||||
|
||||
connect(io, SIGNAL(readyRead()), this, SLOT(processInputStream()));
|
||||
@ -157,10 +155,18 @@ bool UAVTalk::sendObject(UAVObject* obj, bool acked, bool allInstances)
|
||||
/**
|
||||
* Cancel a pending transaction
|
||||
*/
|
||||
void UAVTalk::cancelTransaction()
|
||||
void UAVTalk::cancelTransaction(UAVObject* obj)
|
||||
{
|
||||
QMutexLocker locker(mutex);
|
||||
respObj = NULL;
|
||||
quint32 objId = obj->getObjID();
|
||||
if(io.isNull())
|
||||
return;
|
||||
QMap<quint32, Transaction*>::iterator itr = transMap.find(objId);
|
||||
if ( itr != transMap.end() )
|
||||
{
|
||||
transMap.remove(objId);
|
||||
delete itr.value();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -180,8 +186,10 @@ bool UAVTalk::objectTransaction(UAVObject* obj, quint8 type, bool allInstances)
|
||||
{
|
||||
if ( transmitObject(obj, type, allInstances) )
|
||||
{
|
||||
respObj = obj;
|
||||
respAllInstances = allInstances;
|
||||
Transaction *trans = new Transaction();
|
||||
trans->obj = obj;
|
||||
trans->allInstances = allInstances;
|
||||
transMap.insert(obj->getObjID(), trans);
|
||||
return true;
|
||||
}
|
||||
else
|
||||
@ -627,9 +635,15 @@ UAVObject* UAVTalk::updateObject(quint32 objId, quint16 instId, quint8* data)
|
||||
*/
|
||||
void UAVTalk::updateNack(UAVObject* obj)
|
||||
{
|
||||
if (respObj != NULL && respObj->getObjID() == obj->getObjID() && (respObj->getInstID() == obj->getInstID() || respAllInstances))
|
||||
Q_ASSERT(obj);
|
||||
if ( ! obj )
|
||||
return;
|
||||
quint32 objId = obj->getObjID();
|
||||
QMap<quint32, Transaction*>::iterator itr = transMap.find(objId);
|
||||
if ( itr != transMap.end() && (itr.value()->obj->getInstID() == obj->getInstID() || itr.value()->allInstances))
|
||||
{
|
||||
respObj = NULL;
|
||||
transMap.remove(objId);
|
||||
delete itr.value();
|
||||
emit transactionCompleted(obj, false);
|
||||
}
|
||||
}
|
||||
@ -640,9 +654,12 @@ void UAVTalk::updateNack(UAVObject* obj)
|
||||
*/
|
||||
void UAVTalk::updateAck(UAVObject* obj)
|
||||
{
|
||||
if (respObj != NULL && respObj->getObjID() == obj->getObjID() && (respObj->getInstID() == obj->getInstID() || respAllInstances))
|
||||
quint32 objId = obj->getObjID();
|
||||
QMap<quint32, Transaction*>::iterator itr = transMap.find(objId);
|
||||
if ( itr != transMap.end() && (itr.value()->obj->getInstID() == obj->getInstID() || itr.value()->allInstances))
|
||||
{
|
||||
respObj = NULL;
|
||||
transMap.remove(objId);
|
||||
delete itr.value();
|
||||
emit transactionCompleted(obj, true);
|
||||
}
|
||||
}
|
||||
@ -812,7 +829,7 @@ bool UAVTalk::transmitSingleObject(UAVObject* obj, quint8 type, bool allInstance
|
||||
txBuffer[dataOffset+length] = updateCRC(0, txBuffer, dataOffset + length);
|
||||
|
||||
// Send buffer, check that the transmit backlog does not grow above limit
|
||||
if (io && io->isWritable() && io->bytesToWrite() < TX_BUFFER_SIZE )
|
||||
if (!io.isNull() && io->isWritable() && io->bytesToWrite() < TX_BUFFER_SIZE )
|
||||
{
|
||||
io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH);
|
||||
}
|
||||
|
@ -31,6 +31,7 @@
|
||||
#include <QIODevice>
|
||||
#include <QMutex>
|
||||
#include <QMutexLocker>
|
||||
#include <QMap>
|
||||
#include <QSemaphore>
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavtalk_global.h"
|
||||
@ -55,7 +56,7 @@ public:
|
||||
~UAVTalk();
|
||||
bool sendObject(UAVObject* obj, bool acked, bool allInstances);
|
||||
bool sendObjectRequest(UAVObject* obj, bool allInstances);
|
||||
void cancelTransaction();
|
||||
void cancelTransaction(UAVObject* obj);
|
||||
ComStats getStats();
|
||||
void resetStats();
|
||||
|
||||
@ -66,6 +67,12 @@ private slots:
|
||||
void processInputStream(void);
|
||||
|
||||
private:
|
||||
|
||||
typedef struct {
|
||||
UAVObject* obj;
|
||||
bool allInstances;
|
||||
} Transaction;
|
||||
|
||||
// Constants
|
||||
static const int TYPE_MASK = 0xF8;
|
||||
static const int TYPE_VER = 0x20;
|
||||
@ -97,8 +104,7 @@ private:
|
||||
QPointer<QIODevice> io;
|
||||
UAVObjectManager* objMngr;
|
||||
QMutex* mutex;
|
||||
UAVObject* respObj;
|
||||
bool respAllInstances;
|
||||
QMap<quint32, Transaction*> transMap;
|
||||
quint8 rxBuffer[MAX_PACKET_LENGTH];
|
||||
quint8 txBuffer[MAX_PACKET_LENGTH];
|
||||
// Variables used by the receive state machine
|
||||
|
@ -20,6 +20,7 @@ isEmpty(QMAKESPEC) {
|
||||
win32:SPEC = win32-g++
|
||||
macx-g++:SPEC = macx-g++
|
||||
linux-g++:SPEC = linux-g++
|
||||
linux-g++-32:SPEC = linux-g++
|
||||
linux-g++-64:SPEC = linux-g++-64
|
||||
} else {
|
||||
SPEC = $$QMAKESPEC
|
||||
|
@ -56,6 +56,8 @@ void replaceCommonTags(QString& out, ObjectInfo* info)
|
||||
out.replace(QString("$(NAMELC)"), info->namelc);
|
||||
// Replace $(DESCRIPTION) tag
|
||||
out.replace(QString("$(DESCRIPTION)"), info->description);
|
||||
// Replace $(CATEGORY) tag
|
||||
out.replace(QString("$(CATEGORY)"), info->category);
|
||||
// Replace $(NAMEUC) tag
|
||||
out.replace(QString("$(NAMEUC)"), info->name.toUpper());
|
||||
// Replace $(OBJID) tag
|
||||
|
@ -499,6 +499,13 @@ QString UAVObjectParser::processObjectAttributes(QDomNode& node, ObjectInfo* inf
|
||||
info->name = attr.nodeValue();
|
||||
info->namelc = attr.nodeValue().toLower();
|
||||
|
||||
// Get category attribute if present
|
||||
attr = attributes.namedItem("category");
|
||||
if ( !attr.isNull() )
|
||||
{
|
||||
info->category = attr.nodeValue();
|
||||
}
|
||||
|
||||
// Get singleinstance attribute
|
||||
attr = attributes.namedItem("singleinstance");
|
||||
if ( attr.isNull() )
|
||||
|
@ -96,6 +96,7 @@ typedef struct {
|
||||
int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */
|
||||
QList<FieldInfo*> fields; /** The data fields for the object **/
|
||||
QString description; /** Description used for Doxygen **/
|
||||
QString category; /** Description used for Doxygen **/
|
||||
} ObjectInfo;
|
||||
|
||||
class UAVObjectParser
|
||||
@ -127,6 +128,7 @@ private:
|
||||
QString processObjectFields(QDomNode& childNode, ObjectInfo* info);
|
||||
QString processObjectAccess(QDomNode& childNode, ObjectInfo* info);
|
||||
QString processObjectDescription(QDomNode& childNode, QString * description);
|
||||
QString processObjectCategory(QDomNode& childNode, QString * category);
|
||||
QString processObjectMetadata(QDomNode& childNode, UpdateMode* mode, int* period, bool* acked);
|
||||
void calculateID(ObjectInfo* info);
|
||||
quint32 updateHash(quint32 value, quint32 hash);
|
||||
|
@ -1,7 +1,7 @@
|
||||
#
|
||||
# Project: OpenPilot
|
||||
# NSIS configuration file for OpenPilot GCS
|
||||
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2010-2011.
|
||||
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2010-2012.
|
||||
#
|
||||
# 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
|
||||
@ -21,14 +21,15 @@
|
||||
# This script requires Unicode NSIS 2.46 or higher:
|
||||
# http://www.scratchpaper.com/
|
||||
|
||||
# Features:
|
||||
# - Installs to the user local appdata path, no admin rights required.
|
||||
#
|
||||
# TODO:
|
||||
# - optionally install for all users (to Program Files with admin rights on Vista/7).
|
||||
# - install only built/used modules, not a whole directory.
|
||||
# - remove only installed files, not a whole directory.
|
||||
|
||||
;--------------------------------
|
||||
; Includes
|
||||
|
||||
!include "x64.nsh"
|
||||
|
||||
;--------------------------------
|
||||
; Paths
|
||||
|
||||
@ -36,12 +37,13 @@
|
||||
!define PROJECT_ROOT "..\.."
|
||||
!define NSIS_DATA_TREE "."
|
||||
!define GCS_BUILD_TREE "..\..\build\ground\openpilotgcs"
|
||||
!define UAVO_SYNTH_TREE "..\..\build\uavobject-synthetics"
|
||||
|
||||
; Default installation folder
|
||||
InstallDir "$LOCALAPPDATA\OpenPilot"
|
||||
InstallDir "$PROGRAMFILES\OpenPilot"
|
||||
|
||||
; Get installation folder from registry if available
|
||||
InstallDirRegKey HKCU "Software\OpenPilot" "Install Location"
|
||||
InstallDirRegKey HKLM "Software\OpenPilot" "Install Location"
|
||||
|
||||
;--------------------------------
|
||||
; Version information
|
||||
@ -82,7 +84,7 @@
|
||||
XPStyle on
|
||||
|
||||
; Request application privileges for Windows Vista/7
|
||||
RequestExecutionLevel user
|
||||
RequestExecutionLevel admin
|
||||
|
||||
; Compression level
|
||||
SetCompressor /solid lzma
|
||||
@ -90,7 +92,7 @@
|
||||
;--------------------------------
|
||||
; Branding
|
||||
|
||||
BrandingText "© 2010-2011 The OpenPilot Team, http://www.openpilot.org"
|
||||
BrandingText "© 2010-2012 The OpenPilot Team, http://www.openpilot.org"
|
||||
|
||||
!define MUI_ICON "${NSIS_DATA_TREE}\resources\openpilot.ico"
|
||||
!define MUI_HEADERIMAGE
|
||||
@ -113,6 +115,7 @@
|
||||
;--------------------------------
|
||||
; Settings for MUI_PAGE_FINISH
|
||||
!define MUI_FINISHPAGE_RUN
|
||||
!define MUI_FINISHPAGE_SHOWREADME "$INSTDIR\HISTORY.txt"
|
||||
!define MUI_FINISHPAGE_RUN_FUNCTION "RunApplication"
|
||||
|
||||
;--------------------------------
|
||||
@ -148,6 +151,7 @@
|
||||
;--------------------------------
|
||||
; Installer sections
|
||||
|
||||
; Copy GCS core files
|
||||
Section "Core files" InSecCore
|
||||
SectionIn RO
|
||||
SetOutPath "$INSTDIR\bin"
|
||||
@ -156,6 +160,7 @@ Section "Core files" InSecCore
|
||||
File "${PROJECT_ROOT}\HISTORY.txt"
|
||||
SectionEnd
|
||||
|
||||
; Copy GCS plugins
|
||||
Section "Plugins" InSecPlugins
|
||||
SectionIn RO
|
||||
SetOutPath "$INSTDIR\lib\openpilotgcs\plugins"
|
||||
@ -163,6 +168,7 @@ Section "Plugins" InSecPlugins
|
||||
File /r "${GCS_BUILD_TREE}\lib\openpilotgcs\plugins\*.pluginspec"
|
||||
SectionEnd
|
||||
|
||||
; Copy GCS resources
|
||||
Section "Resources" InSecResources
|
||||
SetOutPath "$INSTDIR\share\openpilotgcs\diagrams"
|
||||
File /r "${GCS_BUILD_TREE}\share\openpilotgcs\diagrams\*"
|
||||
@ -176,22 +182,51 @@ Section "Resources" InSecResources
|
||||
File /r "${GCS_BUILD_TREE}\share\openpilotgcs\pfd\*"
|
||||
SectionEnd
|
||||
|
||||
; Copy Notify plugin sound files
|
||||
Section "Sound files" InSecSounds
|
||||
SetOutPath "$INSTDIR\share\openpilotgcs\sounds"
|
||||
File /r "${GCS_BUILD_TREE}\share\openpilotgcs\sounds\*"
|
||||
SectionEnd
|
||||
|
||||
; Copy localization files
|
||||
; Disabled until GCS source is stable and properly localized
|
||||
Section "Localization" InSecLocalization
|
||||
SetOutPath "$INSTDIR\share\openpilotgcs\translations"
|
||||
; File /r "${GCS_BUILD_TREE}\share\openpilotgcs\translations\openpilotgcs_*.qm"
|
||||
File /r "${GCS_BUILD_TREE}\share\openpilotgcs\translations\qt_*.qm"
|
||||
SectionEnd
|
||||
|
||||
; Copy firmware files
|
||||
Section "Firmware" InSecFirmware
|
||||
; SetOutPath "$INSTDIR\firmware\${FIRMWARE_DIR}"
|
||||
; File /r "${PACKAGE_DIR}\${FIRMWARE_DIR}\*"
|
||||
SetOutPath "$INSTDIR\firmware"
|
||||
File /r "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_coptercontrol-${PACKAGE_LBL}.opfw"
|
||||
File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_coptercontrol-${PACKAGE_LBL}.opfw"
|
||||
File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_pipxtreme-${PACKAGE_LBL}.opfw"
|
||||
SectionEnd
|
||||
|
||||
; Copy utility files
|
||||
Section "-Utilities" InSecUtilities
|
||||
SetOutPath "$INSTDIR\utilities"
|
||||
File "/oname=OPLogConvert-${PACKAGE_LBL}.m" "${UAVO_SYNTH_TREE}\matlab\OPLogConvert.m"
|
||||
SectionEnd
|
||||
|
||||
; Copy driver files
|
||||
Section "-Drivers" InSecDrivers
|
||||
SetOutPath "$INSTDIR\drivers"
|
||||
File "${PROJECT_ROOT}\flight\Project\Windows USB\OpenPilot-CDC.inf"
|
||||
SectionEnd
|
||||
|
||||
; Preinstall OpenPilot CDC driver
|
||||
Section "CDC driver" InSecInstallDrivers
|
||||
InitPluginsDir
|
||||
SetOutPath "$PLUGINSDIR"
|
||||
${If} ${RunningX64}
|
||||
File "/oname=dpinst.exe" "${NSIS_DATA_TREE}\redist\dpinst_x64.exe"
|
||||
${Else}
|
||||
File "/oname=dpinst.exe" "${NSIS_DATA_TREE}\redist\dpinst_x86.exe"
|
||||
${EndIf}
|
||||
ExecWait '"$PLUGINSDIR\dpinst.exe" /lm /path "$INSTDIR\drivers"'
|
||||
SectionEnd
|
||||
|
||||
Section "Shortcuts" InSecShortcuts
|
||||
@ -239,6 +274,9 @@ SectionEnd
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecSounds} $(DESC_InSecSounds)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecLocalization} $(DESC_InSecLocalization)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecFirmware} $(DESC_InSecFirmware)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecUtilities} $(DESC_InSecUtilities)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecDrivers} $(DESC_InSecDrivers)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecInstallDrivers} $(DESC_InSecInstallDrivers)
|
||||
!insertmacro MUI_DESCRIPTION_TEXT ${InSecShortcuts} $(DESC_InSecShortcuts)
|
||||
!insertmacro MUI_FUNCTION_DESCRIPTION_END
|
||||
|
||||
@ -247,6 +285,7 @@ SectionEnd
|
||||
|
||||
Function .onInit
|
||||
|
||||
SetShellVarContext all
|
||||
!insertmacro MUI_LANGDLL_DISPLAY
|
||||
|
||||
FunctionEnd
|
||||
@ -260,6 +299,8 @@ Section "un.OpenPilot GCS" UnSecProgram
|
||||
RMDir /r /rebootok "$INSTDIR\lib"
|
||||
RMDir /r /rebootok "$INSTDIR\share"
|
||||
RMDir /r /rebootok "$INSTDIR\firmware"
|
||||
RMDir /r /rebootok "$INSTDIR\utilities"
|
||||
RMDir /r /rebootok "$INSTDIR\drivers"
|
||||
Delete /rebootok "$INSTDIR\HISTORY.txt"
|
||||
Delete /rebootok "$INSTDIR\Uninstall.exe"
|
||||
|
||||
@ -306,6 +347,7 @@ SectionEnd
|
||||
|
||||
Function un.onInit
|
||||
|
||||
SetShellVarContext all
|
||||
!insertmacro MUI_UNGETLANGUAGE
|
||||
|
||||
FunctionEnd
|
||||
|
BIN
package/winx86/redist/dpinst_x64.exe
Normal file
BIN
package/winx86/redist/dpinst_x64.exe
Normal file
Binary file not shown.
BIN
package/winx86/redist/dpinst_x86.exe
Normal file
BIN
package/winx86/redist/dpinst_x86.exe
Normal file
Binary file not shown.
@ -31,6 +31,9 @@
|
||||
LangString DESC_InSecSounds ${LANG_GERMAN} "GCS Sounddateien (benötigt für akustische Ereignisbenachrichtigungen)."
|
||||
LangString DESC_InSecLocalization ${LANG_GERMAN} "GCS Lokalisierung (für unterstützte Sprachen)."
|
||||
LangString DESC_InSecFirmware ${LANG_GERMAN} "OpenPilot firmware binaries."
|
||||
LangString DESC_InSecUtilities ${LANG_GERMAN} "OpenPilot utilities (Matlab log parser)."
|
||||
LangString DESC_InSecDrivers ${LANG_GERMAN} "OpenPilot hardware driver files (optional OpenPilot CDC driver)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_GERMAN} "Install OpenPilot CDC driver (optional)."
|
||||
LangString DESC_InSecShortcuts ${LANG_GERMAN} "Installiere Verknüpfungen unter Startmenü->Anwendungen."
|
||||
|
||||
;--------------------------------
|
||||
|
@ -31,6 +31,9 @@
|
||||
LangString DESC_InSecSounds ${LANG_ENGLISH} "GCS sound files (used for audible event notifications)."
|
||||
LangString DESC_InSecLocalization ${LANG_ENGLISH} "GCS localization (for supported languages)."
|
||||
LangString DESC_InSecFirmware ${LANG_ENGLISH} "OpenPilot firmware binaries."
|
||||
LangString DESC_InSecUtilities ${LANG_ENGLISH} "OpenPilot utilities (Matlab log parser)."
|
||||
LangString DESC_InSecDrivers ${LANG_ENGLISH} "OpenPilot hardware driver files (optional OpenPilot CDC driver)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_ENGLISH} "Install OpenPilot CDC driver (optional)."
|
||||
LangString DESC_InSecShortcuts ${LANG_ENGLISH} "Install application start menu shortcuts."
|
||||
|
||||
;--------------------------------
|
||||
|
@ -31,6 +31,9 @@
|
||||
LangString DESC_InSecSounds ${LANG_SPANISH} "Archivos de sonido del GCS (usados para los eventos y notificaciones audibles)."
|
||||
LangString DESC_InSecLocalization ${LANG_SPANISH} "Localización GCS (idiomas soportados)."
|
||||
LangString DESC_InSecFirmware ${LANG_SPANISH} "OpenPilot firmware binaries."
|
||||
LangString DESC_InSecUtilities ${LANG_SPANISH} "OpenPilot utilities (Matlab log parser)."
|
||||
LangString DESC_InSecDrivers ${LANG_SPANISH} "OpenPilot hardware driver files (optional OpenPilot CDC driver)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_SPANISH} "Install OpenPilot CDC driver (optional)."
|
||||
LangString DESC_InSecShortcuts ${LANG_SPANISH} "Instalar accesos directos de la aplicación (menú inicio y escritorio)."
|
||||
|
||||
;--------------------------------
|
||||
|
@ -31,6 +31,9 @@
|
||||
LangString DESC_InSecSounds ${LANG_FRENCH} "Fichiers son GCS (pour les notifications sonores)."
|
||||
LangString DESC_InSecLocalization ${LANG_FRENCH} "Fichiers de localisation (langues supportées)."
|
||||
LangString DESC_InSecFirmware ${LANG_FRENCH} "OpenPilot firmware binaries."
|
||||
LangString DESC_InSecUtilities ${LANG_FRENCH} "OpenPilot utilities (Matlab log parser)."
|
||||
LangString DESC_InSecDrivers ${LANG_FRENCH} "OpenPilot hardware driver files (optional OpenPilot CDC driver)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_FRENCH} "Install OpenPilot CDC driver (optional)."
|
||||
LangString DESC_InSecShortcuts ${LANG_FRENCH} "Installer les raccourcis dans le menu démarrer."
|
||||
|
||||
;--------------------------------
|
||||
|
@ -31,6 +31,9 @@
|
||||
LangString DESC_InSecSounds ${LANG_RUSSIAN} "Звуковые файлы (используются для звуковых уведомлений о событиях)."
|
||||
LangString DESC_InSecLocalization ${LANG_RUSSIAN} "Файлы языковой поддержки (для поддерживаемых языков)."
|
||||
LangString DESC_InSecFirmware ${LANG_RUSSIAN} "Файлы прошивок OpenPilot."
|
||||
LangString DESC_InSecUtilities ${LANG_RUSSIAN} "Утилиты (конвертор логов для Matlab)."
|
||||
LangString DESC_InSecDrivers ${LANG_RUSSIAN} "Файлы драйверов (опциональный драйвер CDC порта)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_RUSSIAN} "Установка опционального OpenPilot CDC драйвера."
|
||||
LangString DESC_InSecShortcuts ${LANG_RUSSIAN} "Установка ярлыков для приложения."
|
||||
|
||||
;--------------------------------
|
||||
|
@ -31,6 +31,9 @@
|
||||
LangString DESC_InSecSounds ${LANG_TRADCHINESE} "地面站音频文件(用于对于特定事件的提醒)."
|
||||
LangString DESC_InSecLocalization ${LANG_TRADCHINESE} "地面站本土化(适用于它所支持的语言)."
|
||||
LangString DESC_InSecFirmware ${LANG_TRADCHINESE} "OpenPilot firmware binaries."
|
||||
LangString DESC_InSecUtilities ${LANG_TRADCHINESE} "OpenPilot utilities (Matlab log parser)."
|
||||
LangString DESC_InSecDrivers ${LANG_TRADCHINESE} "OpenPilot hardware driver files (optional OpenPilot CDC driver)."
|
||||
LangString DESC_InSecInstallDrivers ${LANG_TRADCHINESE} "Install OpenPilot CDC driver (optional)."
|
||||
LangString DESC_InSecShortcuts ${LANG_TRADCHINESE} "安装开始菜单的快捷方式."
|
||||
|
||||
;--------------------------------
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user