mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-18 03:52:11 +01:00
Merge branch 'next' into corvuscorax/OP-1216_flight-control-refurbishment
This commit is contained in:
commit
3ea9042279
128
WHATSNEW.txt
128
WHATSNEW.txt
@ -1,12 +1,5 @@
|
||||
--- RELEASE-14.01-RC3 --- Cruising Ratt ---
|
||||
this issue includes the following fixes to previous RC2:
|
||||
OP-1088 OP-1141 OP-1166 OP-1187 OP-1191 OP-1195 OP-1211 OP-1218
|
||||
|
||||
Full list of bug fixed in this release is accessible here
|
||||
http://progress.openpilot.org/issues/?filter=11361
|
||||
|
||||
--- RELEASE-14.01-RC2 --- Cruising Ratt ---
|
||||
This is the RC2 for the first 2014 software release.
|
||||
--- RELEASE-14.01 --- Cruising Ratt ---
|
||||
This is the first 2014 software release.
|
||||
This version still supports the CopterControl and CC3D.
|
||||
It includes some major "under the hood" changes like migration
|
||||
to Qt5.1 and QtQuick2 widgets, an overhaul of UAVTalk to improve
|
||||
@ -20,12 +13,119 @@ Some additions in this release:
|
||||
the full list of features, improvements and bufixes shipping
|
||||
in this release is accessible here:
|
||||
|
||||
http://progress.openpilot.org/browse/OP/fixforversion/10220
|
||||
http://progress.openpilot.org/issues/?filter=11260
|
||||
|
||||
Issues fixes since RC1 release
|
||||
http://progress.openpilot.org/issues/?jql=labels%20%3D%20%2214.01-rc1%22
|
||||
OP-1166 OP-1168 OP-1169 OP-1176 OP-1177 OP-1178 OP-1179 OP-1180
|
||||
OP-1182 OP-1183 OP-1184 OP-1187 OP-1188 OP-1192
|
||||
** Improvement
|
||||
* [OP-771] - Change Wizard wording for better usability
|
||||
* [OP-791] - Integrate About Authors, OpenPilot GCS, Plugins dialogs into a single dialog window
|
||||
* [OP-803] - Gadgets get their configuration set twice when restoring workspaces during GCS startup
|
||||
* [OP-835] - Upgrade GCS to use Qt 5.1.0
|
||||
* [OP-883] - Make system and flight targets cleanup, pass 01
|
||||
* [OP-913] - Poor UAVObject data structure alignment on flight side causes performance degradation
|
||||
* [OP-951] - Add -Wshadow to flight CFLAGS and fix compilation breakage that results
|
||||
* [OP-966] - Scope Plugin Cleanup
|
||||
* [OP-984] - Provide multi PID banks, these should be assignable per flight mode.
|
||||
* [OP-996] - Add GCS option to remember the last selected workspace
|
||||
* [OP-1022] - Additional improvements for altitude hold
|
||||
* [OP-1036] - Improvements to Fixed Wing PathFollower and Nav
|
||||
* [OP-1059] - Typo (2x) in OpenPilot Setup Wizard - Output Calibration Window
|
||||
* [OP-1063] - Multirotor Configuration
|
||||
* [OP-1071] - Make map "emergency" lines less strong and dashed
|
||||
* [OP-1079] - Update to FreeRTOS v7.5.2
|
||||
* [OP-1082] - Add a ticker on the Welcome page showing Jira activity alongside the 'Project News'
|
||||
* [OP-1083] - Fix minor English spelling errors in stabilization tooltips
|
||||
* [OP-1085] - Upgrade GCS to use Qt 5.1.1
|
||||
* [OP-1094] - Turn on Progress for large SDK downloads / remove for MD5 files
|
||||
* [OP-1104] - Create BL version 6 to support larger firmware
|
||||
* [OP-1105] - If firmware .info blob is missing, test string is too long
|
||||
* [OP-1107] - Convert About dialog to QTQuick 2.0 and cleanup code.
|
||||
* [OP-1110] - Move Welcome screen to QtQuick 2
|
||||
* [OP-1111] - Move About to QtQuick2
|
||||
* [OP-1112] - Update contributors in GCS
|
||||
* [OP-1113] - Convert new PFD design to QtQuik2
|
||||
* [OP-1117] - Implement Horizon mode
|
||||
* [OP-1120] - Waypoint upload to board should be transacted
|
||||
* [OP-1133] - UAVTalk - expose send/request all instances of multi instance uav objects + related uavtalk fixes
|
||||
* [OP-1137] - Make Configuration Checkbox checked by default during uninstall
|
||||
* [OP-1141] - Add a further bias correction to barometer to better handle thermal variations
|
||||
* [OP-1143] - Missing Linux udev rules for Revolution boards
|
||||
* [OP-1153] - Provide a mean to instrument SystemMod stack utilization
|
||||
* [OP-1154] - Config Option to Automatically Increase Copter Throttle per 1/cos(bank_angle)
|
||||
* [OP-1158] - Add flight plan consistency checks
|
||||
* [OP-1160] - Some dev Env improvements, git hooks for messages, make prepare etc.
|
||||
|
||||
** Task
|
||||
* [OP-775] - Add ARM DSP library to OP codebase
|
||||
* [OP-813] - Manage merge of translation work to French
|
||||
* [OP-839] - Disable pyMyte dependency until really used
|
||||
* [OP-901] - Update STM32 StdPeriphLib to current
|
||||
* [OP-1087] - Update Qt used from Makefile to 5.1.1 for Windows and Mac
|
||||
* [OP-1109] - Created share Qt5 QtQuick2 port branch
|
||||
* [OP-1115] - Remove old artwork from the Artwork folder in Git
|
||||
* [OP-1119] - Write GCS plugin to access and display on board logs through uavtalk and export .opl files from logged uavobjects
|
||||
* [OP-1058] - UAVO:Implement a structured named accessors for multielement fields (Flight side)
|
||||
|
||||
** Bug
|
||||
* [OP-844] - Fix header comments in altitudehold.c
|
||||
* [OP-845] - Fix reading serial number from USB device on mac platform
|
||||
* [OP-846] - make qt_sdk_install fails
|
||||
* [OP-865] - PWM output 6 does not work on RM
|
||||
* [OP-887] - Provide some standard method of calibrating CPU speed and load measurement for boards
|
||||
* [OP-924] - PPM output does not have failsafe
|
||||
* [OP-934] - Incorrect timeout handling in rfm22b receiver
|
||||
* [OP-971] - Add UI to set AccellTau with revo board
|
||||
* [OP-1004] - UAVObjectBrowser, buttons don't work when scientific display is turned on
|
||||
* [OP-1014] - Com port connections are not working on OPLink
|
||||
* [OP-1018] - Zero point initialization in ETASv3 Airspeed sensor buggy
|
||||
* [OP-1027] - Segfault in UAVObjectBrowser when "Request"ing a UAVObjectCategory
|
||||
* [OP-1042] - Revo firmware version isn't read correctly through OPLink
|
||||
* [OP-1046] - Waypoint upload incomplete, no visual confirmation of failed uploads in uavobjectbrowser and waypoint editor
|
||||
* [OP-1048] - Attitude is not working with AccelTau > 0
|
||||
* [OP-1049] - CC3D attitude estimation failure after multiple settings changes and reboots
|
||||
* [OP-1067] - Invalid value for "LinkState"
|
||||
* [OP-1076] - CF Attitude filter in next randomly re-initializes on arming.
|
||||
* [OP-1078] - GCS segfaults if you close it after playing a log file
|
||||
* [OP-1080] - Unreliable detection of board through OPLink
|
||||
* [OP-1095] - GCS crashing on macosx 10.9 upon connection of oplink mini
|
||||
* [OP-1098] - CDC driver fails installation in Windows 8 or 8.1
|
||||
* [OP-1099] - Hidden icons in Configuration tab
|
||||
* [OP-1101] - Tools.mk has a few tabs and they need to be converted to spaces
|
||||
* [OP-1102] - OP GCS registers some file types is should not
|
||||
* [OP-1103] - GCS can not be compiled on OSX 10.8 after update to Qt5.1.1
|
||||
* [OP-1108] - Minor bugs found while reading the code
|
||||
* [OP-1114] - QGLWidget prohibits QListWidgetItem, set AA_DontCreateNativeWidgetSiblings as work around
|
||||
* [OP-1118] - QComboBox in UAVObjectBrowser does not stay in focus on Mac OSX
|
||||
* [OP-1121] - GCS will not exit if the Waypoint editor/PathPlanner dialog is open
|
||||
* [OP-1123] - GCS assertion failure when loading a waypoint file
|
||||
* [OP-1125] - UAVTalk - acking/nacking multi instance uavobjects is broken (when sending individual instances)
|
||||
* [OP-1132] - LIBEAY32.dll missing from installer
|
||||
* [OP-1139] - Add higher order correction to MS5611 driver for low and very low temperature compensation
|
||||
* [OP-1142] - No yaw in Horizon mode
|
||||
* [OP-1145] - OPLM to GCS link not reliable
|
||||
* [OP-1148] - Futaba R7008SB S.Bus protocol not supported
|
||||
* [OP-1151] - PFD display - inverted flight
|
||||
* [OP-1152] - Check Stack usage for CopterControl & CC3D
|
||||
* [OP-1155] - Fix OSX Packaging for GCS
|
||||
* [OP-1157] - sin_lookup_deg() returns garbage for negative angles
|
||||
* [OP-1166] - GCS misses yaw neutral setting on sync from initial connection
|
||||
* [OP-1167] - New flight mode switch position UAVO to work better with SITL, HITL
|
||||
* [OP-1168] - GCS Reload Board Data button doesn't work
|
||||
* [OP-1169] - GCS UAVO object titles off by one
|
||||
* [OP-1176] - Cruise Control checkboxes use wrong Default button
|
||||
* [OP-1177] - AltHold - Need a setting to allow disabling of bank angle throttle compensation in AH
|
||||
* [OP-1178] - After re-factoring of ConfigTaskWidget code the OPLink config page does not work reliably.
|
||||
* [OP-1179] - About box not working in Linux64 build (but probably the same is for Linux32)
|
||||
* [OP-1180] - GCS AltHold Tab - Reload button and update in real time
|
||||
* [OP-1181] - on radio configuration the pitch slider has maxed out on its own three times randomly
|
||||
* [OP-1182] - Telemetry monitor widget is too small on Mac
|
||||
* [OP-1183] - UAVBrowser displays hex string as decimal
|
||||
* [OP-1184] - Scope gadget - Stack monitor configurations need a cleanup
|
||||
* [OP-1188] - Optimize Stabilization Module stack size usage
|
||||
* [OP-1191] - Revo OPLink bug in GCS
|
||||
* [OP-1192] - Even though Throttle is off there is motor movement in some situations.
|
||||
* [OP-1211] - dT calculation in Stabilization and other modules unsafe
|
||||
* [OP-1218] - PIOS_COM is not thread safe
|
||||
* [OP-1228] - GCS Quits unexpectedly
|
||||
|
||||
--- RELEASE-13.06.04 ---
|
||||
This maintenance release includes the following fixes missing in (previously not released to public) RELEASE-13.06.03.
|
||||
|
@ -518,7 +518,7 @@ static void serialRxTask(__attribute__((unused)) void *parameters)
|
||||
int32_t ret = -2;
|
||||
uint8_t count = 5;
|
||||
while (count-- > 0 && ret < -1) {
|
||||
PIOS_COM_SendBufferNonBlocking(PIOS_COM_RADIO, data->serialRxBuf, bytes_to_process);
|
||||
ret = PIOS_COM_SendBufferNonBlocking(PIOS_COM_RADIO, data->serialRxBuf, bytes_to_process);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
|
@ -45,7 +45,6 @@
|
||||
#define TASK_PRIORITY_RX (tskIDLE_PRIORITY + 2)
|
||||
#define TASK_PRIORITY_TX (tskIDLE_PRIORITY + 2)
|
||||
#define TASK_PRIORITY_RADRX (tskIDLE_PRIORITY + 2)
|
||||
#define TASK_PRIORITY_TXPRI (tskIDLE_PRIORITY + 2)
|
||||
#define REQ_TIMEOUT_MS 250
|
||||
#define MAX_RETRIES 2
|
||||
#define STATS_UPDATE_PERIOD_MS 4000
|
||||
@ -59,8 +58,6 @@ static xQueueHandle queue;
|
||||
|
||||
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
|
||||
static xQueueHandle priorityQueue;
|
||||
static xTaskHandle telemetryTxPriTaskHandle;
|
||||
static void telemetryTxPriTask(void *parameters);
|
||||
#else
|
||||
#define priorityQueue queue
|
||||
#endif
|
||||
@ -119,11 +116,6 @@ int32_t TelemetryStart(void)
|
||||
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_RADIORX, radioRxTaskHandle);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
|
||||
xTaskCreate(telemetryTxPriTask, (signed char *)"TelPriTx", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY_TXPRI, &telemetryTxPriTaskHandle);
|
||||
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_TELEMETRYTXPRI, telemetryTxPriTaskHandle);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -276,7 +268,12 @@ static void updateObject(UAVObjHandle obj, int32_t eventType)
|
||||
eventMask |= EV_LOGGING_MANUAL;
|
||||
break;
|
||||
}
|
||||
UAVObjConnectQueue(obj, priorityQueue, eventMask);
|
||||
// note that all setting objects have implicitly IsPriority=true
|
||||
if (UAVObjIsPriority(obj)) {
|
||||
UAVObjConnectQueue(obj, priorityQueue, eventMask);
|
||||
} else {
|
||||
UAVObjConnectQueue(obj, queue, eventMask);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -374,32 +371,24 @@ static void telemetryTxTask(__attribute__((unused)) void *parameters)
|
||||
|
||||
// Loop forever
|
||||
while (1) {
|
||||
// Wait for queue message
|
||||
if (xQueueReceive(queue, &ev, portMAX_DELAY) == pdTRUE) {
|
||||
// Process event
|
||||
processObjEvent(&ev);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Telemetry transmit task, high priority
|
||||
*/
|
||||
/**
|
||||
* Tries to empty the high priority queue before handling any standard priority item
|
||||
*/
|
||||
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
|
||||
static void telemetryTxPriTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
UAVObjEvent ev;
|
||||
|
||||
// Loop forever
|
||||
while (1) {
|
||||
// Loop forever
|
||||
while (xQueueReceive(priorityQueue, &ev, 1) == pdTRUE) {
|
||||
// Process event
|
||||
processObjEvent(&ev);
|
||||
}
|
||||
#endif
|
||||
// Wait for queue message
|
||||
if (xQueueReceive(priorityQueue, &ev, portMAX_DELAY) == pdTRUE) {
|
||||
if (xQueueReceive(queue, &ev, 0) == pdTRUE) {
|
||||
// Process event
|
||||
processObjEvent(&ev);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* Telemetry receive task. Processes queue events and periodic updates.
|
||||
@ -488,9 +477,11 @@ static int32_t setUpdatePeriod(UAVObjHandle obj, int32_t updatePeriodMs)
|
||||
ev.instId = UAVOBJ_ALL_INSTANCES;
|
||||
ev.event = EV_UPDATED_PERIODIC;
|
||||
|
||||
ret = EventPeriodicQueueUpdate(&ev, queue, updatePeriodMs);
|
||||
xQueueHandle targetQueue = UAVObjIsPriority(obj) ? priorityQueue : queue;
|
||||
|
||||
ret = EventPeriodicQueueUpdate(&ev, targetQueue, updatePeriodMs);
|
||||
if (ret == -1) {
|
||||
ret = EventPeriodicQueueCreate(&ev, queue, updatePeriodMs);
|
||||
ret = EventPeriodicQueueCreate(&ev, targetQueue, updatePeriodMs);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
@ -512,9 +503,11 @@ static int32_t setLoggingPeriod(UAVObjHandle obj, int32_t updatePeriodMs)
|
||||
ev.instId = UAVOBJ_ALL_INSTANCES;
|
||||
ev.event = EV_LOGGING_PERIODIC;
|
||||
|
||||
ret = EventPeriodicQueueUpdate(&ev, queue, updatePeriodMs);
|
||||
xQueueHandle targetQueue = UAVObjIsPriority(obj) ? priorityQueue : queue;
|
||||
|
||||
ret = EventPeriodicQueueUpdate(&ev, targetQueue, updatePeriodMs);
|
||||
if (ret == -1) {
|
||||
ret = EventPeriodicQueueCreate(&ev, queue, updatePeriodMs);
|
||||
ret = EventPeriodicQueueCreate(&ev, targetQueue, updatePeriodMs);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
@ -346,6 +346,7 @@ int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, u
|
||||
* \param[in] len buffer length
|
||||
* \return -1 if port not available
|
||||
* \return -2 if mutex can't be taken;
|
||||
* \return -3 if data cannot be sent in the max allotted time of 5000msec
|
||||
* \return number of bytes transmitted on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendBuffer(uint32_t com_id, const uint8_t *buffer, uint16_t len)
|
||||
@ -358,7 +359,7 @@ int32_t PIOS_COM_SendBuffer(uint32_t com_id, const uint8_t *buffer, uint16_t len
|
||||
}
|
||||
PIOS_Assert(com_dev->has_tx);
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
if (xSemaphoreTake(com_dev->sendbuffer_sem, 0) != pdTRUE) {
|
||||
if (xSemaphoreTake(com_dev->sendbuffer_sem, 5) != pdTRUE) {
|
||||
return -2;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_FREERTOS */
|
||||
|
@ -44,6 +44,7 @@
|
||||
#define $(NAMEUC)_OBJID $(OBJIDHEX)
|
||||
#define $(NAMEUC)_ISSINGLEINST $(ISSINGLEINST)
|
||||
#define $(NAMEUC)_ISSETTINGS $(ISSETTINGS)
|
||||
#define $(NAMEUC)_ISPRIORITY $(ISPRIORITY)
|
||||
#define $(NAMEUC)_NUMBYTES sizeof($(NAME)Data)
|
||||
|
||||
/* Generic interface functions */
|
||||
|
@ -147,8 +147,7 @@ typedef struct {
|
||||
int32_t UAVObjInitialize();
|
||||
void UAVObjGetStats(UAVObjStats *statsOut);
|
||||
void UAVObjClearStats();
|
||||
UAVObjHandle UAVObjRegister(uint32_t id,
|
||||
int32_t isSingleInstance, int32_t isSettings, uint32_t numBytes, UAVObjInitializeCallback initCb);
|
||||
UAVObjHandle UAVObjRegister(uint32_t id, bool isSingleInstance, bool isSettings, bool isPriority, uint32_t num_bytes, UAVObjInitializeCallback initCb);
|
||||
UAVObjHandle UAVObjGetByID(uint32_t id);
|
||||
uint32_t UAVObjGetID(UAVObjHandle obj);
|
||||
uint32_t UAVObjGetNumBytes(UAVObjHandle obj);
|
||||
@ -158,6 +157,7 @@ uint16_t UAVObjCreateInstance(UAVObjHandle obj_handle, UAVObjInitializeCallback
|
||||
bool UAVObjIsSingleInstance(UAVObjHandle obj);
|
||||
bool UAVObjIsMetaobject(UAVObjHandle obj);
|
||||
bool UAVObjIsSettings(UAVObjHandle obj);
|
||||
bool UAVObjIsPriority(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);
|
||||
uint8_t UAVObjUpdateCRC(UAVObjHandle obj_handle, uint16_t instId, uint8_t crc);
|
||||
|
@ -65,7 +65,7 @@ int32_t $(NAME)Initialize(void)
|
||||
|
||||
// Register object with the object manager
|
||||
handle = UAVObjRegister($(NAMEUC)_OBJID,
|
||||
$(NAMEUC)_ISSINGLEINST, $(NAMEUC)_ISSETTINGS, $(NAMEUC)_NUMBYTES, &$(NAME)SetDefaults);
|
||||
$(NAMEUC)_ISSINGLEINST, $(NAMEUC)_ISSETTINGS, $(NAMEUC)_ISPRIORITY, $(NAMEUC)_NUMBYTES, &$(NAME)SetDefaults);
|
||||
|
||||
// Done
|
||||
return handle ? 0 : -1;
|
||||
|
@ -108,6 +108,7 @@ struct UAVOBase {
|
||||
bool isMeta : 1;
|
||||
bool isSingle : 1;
|
||||
bool isSettings : 1;
|
||||
bool isPriority : 1;
|
||||
} flags;
|
||||
} __attribute__((packed));
|
||||
|
||||
@ -339,7 +340,7 @@ static struct UAVOData *UAVObjAllocMulti(uint32_t num_bytes)
|
||||
* \return
|
||||
*/
|
||||
UAVObjHandle UAVObjRegister(uint32_t id,
|
||||
int32_t isSingleInstance, int32_t isSettings,
|
||||
bool isSingleInstance, bool isSettings, bool isPriority,
|
||||
uint32_t num_bytes,
|
||||
UAVObjInitializeCallback initCb)
|
||||
{
|
||||
@ -368,8 +369,11 @@ UAVObjHandle UAVObjRegister(uint32_t id,
|
||||
uavo_data->instance_size = num_bytes;
|
||||
if (isSettings) {
|
||||
uavo_data->base.flags.isSettings = true;
|
||||
// settings defaults to being sent with priority
|
||||
uavo_data->base.flags.isPriority = true;
|
||||
} else {
|
||||
uavo_data->base.flags.isPriority = isPriority;
|
||||
}
|
||||
|
||||
/* Initialize the embedded meta UAVO */
|
||||
UAVObjInitMetaData(&uavo_data->metaObj);
|
||||
|
||||
@ -605,6 +609,22 @@ bool UAVObjIsSettings(UAVObjHandle obj_handle)
|
||||
return uavo_base->flags.isSettings;
|
||||
}
|
||||
|
||||
/**
|
||||
* Is this a prioritized object?
|
||||
* \param[in] obj The object handle
|
||||
* \return True (1) if this is a prioritized object
|
||||
*/
|
||||
bool UAVObjIsPriority(UAVObjHandle obj_handle)
|
||||
{
|
||||
PIOS_Assert(obj_handle);
|
||||
|
||||
/* Recover the common object header */
|
||||
struct UAVOBase *uavo_base = (struct UAVOBase *)obj_handle;
|
||||
|
||||
return uavo_base->flags.isPriority;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Unpack an object from a byte array
|
||||
* \param[in] obj The object handle
|
||||
|
@ -2252,49 +2252,29 @@
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>240</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294945280</color>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-System</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>1.02360527502876e-306</yMaximum>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>6.92921153577169e-310</yMinimum>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Actuator</uavField>
|
||||
<uavField>StackRemaining-CallbackScheduler0</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve10>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Guidance</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>6.92921442421083e-310</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>-1.29073709209104e-231</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve10>
|
||||
<plotCurve11>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Watchdog</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>6.92920724098472e-310</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>3.91299991506267e-321</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve11>
|
||||
<plotCurve2>
|
||||
<color>4294945280</color>
|
||||
<color>4278190335</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavField>StackRemaining-CallbackScheduler1</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2302,43 +2282,43 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTxPri</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>1.72723371101889e-77</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>1.72723371101889e-77</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
<plotCurve4>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>6.92921438535612e-310</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>1.72723371101889e-77</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve4>
|
||||
<plotCurve5>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-GPS</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>1.72723371101889e-77</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>1.03979250816176e-312</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve5>
|
||||
<plotCurve6>
|
||||
<color>4294945280</color>
|
||||
<color>4294967040</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>6.92921438705062e-310</yMaximum>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>6.92921152810932e-310</yMinimum>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
<plotCurve4>
|
||||
<color>4278255615</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Stabilization</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve4>
|
||||
<plotCurve5>
|
||||
<color>4294923775</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Actuator</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve5>
|
||||
<plotCurve6>
|
||||
<color>4289331327</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Sensors</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve6>
|
||||
<plotCurve7>
|
||||
@ -2346,32 +2326,42 @@
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Altitude</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>7.4109846876187e-323</yMaximum>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>1.72723371101889e-77</yMinimum>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve7>
|
||||
<plotCurve8>
|
||||
<color>4294945280</color>
|
||||
<color>4283760767</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-AHRSComms</uavField>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>5.43472210425371e-323</yMaximum>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>1.72723371101889e-77</yMinimum>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve8>
|
||||
<plotCurve9>
|
||||
<color>4294945280</color>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Stabilization</uavField>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>1.72723371101889e-77</yMaximum>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>1.72723371101889e-77</yMinimum>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve9>
|
||||
<plotCurveCount>12</plotCurveCount>
|
||||
<plotCurve10>
|
||||
<color>4283782527</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-RadioRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve10>
|
||||
<plotCurveCount>11</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>1000</refreshInterval>
|
||||
</data>
|
||||
|
@ -2375,16 +2375,6 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve8>
|
||||
<plotCurve9>
|
||||
<color>4289331327</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTxPri</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve9>
|
||||
<plotCurve10>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
@ -2393,8 +2383,8 @@
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve10>
|
||||
<plotCurve11>
|
||||
</plotCurve9>
|
||||
<plotCurve10>
|
||||
<color>4283782527</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-RadioRx</uavField>
|
||||
@ -2403,7 +2393,7 @@
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve11>
|
||||
</plotCurve10>
|
||||
<plotCurveCount>12</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>1000</refreshInterval>
|
||||
|
@ -2260,7 +2260,7 @@
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>240</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294945280</color>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-System</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
@ -2272,37 +2272,17 @@
|
||||
<plotCurve1>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Actuator</uavField>
|
||||
<uavField>StackRemaining-CallbackScheduler0</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve10>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Guidance</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve10>
|
||||
<plotCurve11>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Watchdog</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve11>
|
||||
<plotCurve2>
|
||||
<color>4294945280</color>
|
||||
<color>4278190335</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavField>StackRemaining-CallbackScheduler1</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2310,9 +2290,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4294945280</color>
|
||||
<color>4294967040</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTxPri</uavField>
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2320,9 +2300,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
<plotCurve4>
|
||||
<color>4294945280</color>
|
||||
<color>4278255615</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavField>StackRemaining-Stabilization</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2330,9 +2310,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve4>
|
||||
<plotCurve5>
|
||||
<color>4294945280</color>
|
||||
<color>4294923775</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-GPS</uavField>
|
||||
<uavField>StackRemaining-Actuator</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2340,9 +2320,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve5>
|
||||
<plotCurve6>
|
||||
<color>4294945280</color>
|
||||
<color>4289331327</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavField>StackRemaining-Sensors</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2360,9 +2340,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve7>
|
||||
<plotCurve8>
|
||||
<color>4294945280</color>
|
||||
<color>4283760767</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-AHRSComms</uavField>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2370,16 +2350,26 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve8>
|
||||
<plotCurve9>
|
||||
<color>4294945280</color>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Stabilization</uavField>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve9>
|
||||
<plotCurveCount>12</plotCurveCount>
|
||||
<plotCurve10>
|
||||
<color>4283782527</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-RadioRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve10>
|
||||
<plotCurveCount>11</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>1000</refreshInterval>
|
||||
</data>
|
||||
|
@ -2,175 +2,6 @@
|
||||
<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
|
||||
<plist version="1.0">
|
||||
<dict>
|
||||
<key>CFBundleDocumentTypes</key>
|
||||
<array>
|
||||
<dict>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
<key>CFBundleTypeIconFile</key>
|
||||
<string>profile.icns</string>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>pro</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>Qt Project File</string>
|
||||
<key>LSHandlerRank</key>
|
||||
<string>Default</string>
|
||||
</dict>
|
||||
<dict>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
<key>CFBundleTypeIconFile</key>
|
||||
<string>prifile.icns</string>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>pri</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>Qt Project Include File</string>
|
||||
<key>LSHandlerRank</key>
|
||||
<string>Default</string>
|
||||
</dict>
|
||||
<dict>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>qrc</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>Qt Resource File</string>
|
||||
<key>LSHandlerRank</key>
|
||||
<string>Default</string>
|
||||
</dict>
|
||||
<dict>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>ui</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>Qt UI File</string>
|
||||
</dict>
|
||||
<dict>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>h</string>
|
||||
<string>hpp</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>Header File</string>
|
||||
<key>CFBundleTypeOSTypes</key>
|
||||
<array>
|
||||
<string>TEXT</string>
|
||||
<string>utxt</string>
|
||||
</array>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
</dict>
|
||||
<dict>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>cc</string>
|
||||
<string>CC</string>
|
||||
<string>cp</string>
|
||||
<string>CP</string>
|
||||
<string>cpp</string>
|
||||
<string>CPP</string>
|
||||
<string>cxx</string>
|
||||
<string>CXX</string>
|
||||
<string>c++</string>
|
||||
<string>C++</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>C++ Source File</string>
|
||||
<key>CFBundleTypeOSTypes</key>
|
||||
<array>
|
||||
<string>TEXT</string>
|
||||
<string>utxt</string>
|
||||
</array>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
</dict>
|
||||
<dict>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>mm</string>
|
||||
<string>MM</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>Objective-C++ Source File</string>
|
||||
<key>CFBundleTypeOSTypes</key>
|
||||
<array>
|
||||
<string>TEXT</string>
|
||||
<string>utxt</string>
|
||||
</array>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
</dict>
|
||||
<dict>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>m</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>Objective-C Source File</string>
|
||||
<key>CFBundleTypeOSTypes</key>
|
||||
<array>
|
||||
<string>TEXT</string>
|
||||
<string>utxt</string>
|
||||
</array>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
</dict>
|
||||
<dict>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>c</string>
|
||||
<string>C</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>C Source File</string>
|
||||
<key>CFBundleTypeOSTypes</key>
|
||||
<array>
|
||||
<string>TEXT</string>
|
||||
<string>utxt</string>
|
||||
</array>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
</dict>
|
||||
<dict>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>txt</string>
|
||||
<string>text</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>Text File</string>
|
||||
<key>CFBundleTypeOSTypes</key>
|
||||
<array>
|
||||
<string>TEXT</string>
|
||||
</array>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
</dict>
|
||||
<dict>
|
||||
<key>CFBundleTypeExtensions</key>
|
||||
<array>
|
||||
<string>*</string>
|
||||
</array>
|
||||
<key>CFBundleTypeName</key>
|
||||
<string>NSStringPboardType</string>
|
||||
<key>CFBundleTypeOSTypes</key>
|
||||
<array>
|
||||
<string>****</string>
|
||||
</array>
|
||||
<key>CFBundleTypeRole</key>
|
||||
<string>Editor</string>
|
||||
</dict>
|
||||
</array>
|
||||
<key>CFBundleGetInfoString</key>
|
||||
<string>OpenPilot GCS; Copyright OpenPilot</string>
|
||||
<key>CFBundleIconFile</key>
|
||||
|
@ -92,6 +92,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
addWidgetBinding("ManualControlSettings", "ChannelGroups", inpForm->ui->channelGroup, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelNeutral", inpForm->ui->channelNeutral, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelNeutral", inpForm->ui->neutralValue, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelMax", inpForm->ui->channelMax, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelMin", inpForm->ui->channelMin, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelMax", inpForm->ui->channelMax, index);
|
||||
|
||||
|
@ -81,5 +81,5 @@ IUAVGadgetConfiguration *MonitorGadgetFactory::createConfiguration(QSettings *qS
|
||||
|
||||
IOptionsPage *MonitorGadgetFactory::createOptionsPage(IUAVGadgetConfiguration *config)
|
||||
{
|
||||
return new MonitorGadgetOptionsPage(qobject_cast<MonitorGadgetConfiguration *>(config));
|
||||
return 0; // new MonitorGadgetOptionsPage(qobject_cast<MonitorGadgetConfiguration *>(config));
|
||||
}
|
||||
|
@ -72,6 +72,9 @@ void replaceCommonTags(QString & out, ObjectInfo *info)
|
||||
// Replace $(ISSETTINGS) tag
|
||||
out.replace(QString("$(ISSETTINGS)"), boolTo01String(info->isSettings));
|
||||
out.replace(QString("$(ISSETTINGSTF)"), boolToTRUEFALSEString(info->isSettings));
|
||||
// Replace $(ISPRIORITY) tag
|
||||
out.replace(QString("$(ISPRIORITY)"), boolTo01String(info->isPriority));
|
||||
out.replace(QString("$(ISPRIORITYTF)"), boolToTRUEFALSEString(info->isPriority));
|
||||
// Replace $(GCSACCESS) tag
|
||||
value = accessModeStr[info->gcsAccess];
|
||||
out.replace(QString("$(GCSACCESS)"), value);
|
||||
|
@ -623,9 +623,19 @@ QString UAVObjectParser::processObjectAttributes(QDomNode & node, ObjectInfo *in
|
||||
} else if (attr.nodeValue().compare(QString("false")) == 0) {
|
||||
info->isSettings = false;
|
||||
} else {
|
||||
return QString("Object:settings attribute value is invalid");
|
||||
return QString("Object:settings attribute value is invalid (true|false)");
|
||||
}
|
||||
|
||||
// Get priority attribute
|
||||
attr = attributes.namedItem("priority");
|
||||
info->isPriority = false;
|
||||
if (!attr.isNull()) {
|
||||
if (attr.nodeValue().compare(QString("true")) == 0) {
|
||||
info->isPriority = true;
|
||||
} else if (attr.nodeValue().compare(QString("false")) != 0) {
|
||||
return QString("Object:priority attribute value is invalid (true|false)");
|
||||
}
|
||||
}
|
||||
|
||||
// Settings objects can only have a single instance
|
||||
if (info->isSettings && !info->isSingleInst) {
|
||||
|
@ -84,6 +84,7 @@ typedef struct {
|
||||
quint32 id;
|
||||
bool isSingleInst;
|
||||
bool isSettings;
|
||||
bool isPriority;
|
||||
AccessMode gcsAccess;
|
||||
AccessMode flightAccess;
|
||||
bool flightTelemetryAcked;
|
||||
|
@ -1,5 +1,5 @@
|
||||
<xml>
|
||||
<object name="FirmwareIAPObj" singleinstance="true" settings="false" category="System">
|
||||
<object name="FirmwareIAPObj" singleinstance="true" settings="false" category="System" priority="true">
|
||||
<description>Queries board for SN, model, revision, and sends reset command</description>
|
||||
<field name="Command" units="" type="uint16" elements="1"/>
|
||||
<field name="Description" units="" type="uint8" elements="100"/>
|
||||
|
@ -1,5 +1,5 @@
|
||||
<xml>
|
||||
<object name="FlightTelemetryStats" singleinstance="true" settings="false" category="System">
|
||||
<object name="FlightTelemetryStats" singleinstance="true" settings="false" category="System" priority="true">
|
||||
<description>Maintains the telemetry statistics from the OpenPilot flight computer.</description>
|
||||
|
||||
<field name="Status" units="" type="enum" elements="1" options="Disconnected,HandshakeReq,HandshakeAck,Connected"/>
|
||||
|
@ -1,5 +1,5 @@
|
||||
<xml>
|
||||
<object name="GCSTelemetryStats" singleinstance="true" settings="false" category="System">
|
||||
<object name="GCSTelemetryStats" singleinstance="true" settings="false" category="System" priority="true">
|
||||
<description>The telemetry statistics from the ground computer</description>
|
||||
|
||||
<field name="Status" units="" type="enum" elements="1" options="Disconnected,HandshakeReq,HandshakeAck,Connected"/>
|
||||
|
@ -1,6 +1,6 @@
|
||||
<xml>
|
||||
<object name="ObjectPersistence" singleinstance="true" settings="false" category="System">
|
||||
<description>Someone who knows please enter this</description>
|
||||
<object name="ObjectPersistence" singleinstance="true" settings="false" category="System" priority="true">
|
||||
<description>Used by gcs to handle object persistence to flash memory</description>
|
||||
<field name="Operation" units="" type="enum" elements="1" options="NOP,Load,Save,Delete,FullErase,Completed,Error"/>
|
||||
<field name="Selection" units="" type="enum" elements="1" options="SingleObject,AllSettings,AllMetaObjects,AllObjects"/>
|
||||
<field name="ObjectID" units="" type="uint32" elements="1"/>
|
||||
|
@ -1,5 +1,5 @@
|
||||
<xml>
|
||||
<object name="OPLinkStatus" singleinstance="true" settings="false" category="System">
|
||||
<object name="OPLinkStatus" singleinstance="true" settings="false" category="System" priority="true">
|
||||
<description>OPLink device status.</description>
|
||||
<field name="Description" units="" type="uint8" elements="40"/>
|
||||
<field name="CPUSerial" units="hex" type="uint8" elements="12" />
|
||||
|
@ -1,5 +1,5 @@
|
||||
<xml>
|
||||
<object name="SystemAlarms" singleinstance="true" settings="false" category="System">
|
||||
<object name="SystemAlarms" singleinstance="true" settings="false" category="System" priority="true">
|
||||
<description>Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. Some modules may have a module defined Status and Substatus fields that details its condition.</description>
|
||||
<field name="Alarm" units="" type="enum" options="Uninitialised,OK,Warning,Error,Critical" defaultvalue="Uninitialised">
|
||||
<elementnames>
|
||||
|
@ -24,7 +24,6 @@
|
||||
<elementname>FlightPlan</elementname>
|
||||
<!-- telemetry -->
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<!-- com -->
|
||||
<elementname>RadioRx</elementname>
|
||||
@ -111,8 +110,8 @@
|
||||
</elementnames>
|
||||
</field>
|
||||
<access gcs="readonly" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="periodic" period="10000"/>
|
||||
<telemetrygcs acked="false" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="false" updatemode="periodic" period="10000"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
</xml>
|
||||
|
Loading…
x
Reference in New Issue
Block a user