mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Merge remote-tracking branch 'origin/amorale/OP-1212_telemetry_prio_queue' into next
This commit is contained in:
commit
3cf1662bc8
@ -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;
|
||||
}
|
||||
|
@ -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>
|
||||
|
@ -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>
|
||||
|
@ -23,7 +23,6 @@
|
||||
<elementname>FlightPlan</elementname>
|
||||
<!-- telemetry -->
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<!-- com -->
|
||||
<elementname>RadioRx</elementname>
|
||||
|
Loading…
Reference in New Issue
Block a user