mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-18 03:52:11 +01:00
Merge branch 'next' into theothercliff/OP-1259_Cruise_Control_Tweaks
Conflicts: flight/pios/stm32f10x/inc/usb_conf.h
This commit is contained in:
commit
f7a2e31809
5
Makefile
5
Makefile
@ -723,7 +723,7 @@ $(OPFW_RESOURCE): $(FW_TARGETS)
|
||||
|
||||
# If opfw_resource or all firmware are requested, GCS should depend on the resource
|
||||
ifneq ($(strip $(filter opfw_resource all all_fw all_flight,$(MAKECMDGOALS))),)
|
||||
$(eval openpilotgcs: $(OPFW_RESOURCE))
|
||||
$(eval openpilotgcs_qmake: $(OPFW_RESOURCE))
|
||||
endif
|
||||
|
||||
# Packaging targets: package, clean_package
|
||||
@ -878,9 +878,8 @@ help:
|
||||
@$(ECHO) " [Tool Installers]"
|
||||
@$(ECHO) " arm_sdk_install - Install the GNU ARM gcc toolchain"
|
||||
@$(ECHO) " qt_sdk_install - Install the QT development tools"
|
||||
@$(ECHO) " mingw_install - Install the MinGW toolchain (Windows only)"
|
||||
@$(ECHO) " python_install - Install the Python interpreter (Windows only)"
|
||||
@$(ECHO) " nsis_install - Install the NSIS Unicode (Windows only)"
|
||||
@$(ECHO) " sdl_install - Install the SDL library (Windows only)"
|
||||
@$(ECHO) " openssl_install - Install the OpenSSL libraries (Windows only)"
|
||||
@$(ECHO) " uncrustify_install - Install the Uncrustify source code beautifier"
|
||||
@$(ECHO) " doxygen_install - Install the Doxygen documentation generator"
|
||||
|
@ -32,11 +32,17 @@
|
||||
#include "inc/alarms.h"
|
||||
|
||||
// Private constants
|
||||
#ifndef PIOS_ALARM_GRACETIME
|
||||
// alarm cannot be turned off for at least 1000 milliseconds
|
||||
// to prevent event system overload through flapping alarms
|
||||
#define PIOS_ALARM_GRACETIME 1000
|
||||
#endif // PIOS_ALARM_GRACETIME
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static xSemaphoreHandle lock;
|
||||
static volatile uint16_t lastAlarmChange[SYSTEMALARMS_ALARM_NUMELEM] = { 0 }; // this deliberately overflows every 2^16 milliseconds to save memory
|
||||
|
||||
// Private functions
|
||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
||||
@ -63,7 +69,7 @@ int32_t AlarmsInitialize(void)
|
||||
*/
|
||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
||||
{
|
||||
SystemAlarmsData alarms;
|
||||
SystemAlarmsAlarmData alarms;
|
||||
|
||||
// Check that this is a valid alarm
|
||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) {
|
||||
@ -74,10 +80,14 @@ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
|
||||
// Read alarm and update its severity only if it was changed
|
||||
SystemAlarmsGet(&alarms);
|
||||
if (cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[alarm] != severity) {
|
||||
cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[alarm] = severity;
|
||||
SystemAlarmsSet(&alarms);
|
||||
SystemAlarmsAlarmGet(&alarms);
|
||||
uint16_t flightTime = (uint16_t)xTaskGetTickCount() * (uint16_t)portTICK_RATE_MS; // this deliberately overflows every 2^16 milliseconds to save memory
|
||||
if ((flightTime - lastAlarmChange[alarm] > PIOS_ALARM_GRACETIME &&
|
||||
cast_struct_to_array(alarms, alarms.Actuator)[alarm] != severity)
|
||||
|| cast_struct_to_array(alarms, alarms.Actuator)[alarm] < severity) {
|
||||
cast_struct_to_array(alarms, alarms.Actuator)[alarm] = severity;
|
||||
lastAlarmChange[alarm] = flightTime;
|
||||
SystemAlarmsAlarmSet(&alarms);
|
||||
}
|
||||
|
||||
// Release lock
|
||||
@ -110,10 +120,14 @@ int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm,
|
||||
|
||||
// Read alarm and update its severity only if it was changed
|
||||
SystemAlarmsGet(&alarms);
|
||||
if (cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[alarm] != severity) {
|
||||
uint16_t flightTime = (uint16_t)xTaskGetTickCount() * (uint16_t)portTICK_RATE_MS; // this deliberately overflows every 2^16 milliseconds to save memory
|
||||
if ((flightTime - lastAlarmChange[alarm] > PIOS_ALARM_GRACETIME &&
|
||||
cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[alarm] != severity)
|
||||
|| cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[alarm] < severity) {
|
||||
cast_struct_to_array(alarms.ExtendedAlarmStatus, alarms.ExtendedAlarmStatus.BootFault)[alarm] = status;
|
||||
cast_struct_to_array(alarms.ExtendedAlarmSubStatus, alarms.ExtendedAlarmStatus.BootFault)[alarm] = subStatus;
|
||||
cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[alarm] = severity;
|
||||
lastAlarmChange[alarm] = flightTime;
|
||||
SystemAlarmsSet(&alarms);
|
||||
}
|
||||
|
||||
@ -129,7 +143,7 @@ int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm,
|
||||
*/
|
||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
||||
{
|
||||
SystemAlarmsData alarms;
|
||||
SystemAlarmsAlarmData alarms;
|
||||
|
||||
// Check that this is a valid alarm
|
||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) {
|
||||
@ -137,8 +151,8 @@ SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
||||
}
|
||||
|
||||
// Read alarm
|
||||
SystemAlarmsGet(&alarms);
|
||||
return cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[alarm];
|
||||
SystemAlarmsAlarmGet(&alarms);
|
||||
return cast_struct_to_array(alarms, alarms.Actuator)[alarm];
|
||||
}
|
||||
|
||||
/**
|
||||
@ -220,17 +234,17 @@ int32_t AlarmsHasCritical()
|
||||
*/
|
||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
||||
{
|
||||
SystemAlarmsData alarms;
|
||||
SystemAlarmsAlarmData alarms;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
|
||||
// Read alarms
|
||||
SystemAlarmsGet(&alarms);
|
||||
SystemAlarmsAlarmGet(&alarms);
|
||||
|
||||
// Go through alarms and check if any are of the given severity or higher
|
||||
for (uint32_t n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) {
|
||||
if (cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[n] >= severity) {
|
||||
if (cast_struct_to_array(alarms, alarms.Actuator)[n] >= severity) {
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
return 1;
|
||||
}
|
||||
|
@ -41,9 +41,11 @@
|
||||
#include "hwsettings.h"
|
||||
#include "airspeedsettings.h"
|
||||
#include "airspeedsensor.h" // object that will be updated by the module
|
||||
#include "baro_airspeed_ms4525do.h"
|
||||
#include "baro_airspeed_etasv3.h"
|
||||
#include "baro_airspeed_mpxv.h"
|
||||
#include "gps_airspeed.h"
|
||||
#include "airspeedalarm.h"
|
||||
#include "taskinfo.h"
|
||||
|
||||
// Private constants
|
||||
@ -59,7 +61,7 @@
|
||||
static xTaskHandle taskHandle;
|
||||
static bool airspeedEnabled = false;
|
||||
static AirspeedSettingsData airspeedSettings;
|
||||
|
||||
static AirspeedSettingsAirspeedSensorTypeOptions lastAirspeedSensorType = 0;
|
||||
static int8_t airspeedADCPin = -1;
|
||||
|
||||
|
||||
@ -118,6 +120,8 @@ int32_t AirspeedInitialize()
|
||||
}
|
||||
}
|
||||
|
||||
lastAirspeedSensorType = airspeedSettings.AirspeedSensorType;
|
||||
|
||||
AirspeedSensorInitialize();
|
||||
AirspeedSettingsInitialize();
|
||||
|
||||
@ -144,6 +148,7 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
|
||||
|
||||
airspeedData.SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
|
||||
|
||||
// Main task loop
|
||||
portTickType lastSysTime = xTaskGetTickCount();
|
||||
while (1) {
|
||||
@ -152,6 +157,12 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
|
||||
// Update the airspeed object
|
||||
AirspeedSensorGet(&airspeedData);
|
||||
|
||||
// if sensor type changed reset Airspeed alarm
|
||||
if (airspeedSettings.AirspeedSensorType != lastAirspeedSensorType) {
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_DEFAULT);
|
||||
lastAirspeedSensorType = airspeedSettings.AirspeedSensorType;
|
||||
}
|
||||
|
||||
switch (airspeedSettings.AirspeedSensorType) {
|
||||
#if defined(PIOS_INCLUDE_MPXV)
|
||||
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_DIYDRONESMPXV7002:
|
||||
@ -165,12 +176,20 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
|
||||
// Eagletree Airspeed v3
|
||||
baro_airspeedGetETASV3(&airspeedData, &airspeedSettings);
|
||||
break;
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_MS4525DO)
|
||||
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_PIXHAWKAIRSPEEDMS4525DO:
|
||||
// PixHawk Airpeed based on MS4525DO
|
||||
baro_airspeedGetMS4525DO(&airspeedData, &airspeedSettings);
|
||||
break;
|
||||
#endif
|
||||
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_GROUNDSPEEDBASEDWINDESTIMATION:
|
||||
gps_airspeedGet(&airspeedData, &airspeedSettings);
|
||||
break;
|
||||
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_NONE:
|
||||
default:
|
||||
airspeedData.SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
break;
|
||||
}
|
||||
|
||||
// Set the UAVO
|
||||
|
65
flight/modules/Airspeed/airspeedalarm.c
Normal file
65
flight/modules/Airspeed/airspeedalarm.c
Normal file
@ -0,0 +1,65 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup AirspeedModule Airspeed Module
|
||||
* @brief Handle locally airspeed alarms issue changes to PIOS only when necessary
|
||||
* @{
|
||||
*
|
||||
* @file airspeedalarm.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief Airspeed module
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/**
|
||||
* Output object: none
|
||||
*
|
||||
* Handle locally airspeed alarms issue changes to PIOS only when necessary
|
||||
*
|
||||
*/
|
||||
|
||||
#include "airspeedalarm.h"
|
||||
|
||||
// local variable
|
||||
|
||||
static SystemAlarmsAlarmOptions severitySet = SYSTEMALARMS_ALARM_UNINITIALISED;
|
||||
|
||||
// functions
|
||||
|
||||
/**
|
||||
* Handle airspeed alarms and isuue an Alarm to PIOS only if necessary
|
||||
*/
|
||||
bool AirspeedAlarm(SystemAlarmsAlarmOptions severity)
|
||||
{
|
||||
if (severity == severitySet) {
|
||||
return false;
|
||||
}
|
||||
|
||||
severitySet = severity;
|
||||
|
||||
return AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, severity) == 0;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -40,6 +40,7 @@
|
||||
#include "hwsettings.h"
|
||||
#include "airspeedsettings.h"
|
||||
#include "airspeedsensor.h" // object that will be updated by the module
|
||||
#include "airspeedalarm.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_ETASV3)
|
||||
|
||||
@ -64,11 +65,13 @@ void baro_airspeedGetETASV3(AirspeedSensorData *airspeedSensor, AirspeedSettings
|
||||
if (airspeedSensor->SensorValue == (uint16_t)-1) {
|
||||
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
airspeedSensor->CalibratedAirspeed = 0;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_ERROR);
|
||||
return;
|
||||
}
|
||||
|
||||
// only calibrate if no stored calibration is available
|
||||
if (!airspeedSettings->ZeroPoint) {
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_WARNING);
|
||||
// Calibrate sensor by averaging zero point value
|
||||
if (calibrationCount <= CALIBRATION_IDLE_MS / airspeedSettings->SamplePeriod) {
|
||||
calibrationCount++;
|
||||
@ -93,6 +96,7 @@ void baro_airspeedGetETASV3(AirspeedSensorData *airspeedSensor, AirspeedSettings
|
||||
// Compute airspeed
|
||||
airspeedSensor->CalibratedAirspeed = airspeedSettings->Scale * sqrtf((float)abs(airspeedSensor->SensorValue - airspeedSettings->ZeroPoint));
|
||||
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_OK);
|
||||
}
|
||||
|
||||
|
||||
|
@ -40,6 +40,7 @@
|
||||
#include "hwsettings.h"
|
||||
#include "airspeedsettings.h"
|
||||
#include "airspeedsensor.h" // object that will be updated by the module
|
||||
#include "airspeedalarm.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_MPXV)
|
||||
|
||||
@ -63,7 +64,7 @@ void baro_airspeedGetMPXV(AirspeedSensorData *airspeedSensor, AirspeedSettingsDa
|
||||
// Ensure that the ADC pin is properly configured
|
||||
if (airspeedADCPin < 0) {
|
||||
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_ERROR);
|
||||
return;
|
||||
}
|
||||
if (sensor.type == PIOS_MPXV_UNKNOWN) {
|
||||
@ -76,6 +77,7 @@ void baro_airspeedGetMPXV(AirspeedSensorData *airspeedSensor, AirspeedSettingsDa
|
||||
break;
|
||||
default:
|
||||
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_ERROR);
|
||||
return;
|
||||
}
|
||||
}
|
||||
@ -83,6 +85,7 @@ void baro_airspeedGetMPXV(AirspeedSensorData *airspeedSensor, AirspeedSettingsDa
|
||||
airspeedSensor->SensorValue = PIOS_MPXV_Measure(&sensor);
|
||||
|
||||
if (!airspeedSettings->ZeroPoint) {
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_WARNING);
|
||||
// Calibrate sensor by averaging zero point value
|
||||
if (calibrationCount < CALIBRATION_IDLE_MS / airspeedSettings->SamplePeriod) { // First let sensor warm up and stabilize.
|
||||
calibrationCount++;
|
||||
@ -107,6 +110,7 @@ void baro_airspeedGetMPXV(AirspeedSensorData *airspeedSensor, AirspeedSettingsDa
|
||||
|
||||
airspeedSensor->CalibratedAirspeed = PIOS_MPXV_CalcAirspeed(&sensor, airspeedSensor->SensorValue) * (alpha) + airspeedSensor->CalibratedAirspeed * (1.0f - alpha);
|
||||
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_OK);
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_MPXV) */
|
||||
|
140
flight/modules/Airspeed/baro_airspeed_ms4525do.c
Normal file
140
flight/modules/Airspeed/baro_airspeed_ms4525do.c
Normal file
@ -0,0 +1,140 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup AirspeedModule Airspeed Module
|
||||
* @brief Communicate with airspeed sensors and return values
|
||||
* @{
|
||||
*
|
||||
* @file baro_airspeed_ms4525do.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief Airspeed module, handles temperature and pressure readings from MS4525DO
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/**
|
||||
* Output object: BaroAirspeed
|
||||
*
|
||||
* This module will periodically update the value of the BaroAirspeed object.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "hwsettings.h"
|
||||
#include "airspeedsettings.h"
|
||||
#include "airspeedsensor.h" // object that will be updated by the module
|
||||
#include "airspeedalarm.h"
|
||||
#include "taskinfo.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_MS4525DO)
|
||||
|
||||
#define CALIBRATION_IDLE_MS 0 // Time to wait before calibrating, in [ms]
|
||||
#define CALIBRATION_COUNT_MS 4000 // Time to spend calibrating, in [ms]
|
||||
#define FILTER_SHIFT 5 // Barry Dorr filter parameter k
|
||||
|
||||
#define P0 101325.0f // standard pressure
|
||||
#define CCEXPONENT 0.2857142857f // exponent of compressibility correction 2/7
|
||||
#define CASFACTOR 760.8802669f // sqrt(5) * speed of sound at standard
|
||||
#define TASFACTOR 0.05891022589f // 1/sqrt(T0)
|
||||
|
||||
// Private types
|
||||
|
||||
// Private functions definitions
|
||||
|
||||
// Private variables
|
||||
static uint16_t calibrationCount = 0;
|
||||
static uint32_t filter_reg = 0; // Barry Dorr filter register
|
||||
|
||||
void baro_airspeedGetMS4525DO(AirspeedSensorData *airspeedSensor, AirspeedSettingsData *airspeedSettings)
|
||||
{
|
||||
uint16_t values[2];
|
||||
|
||||
// Read sensor
|
||||
int8_t retVal = PIOS_MS4525DO_Read(values);
|
||||
|
||||
// check for errors
|
||||
if (retVal != 0) {
|
||||
airspeedSensor->SensorValue = -1;
|
||||
airspeedSensor->SensorValueTemperature = -1;
|
||||
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
airspeedSensor->CalibratedAirspeed = 0;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_ERROR);
|
||||
return;
|
||||
}
|
||||
|
||||
airspeedSensor->SensorValue = values[0];
|
||||
airspeedSensor->SensorValueTemperature = values[1];
|
||||
|
||||
// only calibrate if no stored calibration is available
|
||||
if (!airspeedSettings->ZeroPoint) {
|
||||
// Calibrate sensor by averaging zero point value
|
||||
if (calibrationCount <= CALIBRATION_IDLE_MS / airspeedSettings->SamplePeriod) {
|
||||
calibrationCount++;
|
||||
filter_reg = (airspeedSensor->SensorValue << FILTER_SHIFT);
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_WARNING);
|
||||
return;
|
||||
} else if (calibrationCount <= (CALIBRATION_IDLE_MS + CALIBRATION_COUNT_MS) / airspeedSettings->SamplePeriod) {
|
||||
calibrationCount++;
|
||||
// update filter register
|
||||
filter_reg = filter_reg - (filter_reg >> FILTER_SHIFT) + airspeedSensor->SensorValue;
|
||||
|
||||
if (calibrationCount > (CALIBRATION_IDLE_MS + CALIBRATION_COUNT_MS) / airspeedSettings->SamplePeriod) {
|
||||
// Scale output for unity gain.
|
||||
airspeedSettings->ZeroPoint = (uint16_t)(filter_reg >> FILTER_SHIFT);
|
||||
|
||||
AirspeedSettingsZeroPointSet(&airspeedSettings->ZeroPoint);
|
||||
calibrationCount = 0;
|
||||
}
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_WARNING);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/* Compute airspeed
|
||||
assume sensor is A Type and has a range of 1 psi, i.e. Pmin=-1.0 psi and Pmax=1.0 psi
|
||||
Datasheet pressure: output = 0.8 * 16383 / (Pmax-Pmin) * (P - Pmin) + 0.1 * 16383
|
||||
Inversion: P = (10*output - 81915)/65532 in psi
|
||||
1 psi = 6894,757293168 Pa
|
||||
P = (10*output - 81915)*0.1052120688 in Pa
|
||||
Datasheet temperature: output = (T+50)*2047 / 200
|
||||
Inversion: T = (200*out - 102350)/2047 in C
|
||||
T = (200*out - 102350)/2047 + 273.15 in K
|
||||
*/
|
||||
const float dP = (10 * (int32_t)(airspeedSensor->SensorValue - airspeedSettings->ZeroPoint)) * 0.1052120688f;
|
||||
const float T = (float)(200 * (int32_t)airspeedSensor->SensorValueTemperature - 102350) / 2047 + 273.15f;
|
||||
|
||||
airspeedSensor->DifferentialPressure = dP;
|
||||
airspeedSensor->Temperature = T;
|
||||
// CAS = Csound * sqrt( 5 *( (dP/P0 +1)^(2/7) - 1) )
|
||||
// TAS = Csound * sqrt( 5 T/T0 *( (dP/P0 +1)^(2/7) - 1) )
|
||||
// where Csound = 340.276 m/s at standard condition T0=288.15 K and P0 = 101315 Pa
|
||||
airspeedSensor->CalibratedAirspeed = airspeedSettings->Scale * CASFACTOR * sqrtf(powf(fabsf(dP) / P0 + 1.0f, CCEXPONENT) - 1.0f);
|
||||
airspeedSensor->TrueAirspeed = airspeedSensor->CalibratedAirspeed * TASFACTOR * sqrtf(T);
|
||||
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE;
|
||||
// everything is fine so set ALARM_OK
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_OK);
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_MS4525DO) */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -37,6 +37,7 @@
|
||||
#include "airspeedsettings.h"
|
||||
#include "gps_airspeed.h"
|
||||
#include "CoordinateConversions.h"
|
||||
#include "airspeedalarm.h"
|
||||
#include <pios_math.h>
|
||||
|
||||
|
||||
@ -127,6 +128,7 @@ void gps_airspeedGet(AirspeedSensorData *airspeedData, AirspeedSettingsData *air
|
||||
if (gpsVelData.North * gpsVelData.North + gpsVelData.East * gpsVelData.East + gpsVelData.Down * gpsVelData.Down < 1.0f) {
|
||||
airspeedData->CalibratedAirspeed = 0;
|
||||
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_ERROR);
|
||||
return; // do not calculate if gps velocity is insufficient...
|
||||
}
|
||||
|
||||
@ -141,11 +143,13 @@ void gps_airspeedGet(AirspeedSensorData *airspeedData, AirspeedSettingsData *air
|
||||
if (!IS_REAL(airspeedData->CalibratedAirspeed)) {
|
||||
airspeedData->CalibratedAirspeed = 0;
|
||||
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_ERROR);
|
||||
} else {
|
||||
// need a low pass filter to filter out spikes in non coordinated maneuvers
|
||||
airspeedData->CalibratedAirspeed = (1.0f - airspeedSettings->GroundSpeedBasedEstimationLowPassAlpha) * gps->oldAirspeed + airspeedSettings->GroundSpeedBasedEstimationLowPassAlpha * airspeed;
|
||||
gps->oldAirspeed = airspeedData->CalibratedAirspeed;
|
||||
airspeedData->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_TRUE;
|
||||
AirspeedAlarm(SYSTEMALARMS_ALARM_OK);
|
||||
}
|
||||
|
||||
// Save old variables for next pass
|
||||
|
45
flight/modules/Airspeed/inc/airspeedalarm.h
Normal file
45
flight/modules/Airspeed/inc/airspeedalarm.h
Normal file
@ -0,0 +1,45 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup AirspeedModule Airspeed Module
|
||||
* @brief Handle locally airspeed alarms issue changes to PIOS only when necessary
|
||||
* @{
|
||||
*
|
||||
* @file airspeedalarm.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief Airspeed module, reads temperature and pressure from MS4525DO
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef AIRSPEEDALARM_H
|
||||
#define AIRSPEEDALARM_H
|
||||
|
||||
#include <openpilot.h>
|
||||
#include "alarms.h"
|
||||
|
||||
|
||||
bool AirspeedAlarm(SystemAlarmsAlarmOptions severity);
|
||||
|
||||
#endif // AIRSPEEDALARM_H
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
43
flight/modules/Airspeed/inc/baro_airspeed_ms4525do.h
Normal file
43
flight/modules/Airspeed/inc/baro_airspeed_ms4525do.h
Normal file
@ -0,0 +1,43 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup AirspeedModule Airspeed Module
|
||||
* @brief Calculate airspeed from measurements of differential pressure from a MS4525DO (PixHawk airspeed sensor)
|
||||
* @{
|
||||
*
|
||||
* @file baro_airspeed_mas4525do.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief Airspeed module, reads temperature and pressure from MS4525DO
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef BARO_AIRSPEED_MS4525DO_H
|
||||
#define BARO_AIRSPEED_MS4525DO_H
|
||||
#if defined(PIOS_INCLUDE_MS4525DO)
|
||||
|
||||
void baro_airspeedGetMS4525DO(AirspeedSensorData *airspeedSensor, AirspeedSettingsData *airspeedSettings);
|
||||
|
||||
#endif /* PIOS_INCLUDE_MS4525DO */
|
||||
#endif // BARO_AIRSPEED_MS4525DO_H
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -278,7 +278,7 @@ static void AttitudeTask(__attribute__((unused)) void *parameters)
|
||||
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARY:
|
||||
ret_val = updateAttitudeComplementary(first_run);
|
||||
break;
|
||||
case REVOSETTINGS_FUSIONALGORITHM_INS13OUTDOOR:
|
||||
case REVOSETTINGS_FUSIONALGORITHM_INS13GPSOUTDOOR:
|
||||
ret_val = updateAttitudeINSGPS(first_run, true);
|
||||
break;
|
||||
case REVOSETTINGS_FUSIONALGORITHM_INS13INDOOR:
|
||||
@ -650,7 +650,7 @@ static int32_t updateAttitudeComplementary(bool first_run)
|
||||
if (airspeedSensor.SensorConnected == AIRSPEEDSENSOR_SENSORCONNECTED_TRUE) {
|
||||
// we have airspeed available
|
||||
airspeed.CalibratedAirspeed = airspeedSensor.CalibratedAirspeed;
|
||||
airspeed.TrueAirspeed = airspeed.CalibratedAirspeed * IAS2TAS(homeLocation.Altitude - positionState.Down);
|
||||
airspeed.TrueAirspeed = (airspeedSensor.TrueAirspeed < 0.f) ? airspeed.CalibratedAirspeed *IAS2TAS(homeLocation.Altitude - positionState.Down) : airspeedSensor.TrueAirspeed;
|
||||
AirspeedStateSet(&airspeed);
|
||||
}
|
||||
}
|
||||
@ -1072,13 +1072,23 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode)
|
||||
vel[2] = gpsVelData.Down;
|
||||
}
|
||||
|
||||
// Copy the position into the UAVO
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
positionState.North = Nav.Pos[0];
|
||||
positionState.East = Nav.Pos[1];
|
||||
positionState.Down = Nav.Pos[2];
|
||||
PositionStateSet(&positionState);
|
||||
|
||||
// airspeed correction needs current positionState
|
||||
if (airspeed_updated) {
|
||||
// we have airspeed available
|
||||
AirspeedStateData airspeed;
|
||||
AirspeedStateGet(&airspeed);
|
||||
|
||||
airspeed.CalibratedAirspeed = airspeedData.CalibratedAirspeed;
|
||||
airspeed.TrueAirspeed = airspeed.CalibratedAirspeed * IAS2TAS(homeLocation.Altitude - Nav.Pos[2]);
|
||||
airspeed.TrueAirspeed = (airspeedData.TrueAirspeed < 0.f) ? airspeed.CalibratedAirspeed *IAS2TAS(homeLocation.Altitude - positionState.Down) : airspeedData.TrueAirspeed;
|
||||
|
||||
AirspeedStateSet(&airspeed);
|
||||
|
||||
if (!gps_vel_updated && !gps_updated) {
|
||||
@ -1107,14 +1117,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode)
|
||||
INSCorrection(&magData.x, NED, vel, (baroData.Altitude + baroOffset), sensors);
|
||||
}
|
||||
|
||||
// Copy the position and velocity into the UAVO
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
positionState.North = Nav.Pos[0];
|
||||
positionState.East = Nav.Pos[1];
|
||||
positionState.Down = Nav.Pos[2];
|
||||
PositionStateSet(&positionState);
|
||||
|
||||
// Copy the velocity into the UAVO
|
||||
VelocityStateData velocityState;
|
||||
VelocityStateGet(&velocityState);
|
||||
velocityState.North = Nav.Vel[0];
|
||||
|
@ -47,6 +47,7 @@
|
||||
|
||||
#include "openpilot.h"
|
||||
|
||||
#include "flightstatus.h"
|
||||
#include "flightbatterystate.h"
|
||||
#include "flightbatterysettings.h"
|
||||
#include "hwsettings.h"
|
||||
@ -69,6 +70,7 @@ static int8_t currentADCPin = -1; // ADC pin for current
|
||||
|
||||
// Private functions
|
||||
static void onTimer(UAVObjEvent *ev);
|
||||
static int8_t GetNbCells(const FlightBatterySettingsData *batterySettings, FlightBatteryStateData *flightBatteryData);
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
@ -113,6 +115,8 @@ int32_t BatteryInitialize(void)
|
||||
FlightBatteryStateInitialize();
|
||||
FlightBatterySettingsInitialize();
|
||||
|
||||
// FlightBatterySettingsConnectCallback(FlightBatterySettingsUpdatedCb);
|
||||
|
||||
static UAVObjEvent ev;
|
||||
|
||||
memset(&ev, 0, sizeof(UAVObjEvent));
|
||||
@ -125,10 +129,11 @@ int32_t BatteryInitialize(void)
|
||||
MODULE_INITCALL(BatteryInitialize, 0);
|
||||
static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
static FlightBatteryStateData flightBatteryData;
|
||||
static FlightBatterySettingsData batterySettings;
|
||||
static FlightBatteryStateData flightBatteryData;
|
||||
|
||||
FlightBatterySettingsGet(&batterySettings);
|
||||
FlightBatteryStateGet(&flightBatteryData);
|
||||
|
||||
const float dT = SAMPLE_PERIOD_MS / 1000.0f;
|
||||
float energyRemaining;
|
||||
@ -140,7 +145,11 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
|
||||
flightBatteryData.Voltage = 0; // Dummy placeholder value. This is in case we get another source of battery current which is not from the ADC
|
||||
}
|
||||
|
||||
if (currentADCPin >= 0) {
|
||||
// voltage available: get the number of cells if possible, desired and not armed
|
||||
GetNbCells(&batterySettings, &flightBatteryData);
|
||||
|
||||
// ad a plausibility check: zero voltage => zero current
|
||||
if (currentADCPin >= 0 && flightBatteryData.Voltage > 0.f) {
|
||||
flightBatteryData.Current = (PIOS_ADC_PinGetVolt(currentADCPin) - batterySettings.SensorCalibrations.CurrentZero) * batterySettings.SensorCalibrations.CurrentFactor; // in Amps
|
||||
if (flightBatteryData.Current > flightBatteryData.PeakCurrent) {
|
||||
flightBatteryData.PeakCurrent = flightBatteryData.Current; // in Amps
|
||||
@ -149,7 +158,11 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
|
||||
flightBatteryData.Current = -0; // Dummy placeholder value. This is in case we get another source of battery current which is not from the ADC
|
||||
}
|
||||
|
||||
flightBatteryData.ConsumedEnergy += (flightBatteryData.Current * dT * 1000.0f / 3600.0f); // in mAh
|
||||
// For safety reasons consider only positive currents in energy comsumption, i.e. no charging up.
|
||||
// necesary when sensor are not perfectly calibrated
|
||||
if (flightBatteryData.Current > 0) {
|
||||
flightBatteryData.ConsumedEnergy += (flightBatteryData.Current * dT * 1000.0f / 3600.0f); // in mAh
|
||||
}
|
||||
|
||||
// Apply a 2 second rise time low-pass filter to average the current
|
||||
float alpha = 1.0f - dT / (dT + 2.0f);
|
||||
@ -184,9 +197,9 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
|
||||
|
||||
// FIXME: should make the battery voltage detection dependent on battery type.
|
||||
/*Not so sure. Some users will want to run their batteries harder than others, so it should be the user's choice. [KDS]*/
|
||||
if (flightBatteryData.Voltage < batterySettings.CellVoltageThresholds.Alarm * batterySettings.NbCells) {
|
||||
if (flightBatteryData.Voltage < batterySettings.CellVoltageThresholds.Alarm * flightBatteryData.NbCells) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else if (flightBatteryData.Voltage < batterySettings.CellVoltageThresholds.Warning * batterySettings.NbCells) {
|
||||
} else if (flightBatteryData.Voltage < batterySettings.CellVoltageThresholds.Warning * flightBatteryData.NbCells) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_WARNING);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_BATTERY);
|
||||
@ -196,6 +209,71 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
|
||||
FlightBatteryStateSet(&flightBatteryData);
|
||||
}
|
||||
|
||||
|
||||
static int8_t GetNbCells(const FlightBatterySettingsData *batterySettings, FlightBatteryStateData *flightBatteryData)
|
||||
{
|
||||
// get flight status to check for armed
|
||||
uint8_t armed = 0;
|
||||
|
||||
FlightStatusArmedGet(&armed);
|
||||
|
||||
|
||||
// check only if not armed
|
||||
if (armed == FLIGHTSTATUS_ARMED_ARMED) {
|
||||
return -2;
|
||||
}
|
||||
|
||||
// prescribed number of cells?
|
||||
if (batterySettings->NbCells != 0) {
|
||||
flightBatteryData->NbCells = batterySettings->NbCells;
|
||||
flightBatteryData->NbCellsAutodetected = 0;
|
||||
return -3;
|
||||
}
|
||||
|
||||
// plausibility check
|
||||
if (flightBatteryData->Voltage <= 0.5f) {
|
||||
// cannot detect number of cells
|
||||
flightBatteryData->NbCellsAutodetected = 0;
|
||||
return -1;
|
||||
}
|
||||
|
||||
float voltageMin = 0.f, voltageMax = 0.f;
|
||||
|
||||
// Cell type specific values
|
||||
// TODO: could be implemented as constant arrays indexed by cellType
|
||||
// or could be part of the UAVObject definition
|
||||
switch (batterySettings->Type) {
|
||||
case FLIGHTBATTERYSETTINGS_TYPE_LIPO:
|
||||
case FLIGHTBATTERYSETTINGS_TYPE_LICO:
|
||||
voltageMin = 3.6f;
|
||||
voltageMax = 4.2f;
|
||||
break;
|
||||
case FLIGHTBATTERYSETTINGS_TYPE_A123:
|
||||
voltageMin = 2.01f;
|
||||
voltageMax = 3.59f;
|
||||
break;
|
||||
case FLIGHTBATTERYSETTINGS_TYPE_LIFESO4:
|
||||
default:
|
||||
flightBatteryData->NbCellsAutodetected = 0;
|
||||
return -1;
|
||||
}
|
||||
|
||||
// uniquely measurable under any condition iff n * voltageMax < (n+1) * voltageMin
|
||||
// or n < voltageMin / (voltageMax-voltageMin)
|
||||
// weaken condition by setting n <= voltageMin / (voltageMax-voltageMin) and
|
||||
// checking for v <= voltageMin * voltageMax / (voltageMax-voltageMin)
|
||||
if (flightBatteryData->Voltage > voltageMin * voltageMax / (voltageMax - voltageMin)) {
|
||||
flightBatteryData->NbCellsAutodetected = 0;
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
flightBatteryData->NbCells = (int8_t)(flightBatteryData->Voltage / voltageMin);
|
||||
flightBatteryData->NbCellsAutodetected = 1;
|
||||
|
||||
return flightBatteryData->NbCells;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
@ -503,7 +503,7 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
|
||||
// Error condition: plane cannot hold altitude at current speed.
|
||||
fixedwingpathfollowerStatus.Errors.Lowpower = 0;
|
||||
if (powerCommand >= fixedwingpathfollowerSettings.ThrustLimit.Max && // thrust at maximum
|
||||
if (fixedwingpathfollowerSettings.ThrustLimit.Neutral + powerCommand >= fixedwingpathfollowerSettings.ThrustLimit.Max && // thrust at maximum
|
||||
velocityState.Down > 0 && // we ARE going down
|
||||
descentspeedDesired < 0 && // we WANT to go up
|
||||
airspeedError > 0 && // we are too slow already
|
||||
@ -513,7 +513,7 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
}
|
||||
// Error condition: plane keeps climbing despite minimum thrust (opposite of above)
|
||||
fixedwingpathfollowerStatus.Errors.Highpower = 0;
|
||||
if (powerCommand >= fixedwingpathfollowerSettings.ThrustLimit.Min && // thrust at minimum
|
||||
if (fixedwingpathfollowerSettings.ThrustLimit.Neutral + powerCommand <= fixedwingpathfollowerSettings.ThrustLimit.Min && // thrust at minimum
|
||||
velocityState.Down < 0 && // we ARE going up
|
||||
descentspeedDesired > 0 && // we WANT to go down
|
||||
airspeedError < 0 && // we are too fast already
|
||||
@ -555,7 +555,7 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
|
||||
// Error condition: high speed dive
|
||||
fixedwingpathfollowerStatus.Errors.Pitchcontrol = 0;
|
||||
if (pitchCommand >= fixedwingpathfollowerSettings.PitchLimit.Max && // pitch demand is full up
|
||||
if (fixedwingpathfollowerSettings.PitchLimit.Neutral + pitchCommand >= fixedwingpathfollowerSettings.PitchLimit.Max && // pitch demand is full up
|
||||
velocityState.Down > 0 && // we ARE going down
|
||||
descentspeedDesired < 0 && // we WANT to go up
|
||||
airspeedError < 0 && // we are too fast already
|
||||
|
@ -254,22 +254,25 @@ void parse_ubx_nav_velned(struct UBX_NAV_VELNED *velned, GPSPositionSensorData *
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
void parse_ubx_nav_timeutc(struct UBX_NAV_TIMEUTC *timeutc)
|
||||
{
|
||||
if (!(timeutc->valid & TIMEUTC_VALIDUTC)) {
|
||||
// Test if time is valid
|
||||
if ((timeutc->valid & TIMEUTC_VALIDTOW) && (timeutc->valid & TIMEUTC_VALIDWKN)) {
|
||||
// Time is valid, set GpsTime
|
||||
GPSTimeData GpsTime;
|
||||
|
||||
GpsTime.Year = timeutc->year;
|
||||
GpsTime.Month = timeutc->month;
|
||||
GpsTime.Day = timeutc->day;
|
||||
GpsTime.Hour = timeutc->hour;
|
||||
GpsTime.Minute = timeutc->min;
|
||||
GpsTime.Second = timeutc->sec;
|
||||
|
||||
GPSTimeSet(&GpsTime);
|
||||
} else {
|
||||
// Time is not valid, nothing to do
|
||||
return;
|
||||
}
|
||||
|
||||
GPSTimeData GpsTime;
|
||||
|
||||
GpsTime.Year = timeutc->year;
|
||||
GpsTime.Month = timeutc->month;
|
||||
GpsTime.Day = timeutc->day;
|
||||
GpsTime.Hour = timeutc->hour;
|
||||
GpsTime.Minute = timeutc->min;
|
||||
GpsTime.Second = timeutc->sec;
|
||||
|
||||
GPSTimeSet(&GpsTime);
|
||||
}
|
||||
#endif
|
||||
#endif /* if !defined(PIOS_GPS_MINIMAL) */
|
||||
|
||||
#if !defined(PIOS_GPS_MINIMAL)
|
||||
void parse_ubx_nav_svinfo(struct UBX_NAV_SVINFO *svinfo)
|
||||
|
@ -57,7 +57,7 @@
|
||||
|
||||
// defined handlers
|
||||
|
||||
static controlHandler handler_MANUAL = {
|
||||
static const controlHandler handler_MANUAL = {
|
||||
.controlChain = {
|
||||
.Stabilization = false,
|
||||
.PathFollower = false,
|
||||
@ -65,7 +65,7 @@ static controlHandler handler_MANUAL = {
|
||||
},
|
||||
.handler = &manualHandler,
|
||||
};
|
||||
static controlHandler handler_STABILIZED = {
|
||||
static const controlHandler handler_STABILIZED = {
|
||||
.controlChain = {
|
||||
.Stabilization = true,
|
||||
.PathFollower = false,
|
||||
@ -74,16 +74,8 @@ static controlHandler handler_STABILIZED = {
|
||||
.handler = &stabilizedHandler,
|
||||
};
|
||||
|
||||
// TODO: move the altitude handling into stabi
|
||||
static controlHandler handler_ALTITUDE = {
|
||||
.controlChain = {
|
||||
.Stabilization = true,
|
||||
.PathFollower = false,
|
||||
.PathPlanner = false,
|
||||
},
|
||||
.handler = &altitudeHandler,
|
||||
};
|
||||
static controlHandler handler_AUTOTUNE = {
|
||||
|
||||
static const controlHandler handler_AUTOTUNE = {
|
||||
.controlChain = {
|
||||
.Stabilization = false,
|
||||
.PathFollower = false,
|
||||
@ -92,7 +84,18 @@ static controlHandler handler_AUTOTUNE = {
|
||||
.handler = NULL,
|
||||
};
|
||||
|
||||
static controlHandler handler_PATHFOLLOWER = {
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
// TODO: move the altitude handling into stabi
|
||||
static const controlHandler handler_ALTITUDE = {
|
||||
.controlChain = {
|
||||
.Stabilization = true,
|
||||
.PathFollower = false,
|
||||
.PathPlanner = false,
|
||||
},
|
||||
.handler = &altitudeHandler,
|
||||
};
|
||||
|
||||
static const controlHandler handler_PATHFOLLOWER = {
|
||||
.controlChain = {
|
||||
.Stabilization = true,
|
||||
.PathFollower = true,
|
||||
@ -101,7 +104,7 @@ static controlHandler handler_PATHFOLLOWER = {
|
||||
.handler = &pathFollowerHandler,
|
||||
};
|
||||
|
||||
static controlHandler handler_PATHPLANNER = {
|
||||
static const controlHandler handler_PATHPLANNER = {
|
||||
.controlChain = {
|
||||
.Stabilization = true,
|
||||
.PathFollower = true,
|
||||
@ -110,7 +113,7 @@ static controlHandler handler_PATHPLANNER = {
|
||||
.handler = &pathPlannerHandler,
|
||||
};
|
||||
|
||||
|
||||
#endif /* ifndef PIOS_EXCLUDE_ADVANCED_FEATURES */
|
||||
// Private variables
|
||||
static DelayedCallbackInfo *callbackHandle;
|
||||
|
||||
@ -192,7 +195,7 @@ static void manualControlTask(void)
|
||||
}
|
||||
|
||||
// Depending on the mode update the Stabilization or Actuator objects
|
||||
controlHandler *handler = &handler_MANUAL;
|
||||
const controlHandler *handler = &handler_MANUAL;
|
||||
switch (newMode) {
|
||||
case FLIGHTSTATUS_FLIGHTMODE_MANUAL:
|
||||
handler = &handler_MANUAL;
|
||||
@ -202,6 +205,7 @@ static void manualControlTask(void)
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
|
||||
handler = &handler_STABILIZED;
|
||||
break;
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
case FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE:
|
||||
@ -216,6 +220,7 @@ static void manualControlTask(void)
|
||||
case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO:
|
||||
handler = &handler_ALTITUDE;
|
||||
break;
|
||||
#endif
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE:
|
||||
handler = &handler_AUTOTUNE;
|
||||
break;
|
||||
|
@ -290,34 +290,33 @@ static void updateRadioComBridgeStats()
|
||||
RadioComBridgeStatsData radioComBridgeStats;
|
||||
|
||||
// Get telemetry stats
|
||||
UAVTalkGetStats(data->telemUAVTalkCon, &telemetryUAVTalkStats);
|
||||
UAVTalkResetStats(data->telemUAVTalkCon);
|
||||
UAVTalkGetStats(data->telemUAVTalkCon, &telemetryUAVTalkStats, true);
|
||||
|
||||
// Get radio stats
|
||||
UAVTalkGetStats(data->radioUAVTalkCon, &radioUAVTalkStats);
|
||||
UAVTalkResetStats(data->radioUAVTalkCon);
|
||||
UAVTalkGetStats(data->radioUAVTalkCon, &radioUAVTalkStats, true);
|
||||
|
||||
// Get stats object data
|
||||
RadioComBridgeStatsGet(&radioComBridgeStats);
|
||||
|
||||
radioComBridgeStats.TelemetryTxRetries = data->telemetryTxRetries;
|
||||
radioComBridgeStats.RadioTxRetries = data->radioTxRetries;
|
||||
|
||||
// Update stats object
|
||||
radioComBridgeStats.TelemetryTxBytes += telemetryUAVTalkStats.txBytes;
|
||||
radioComBridgeStats.TelemetryTxFailures += telemetryUAVTalkStats.txErrors;
|
||||
radioComBridgeStats.TelemetryTxRetries += data->telemetryTxRetries;
|
||||
|
||||
radioComBridgeStats.TelemetryRxBytes += telemetryUAVTalkStats.rxBytes;
|
||||
radioComBridgeStats.TelemetryRxFailures += telemetryUAVTalkStats.rxErrors;
|
||||
radioComBridgeStats.TelemetryRxSyncErrors += telemetryUAVTalkStats.rxSyncErrors;
|
||||
radioComBridgeStats.TelemetryRxCrcErrors += telemetryUAVTalkStats.rxCrcErrors;
|
||||
|
||||
radioComBridgeStats.RadioTxBytes += radioUAVTalkStats.txBytes;
|
||||
radioComBridgeStats.RadioTxFailures += radioUAVTalkStats.txErrors;
|
||||
radioComBridgeStats.RadioTxRetries += data->radioTxRetries;
|
||||
radioComBridgeStats.RadioTxBytes += radioUAVTalkStats.txBytes;
|
||||
radioComBridgeStats.RadioTxFailures += radioUAVTalkStats.txErrors;
|
||||
|
||||
radioComBridgeStats.RadioRxBytes += radioUAVTalkStats.rxBytes;
|
||||
radioComBridgeStats.RadioRxFailures += radioUAVTalkStats.rxErrors;
|
||||
radioComBridgeStats.RadioRxSyncErrors += radioUAVTalkStats.rxSyncErrors;
|
||||
radioComBridgeStats.RadioRxCrcErrors += radioUAVTalkStats.rxCrcErrors;
|
||||
radioComBridgeStats.RadioRxBytes += radioUAVTalkStats.rxBytes;
|
||||
radioComBridgeStats.RadioRxFailures += radioUAVTalkStats.rxErrors;
|
||||
radioComBridgeStats.RadioRxSyncErrors += radioUAVTalkStats.rxSyncErrors;
|
||||
radioComBridgeStats.RadioRxCrcErrors += radioUAVTalkStats.rxCrcErrors;
|
||||
|
||||
// Update stats object data
|
||||
RadioComBridgeStatsSet(&radioComBridgeStats);
|
||||
@ -343,11 +342,11 @@ static void telemetryTxTask(__attribute__((unused)) void *parameters)
|
||||
updateRadioComBridgeStats();
|
||||
}
|
||||
// Send update (with retries)
|
||||
int32_t ret = -1;
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendObject(data->telemUAVTalkCon, ev.obj, ev.instId, 0, RETRY_TIMEOUT_MS) == 0;
|
||||
if (success == -1) {
|
||||
while (retries <= MAX_RETRIES && ret == -1) {
|
||||
ret = UAVTalkSendObject(data->telemUAVTalkCon, ev.obj, ev.instId, 0, RETRY_TIMEOUT_MS);
|
||||
if (ret == -1) {
|
||||
++retries;
|
||||
}
|
||||
}
|
||||
@ -377,11 +376,11 @@ static void radioTxTask(__attribute__((unused)) void *parameters)
|
||||
if (xQueueReceive(data->radioEventQueue, &ev, MAX_PORT_DELAY) == pdTRUE) {
|
||||
if ((ev.event == EV_UPDATED) || (ev.event == EV_UPDATE_REQ)) {
|
||||
// Send update (with retries)
|
||||
int32_t ret = -1;
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendObject(data->radioUAVTalkCon, ev.obj, ev.instId, 0, RETRY_TIMEOUT_MS) == 0;
|
||||
if (success == -1) {
|
||||
while (retries <= MAX_RETRIES && ret == -1) {
|
||||
ret = UAVTalkSendObject(data->radioUAVTalkCon, ev.obj, ev.instId, 0, RETRY_TIMEOUT_MS);
|
||||
if (ret == -1) {
|
||||
++retries;
|
||||
}
|
||||
}
|
||||
@ -414,8 +413,8 @@ static void radioRxTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
} else if (PIOS_COM_TELEMETRY) {
|
||||
// Send the data straight to the telemetry port.
|
||||
// FIXME following call can fail (with -2 error code) if buffer is full
|
||||
// it is the caller responsibility to retry in such cases...
|
||||
// Following call can fail with -2 error code (buffer full) or -3 error code (could not acquire send mutex)
|
||||
// It is the caller responsibility to retry in such cases...
|
||||
int32_t ret = -2;
|
||||
uint8_t count = 5;
|
||||
while (count-- > 0 && ret < -1) {
|
||||
@ -514,8 +513,8 @@ static void serialRxTask(__attribute__((unused)) void *parameters)
|
||||
|
||||
if (bytes_to_process > 0) {
|
||||
// Send the data over the radio link.
|
||||
// FIXME following call can fail (with -2 error code) if buffer is full
|
||||
// it is the caller responsibility to retry in such cases...
|
||||
// Following call can fail with -2 error code (buffer full) or -3 error code (could not acquire send mutex)
|
||||
// It is the caller responsibility to retry in such cases...
|
||||
int32_t ret = -2;
|
||||
uint8_t count = 5;
|
||||
while (count-- > 0 && ret < -1) {
|
||||
@ -548,8 +547,8 @@ static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length)
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
if (outputPort) {
|
||||
// FIXME following call can fail (with -2 error code) if buffer is full
|
||||
// it is the caller responsibility to retry in such cases...
|
||||
// Following call can fail with -2 error code (buffer full) or -3 error code (could not acquire send mutex)
|
||||
// It is the caller responsibility to retry in such cases...
|
||||
ret = -2;
|
||||
uint8_t count = 5;
|
||||
while (count-- > 0 && ret < -1) {
|
||||
@ -578,8 +577,8 @@ static int32_t RadioSendHandler(uint8_t *buf, int32_t length)
|
||||
|
||||
// Don't send any data unless the radio port is available.
|
||||
if (outputPort && PIOS_COM_Available(outputPort)) {
|
||||
// FIXME following call can fail (with -2 error code) if buffer is full
|
||||
// it is the caller responsibility to retry in such cases...
|
||||
// Following call can fail with -2 error code (buffer full) or -3 error code (could not acquire send mutex)
|
||||
// It is the caller responsibility to retry in such cases...
|
||||
int32_t ret = -2;
|
||||
uint8_t count = 5;
|
||||
while (count-- > 0 && ret < -1) {
|
||||
|
@ -454,11 +454,11 @@ static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent *objEv)
|
||||
mag_scale[2] = cal.mag_scale.Z;
|
||||
|
||||
accel_temp_calibrated = (agcal.temp_calibrated_extent.max - agcal.temp_calibrated_extent.min > .1f) &&
|
||||
agcal.accel_temp_coeff.X > 1e-9f && agcal.accel_temp_coeff.Y > 1e-9f && agcal.accel_temp_coeff.Z > 1e-9f;
|
||||
(fabsf(agcal.accel_temp_coeff.X) > 1e-9f || fabsf(agcal.accel_temp_coeff.Y) > 1e-9f || fabsf(agcal.accel_temp_coeff.Z) > 1e-9f);
|
||||
|
||||
gyro_temp_calibrated = (agcal.temp_calibrated_extent.max - agcal.temp_calibrated_extent.min > .1f) &&
|
||||
agcal.gyro_temp_coeff.X > 1e-9f && agcal.gyro_temp_coeff.Y > 1e-9f &&
|
||||
agcal.gyro_temp_coeff.Z > 1e-9f && agcal.gyro_temp_coeff.Z2 > 1e-9f;
|
||||
(fabsf(agcal.gyro_temp_coeff.X) > 1e-9f || fabsf(agcal.gyro_temp_coeff.Y) > 1e-9f ||
|
||||
fabsf(agcal.gyro_temp_coeff.Z) > 1e-9f || fabsf(agcal.gyro_temp_coeff.Z2) > 1e-9f);
|
||||
|
||||
|
||||
AttitudeSettingsData attitudeSettings;
|
||||
|
@ -424,7 +424,7 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
// and the Att rate equals the Rate rate
|
||||
// that's where Rate x (1-StickAngle) [Attitude pulling down max X Ratt proportion]
|
||||
// == Rate x StickAngle [Rate pulling up according to stick angle]
|
||||
// * StickAngle [X Ratt proportion]
|
||||
// * StickAngle [X Ratt proportion]
|
||||
// so 1-x == x*x or x*x+x-1=0 where xE(0,1)
|
||||
// (-1+-sqrt(1+4))/2 = (-1+sqrt(5))/2
|
||||
// and quadratic formula says that is 0.618033989f
|
||||
@ -448,7 +448,7 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
magnitude *= STICK_VALUE_AT_MODE_TRANSITION / rattitude_mode_transition_stick_position;
|
||||
} else {
|
||||
magnitude = (magnitude - rattitude_mode_transition_stick_position)
|
||||
* (1.0f-STICK_VALUE_AT_MODE_TRANSITION)
|
||||
* (1.0f - STICK_VALUE_AT_MODE_TRANSITION)
|
||||
/ (1.0f - rattitude_mode_transition_stick_position)
|
||||
+ STICK_VALUE_AT_MODE_TRANSITION;
|
||||
}
|
||||
@ -1056,7 +1056,7 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
cur_flight_mode = -1;
|
||||
|
||||
// Rattitude stick angle where the attitude to rate transition happens
|
||||
if (settings.RattitudeModeTransition < (uint8_t) 10) {
|
||||
if (settings.RattitudeModeTransition < (uint8_t)10) {
|
||||
rattitude_mode_transition_stick_position = 10.0f / 100.0f;
|
||||
} else {
|
||||
rattitude_mode_transition_stick_position = (float)settings.RattitudeModeTransition / 100.0f;
|
||||
|
@ -78,7 +78,7 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
this->altitude = state->baro[0];
|
||||
}
|
||||
// calculate true airspeed estimation
|
||||
if (IS_SET(state->updated, SENSORUPDATES_airspeed)) {
|
||||
if (IS_SET(state->updated, SENSORUPDATES_airspeed) && (state->airspeed[1] < 0.f)) {
|
||||
state->airspeed[1] = state->airspeed[0] * IAS2TAS(this->altitude);
|
||||
}
|
||||
|
||||
|
@ -38,16 +38,23 @@
|
||||
|
||||
// Private constants
|
||||
|
||||
#define STACK_REQUIRED 128
|
||||
// duration of accel bias initialization phase
|
||||
#define INITIALIZATION_DURATION_MS 5000
|
||||
|
||||
#define DT_ALPHA 1e-2f
|
||||
#define DT_MIN 1e-6f
|
||||
#define DT_MAX 1.0f
|
||||
#define DT_AVERAGE 1e-3f
|
||||
#define STACK_REQUIRED 128
|
||||
|
||||
#define DT_ALPHA 1e-2f
|
||||
#define DT_MIN 1e-6f
|
||||
#define DT_MAX 1.0f
|
||||
#define DT_AVERAGE 1e-3f
|
||||
static volatile bool reloadSettings;
|
||||
|
||||
// Private types
|
||||
struct data {
|
||||
float state[4]; // state = altitude,velocity,accel_offset,accel
|
||||
float altitudeState; // state = altitude,velocity,accel_offset,accel
|
||||
float velocityState;
|
||||
float accelBiasState;
|
||||
float accelState;
|
||||
float pos[3]; // position updates from other filters
|
||||
float vel[3]; // position updates from other filters
|
||||
|
||||
@ -56,6 +63,7 @@ struct data {
|
||||
float accelLast;
|
||||
float baroLast;
|
||||
bool first_run;
|
||||
portTickType initTimer;
|
||||
AltitudeFilterSettingsData settings;
|
||||
};
|
||||
|
||||
@ -65,6 +73,7 @@ struct data {
|
||||
|
||||
static int32_t init(stateFilter *self);
|
||||
static int32_t filter(stateFilter *self, stateEstimation *state);
|
||||
static void settingsUpdatedCb(UAVObjEvent *ev);
|
||||
|
||||
|
||||
int32_t filterAltitudeInitialize(stateFilter *handle)
|
||||
@ -74,6 +83,8 @@ int32_t filterAltitudeInitialize(stateFilter *handle)
|
||||
handle->localdata = pvPortMalloc(sizeof(struct data));
|
||||
AttitudeStateInitialize();
|
||||
AltitudeFilterSettingsInitialize();
|
||||
AltitudeFilterSettingsConnectCallback(&settingsUpdatedCb);
|
||||
reloadSettings = true;
|
||||
return STACK_REQUIRED;
|
||||
}
|
||||
|
||||
@ -81,10 +92,10 @@ static int32_t init(stateFilter *self)
|
||||
{
|
||||
struct data *this = (struct data *)self->localdata;
|
||||
|
||||
this->state[0] = 0.0f;
|
||||
this->state[1] = 0.0f;
|
||||
this->state[2] = 0.0f;
|
||||
this->state[3] = 0.0f;
|
||||
this->altitudeState = 0.0f;
|
||||
this->velocityState = 0.0f;
|
||||
this->accelBiasState = 0.0f;
|
||||
this->accelState = 0.0f;
|
||||
this->pos[0] = 0.0f;
|
||||
this->pos[1] = 0.0f;
|
||||
this->pos[2] = 0.0f;
|
||||
@ -96,7 +107,6 @@ static int32_t init(stateFilter *self)
|
||||
this->baroLast = 0.0f;
|
||||
this->accelLast = 0.0f;
|
||||
this->first_run = 1;
|
||||
AltitudeFilterSettingsGet(&this->settings);
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -104,10 +114,16 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
{
|
||||
struct data *this = (struct data *)self->localdata;
|
||||
|
||||
if (reloadSettings) {
|
||||
reloadSettings = false;
|
||||
AltitudeFilterSettingsGet(&this->settings);
|
||||
}
|
||||
|
||||
if (this->first_run) {
|
||||
// Initialize to current altitude reading at initial location
|
||||
if (IS_SET(state->updated, SENSORUPDATES_baro)) {
|
||||
this->first_run = 0;
|
||||
this->initTimer = xTaskGetTickCount();
|
||||
}
|
||||
} else {
|
||||
// save existing position and velocity updates so GPS will still work
|
||||
@ -115,13 +131,13 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
this->pos[0] = state->pos[0];
|
||||
this->pos[1] = state->pos[1];
|
||||
this->pos[2] = state->pos[2];
|
||||
state->pos[2] = -this->state[0];
|
||||
state->pos[2] = -this->altitudeState;
|
||||
}
|
||||
if (IS_SET(state->updated, SENSORUPDATES_vel)) {
|
||||
this->vel[0] = state->vel[0];
|
||||
this->vel[1] = state->vel[1];
|
||||
this->vel[2] = state->vel[2];
|
||||
state->vel[2] = -this->state[1];
|
||||
state->vel[2] = -this->velocityState;
|
||||
}
|
||||
if (IS_SET(state->updated, SENSORUPDATES_accel)) {
|
||||
// rotate accels into global coordinate frame
|
||||
@ -132,51 +148,54 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
float current = -(Rbe[0][2] * state->accel[0] + Rbe[1][2] * state->accel[1] + Rbe[2][2] * state->accel[2] + 9.81f);
|
||||
|
||||
// low pass filter accelerometers
|
||||
this->state[3] = (1.0f - this->settings.AccelLowPassKp) * this->state[3] + this->settings.AccelLowPassKp * current;
|
||||
|
||||
// correct accel offset (low pass zeroing)
|
||||
this->state[2] = (1.0f - this->settings.AccelDriftKi) * this->state[2] + this->settings.AccelDriftKi * this->state[3];
|
||||
|
||||
this->accelState = (1.0f - this->settings.AccelLowPassKp) * this->accelState + this->settings.AccelLowPassKp * current;
|
||||
if (((xTaskGetTickCount() - this->initTimer) / portTICK_RATE_MS) < INITIALIZATION_DURATION_MS) {
|
||||
// allow the offset to reach quickly the target value in case of small AccelDriftKi
|
||||
this->accelBiasState = (1.0f - this->settings.InitializationAccelDriftKi) * this->accelBiasState + this->settings.InitializationAccelDriftKi * this->accelState;
|
||||
} else {
|
||||
// correct accel offset (low pass zeroing)
|
||||
this->accelBiasState = (1.0f - this->settings.AccelDriftKi) * this->accelBiasState + this->settings.AccelDriftKi * this->accelState;
|
||||
}
|
||||
// correct velocity and position state (integration)
|
||||
// low pass for average dT, compensate timing jitter from scheduler
|
||||
//
|
||||
float dT = PIOS_DELTATIME_GetAverageSeconds(&this->dt1config);
|
||||
float speedLast = this->state[1];
|
||||
float speedLast = this->velocityState;
|
||||
|
||||
this->state[1] += 0.5f * (this->accelLast + (this->state[3] - this->state[2])) * dT;
|
||||
this->accelLast = this->state[3] - this->state[2];
|
||||
this->velocityState += 0.5f * (this->accelLast + (this->accelState - this->accelBiasState)) * dT;
|
||||
this->accelLast = this->accelState - this->accelBiasState;
|
||||
|
||||
this->state[0] += 0.5f * (speedLast + this->state[1]) * dT;
|
||||
this->altitudeState += 0.5f * (speedLast + this->velocityState) * dT;
|
||||
|
||||
|
||||
state->pos[0] = this->pos[0];
|
||||
state->pos[1] = this->pos[1];
|
||||
state->pos[2] = -this->state[0];
|
||||
state->pos[2] = -this->altitudeState;
|
||||
state->updated |= SENSORUPDATES_pos;
|
||||
|
||||
state->vel[0] = this->vel[0];
|
||||
state->vel[1] = this->vel[1];
|
||||
state->vel[2] = -this->state[1];
|
||||
state->vel[2] = -this->velocityState;
|
||||
state->updated |= SENSORUPDATES_vel;
|
||||
}
|
||||
if (IS_SET(state->updated, SENSORUPDATES_baro)) {
|
||||
// correct the altitude state (simple low pass)
|
||||
this->state[0] = (1.0f - this->settings.BaroKp) * this->state[0] + this->settings.BaroKp * state->baro[0];
|
||||
this->altitudeState = (1.0f - this->settings.BaroKp) * this->altitudeState + this->settings.BaroKp * state->baro[0];
|
||||
|
||||
// correct the velocity state (low pass differentiation)
|
||||
// low pass for average dT, compensate timing jitter from scheduler
|
||||
float dT = PIOS_DELTATIME_GetAverageSeconds(&this->dt2config);
|
||||
this->state[1] = (1.0f - (this->settings.BaroKp * this->settings.BaroKp)) * this->state[1] + (this->settings.BaroKp * this->settings.BaroKp) * (state->baro[0] - this->baroLast) / dT;
|
||||
this->velocityState = (1.0f - (this->settings.BaroKp * this->settings.BaroKp)) * this->velocityState + (this->settings.BaroKp * this->settings.BaroKp) * (state->baro[0] - this->baroLast) / dT;
|
||||
this->baroLast = state->baro[0];
|
||||
|
||||
state->pos[0] = this->pos[0];
|
||||
state->pos[1] = this->pos[1];
|
||||
state->pos[2] = -this->state[0];
|
||||
state->pos[2] = -this->altitudeState;
|
||||
state->updated |= SENSORUPDATES_pos;
|
||||
|
||||
state->vel[0] = this->vel[0];
|
||||
state->vel[1] = this->vel[1];
|
||||
state->vel[2] = -this->state[1];
|
||||
state->vel[2] = -this->velocityState;
|
||||
state->updated |= SENSORUPDATES_vel;
|
||||
}
|
||||
}
|
||||
@ -184,6 +203,12 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
return 0;
|
||||
}
|
||||
|
||||
void settingsUpdatedCb(UAVObjEvent *ev)
|
||||
{
|
||||
if (ev->obj == AltitudeFilterSettingsHandle()) {
|
||||
reloadSettings = true;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -36,7 +36,7 @@
|
||||
|
||||
// Private constants
|
||||
|
||||
#define STACK_REQUIRED 64
|
||||
#define STACK_REQUIRED 128
|
||||
#define INIT_CYCLES 100
|
||||
|
||||
// Private types
|
||||
@ -44,30 +44,59 @@ struct data {
|
||||
float baroOffset;
|
||||
float baroGPSOffsetCorrectionAlpha;
|
||||
float baroAlt;
|
||||
float gpsAlt;
|
||||
int16_t first_run;
|
||||
bool useGPS;
|
||||
};
|
||||
|
||||
// Private variables
|
||||
|
||||
// Private functions
|
||||
|
||||
static int32_t init(stateFilter *self);
|
||||
static int32_t initwithgps(stateFilter *self);
|
||||
static int32_t initwithoutgps(stateFilter *self);
|
||||
static int32_t maininit(stateFilter *self);
|
||||
static int32_t filter(stateFilter *self, stateEstimation *state);
|
||||
|
||||
|
||||
int32_t filterBaroInitialize(stateFilter *handle)
|
||||
{
|
||||
handle->init = &init;
|
||||
handle->init = &initwithgps;
|
||||
handle->filter = &filter;
|
||||
handle->localdata = pvPortMalloc(sizeof(struct data));
|
||||
return STACK_REQUIRED;
|
||||
}
|
||||
|
||||
static int32_t init(stateFilter *self)
|
||||
int32_t filterBaroiInitialize(stateFilter *handle)
|
||||
{
|
||||
handle->init = &initwithoutgps;
|
||||
handle->filter = &filter;
|
||||
handle->localdata = pvPortMalloc(sizeof(struct data));
|
||||
return STACK_REQUIRED;
|
||||
}
|
||||
|
||||
static int32_t initwithgps(stateFilter *self)
|
||||
{
|
||||
struct data *this = (struct data *)self->localdata;
|
||||
|
||||
this->useGPS = 1;
|
||||
return maininit(self);
|
||||
}
|
||||
|
||||
static int32_t initwithoutgps(stateFilter *self)
|
||||
{
|
||||
struct data *this = (struct data *)self->localdata;
|
||||
|
||||
this->useGPS = 0;
|
||||
return maininit(self);
|
||||
}
|
||||
|
||||
static int32_t maininit(stateFilter *self)
|
||||
{
|
||||
struct data *this = (struct data *)self->localdata;
|
||||
|
||||
this->baroOffset = 0.0f;
|
||||
this->gpsAlt = 0.0f;
|
||||
this->first_run = INIT_CYCLES;
|
||||
|
||||
RevoSettingsInitialize();
|
||||
@ -81,17 +110,29 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
struct data *this = (struct data *)self->localdata;
|
||||
|
||||
if (this->first_run) {
|
||||
// Make sure initial location is initialized properly before continuing
|
||||
if (this->useGPS && IS_SET(state->updated, SENSORUPDATES_pos)) {
|
||||
if (this->first_run == INIT_CYCLES) {
|
||||
this->gpsAlt = state->pos[2];
|
||||
this->first_run--;
|
||||
}
|
||||
}
|
||||
// Initialize to current altitude reading at initial location
|
||||
if (IS_SET(state->updated, SENSORUPDATES_baro)) {
|
||||
this->baroOffset = ((float)(INIT_CYCLES)-this->first_run) / (float)(INIT_CYCLES)*this->baroOffset + (this->first_run / (float)(INIT_CYCLES)) * state->baro[0];
|
||||
this->baroAlt = 0;
|
||||
this->first_run--;
|
||||
if (this->first_run < INIT_CYCLES || !this->useGPS) {
|
||||
this->baroOffset = (((float)(INIT_CYCLES)-this->first_run) / (float)(INIT_CYCLES)) * this->baroOffset + (this->first_run / (float)(INIT_CYCLES)) * (state->baro[0] + this->gpsAlt);
|
||||
this->baroAlt = state->baro[0];
|
||||
this->first_run--;
|
||||
}
|
||||
UNSET_MASK(state->updated, SENSORUPDATES_baro);
|
||||
}
|
||||
// make sure we raise an error until properly initialized - would not be good if people arm and
|
||||
// use altitudehold without initialized barometer filter
|
||||
return 2;
|
||||
} else {
|
||||
// Track barometric altitude offset with a low pass filter
|
||||
// based on GPS altitude if available
|
||||
if (IS_SET(state->updated, SENSORUPDATES_pos)) {
|
||||
if (this->useGPS && IS_SET(state->updated, SENSORUPDATES_pos)) {
|
||||
this->baroOffset = this->baroOffset * this->baroGPSOffsetCorrectionAlpha +
|
||||
(1.0f - this->baroGPSOffsetCorrectionAlpha) * (this->baroAlt + state->pos[2]);
|
||||
}
|
||||
@ -100,9 +141,8 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
this->baroAlt = state->baro[0];
|
||||
state->baro[0] -= this->baroOffset;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
@ -64,6 +64,7 @@ typedef struct stateFilterStruct {
|
||||
|
||||
|
||||
int32_t filterMagInitialize(stateFilter *handle);
|
||||
int32_t filterBaroiInitialize(stateFilter *handle);
|
||||
int32_t filterBaroInitialize(stateFilter *handle);
|
||||
int32_t filterAltitudeInitialize(stateFilter *handle);
|
||||
int32_t filterAirInitialize(stateFilter *handle);
|
||||
|
@ -40,6 +40,7 @@
|
||||
#include <airspeedsensor.h>
|
||||
#include <gpspositionsensor.h>
|
||||
#include <gpsvelocitysensor.h>
|
||||
#include <homelocation.h>
|
||||
|
||||
#include <gyrostate.h>
|
||||
#include <accelstate.h>
|
||||
@ -55,10 +56,14 @@
|
||||
#include "CoordinateConversions.h"
|
||||
|
||||
// Private constants
|
||||
#define STACK_SIZE_BYTES 256
|
||||
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_REGULAR
|
||||
#define TASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
|
||||
#define TIMEOUT_MS 10
|
||||
#define STACK_SIZE_BYTES 256
|
||||
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_REGULAR
|
||||
#define TASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
|
||||
#define TIMEOUT_MS 10
|
||||
|
||||
// Private filter init const
|
||||
#define FILTER_INIT_FORCE -1
|
||||
#define FILTER_INIT_IF_POSSIBLE -2
|
||||
|
||||
// local macros, ONLY to be used in the middle of StateEstimationCb in section RUNSTATE_LOAD after the update of states updated!
|
||||
#define FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_3_DIMENSIONS(sensorname, shortname, a1, a2, a3) \
|
||||
@ -74,6 +79,7 @@
|
||||
UNSET_MASK(states.updated, SENSORUPDATES_##shortname); \
|
||||
} \
|
||||
}
|
||||
|
||||
#define FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_1_DIMENSION_WITH_CUSTOM_EXTRA_CHECK(sensorname, shortname, a1, EXTRACHECK) \
|
||||
if (IS_SET(states.updated, SENSORUPDATES_##shortname)) { \
|
||||
sensorname##Data s; \
|
||||
@ -86,6 +92,19 @@
|
||||
} \
|
||||
}
|
||||
|
||||
#define FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_2_DIMENSION_WITH_CUSTOM_EXTRA_CHECK(sensorname, shortname, a1, a2, EXTRACHECK) \
|
||||
if (IS_SET(states.updated, SENSORUPDATES_##shortname)) { \
|
||||
sensorname##Data s; \
|
||||
sensorname##Get(&s); \
|
||||
if (IS_REAL(s.a1) && IS_REAL(s.a2) && EXTRACHECK) { \
|
||||
states.shortname[0] = s.a1; \
|
||||
states.shortname[1] = s.a2; \
|
||||
} \
|
||||
else { \
|
||||
UNSET_MASK(states.updated, SENSORUPDATES_##shortname); \
|
||||
} \
|
||||
}
|
||||
|
||||
// local macros, ONLY to be used in the middle of StateEstimationCb in section RUNSTATE_SAVE before the check of alarms!
|
||||
#define EXPORT_STATE_TO_UAVOBJECT_IF_UPDATED_3_DIMENSIONS(statename, shortname, a1, a2, a3) \
|
||||
if (IS_SET(states.updated, SENSORUPDATES_##shortname)) { \
|
||||
@ -96,6 +115,7 @@
|
||||
s.a3 = states.shortname[2]; \
|
||||
statename##Set(&s); \
|
||||
}
|
||||
|
||||
#define EXPORT_STATE_TO_UAVOBJECT_IF_UPDATED_2_DIMENSIONS(statename, shortname, a1, a2) \
|
||||
if (IS_SET(states.updated, SENSORUPDATES_##shortname)) { \
|
||||
statename##Data s; \
|
||||
@ -105,8 +125,8 @@
|
||||
statename##Set(&s); \
|
||||
}
|
||||
|
||||
// Private types
|
||||
|
||||
// Private types
|
||||
struct filterPipelineStruct;
|
||||
|
||||
typedef const struct filterPipelineStruct {
|
||||
@ -119,12 +139,13 @@ static DelayedCallbackInfo *stateEstimationCallback;
|
||||
|
||||
static volatile RevoSettingsData revoSettings;
|
||||
static volatile sensorUpdates updatedSensors;
|
||||
static int32_t fusionAlgorithm = -1;
|
||||
static filterPipeline *filterChain = NULL;
|
||||
static volatile int32_t fusionAlgorithm = -1;
|
||||
static const filterPipeline *filterChain = NULL;
|
||||
|
||||
// different filters available to state estimation
|
||||
static stateFilter magFilter;
|
||||
static stateFilter baroFilter;
|
||||
static stateFilter baroiFilter;
|
||||
static stateFilter altitudeFilter;
|
||||
static stateFilter airFilter;
|
||||
static stateFilter stationaryFilter;
|
||||
@ -135,20 +156,33 @@ static stateFilter ekf13iFilter;
|
||||
static stateFilter ekf13Filter;
|
||||
|
||||
// preconfigured filter chains selectable via revoSettings.FusionAlgorithm
|
||||
static filterPipeline *cfQueue = &(filterPipeline) {
|
||||
static const filterPipeline *cfQueue = &(filterPipeline) {
|
||||
.filter = &magFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &airFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &llaFilter,
|
||||
.filter = &baroiFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &baroFilter,
|
||||
.filter = &altitudeFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &altitudeFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &cfFilter,
|
||||
.next = NULL,
|
||||
}
|
||||
.filter = &cfFilter,
|
||||
.next = NULL,
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
};
|
||||
static const filterPipeline *cfmiQueue = &(filterPipeline) {
|
||||
.filter = &magFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &airFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &baroiFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &altitudeFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &cfmFilter,
|
||||
.next = NULL,
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -178,15 +212,12 @@ static const filterPipeline *ekf13iQueue = &(filterPipeline) {
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &airFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &llaFilter,
|
||||
.filter = &baroiFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &baroFilter,
|
||||
.filter = &stationaryFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &stationaryFilter,
|
||||
.next = &(filterPipeline) {
|
||||
.filter = &ekf13iFilter,
|
||||
.next = NULL,
|
||||
}
|
||||
.filter = &ekf13iFilter,
|
||||
.next = NULL,
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -213,6 +244,7 @@ static const filterPipeline *ekf13Queue = &(filterPipeline) {
|
||||
|
||||
static void settingsUpdatedCb(UAVObjEvent *objEv);
|
||||
static void sensorUpdatedCb(UAVObjEvent *objEv);
|
||||
static void homeLocationUpdatedCb(UAVObjEvent *objEv);
|
||||
static void StateEstimationCb(void);
|
||||
|
||||
static inline int32_t maxint32_t(int32_t a, int32_t b)
|
||||
@ -238,6 +270,8 @@ int32_t StateEstimationInitialize(void)
|
||||
GPSVelocitySensorInitialize();
|
||||
GPSPositionSensorInitialize();
|
||||
|
||||
HomeLocationInitialize();
|
||||
|
||||
GyroStateInitialize();
|
||||
AccelStateInitialize();
|
||||
MagStateInitialize();
|
||||
@ -247,6 +281,8 @@ int32_t StateEstimationInitialize(void)
|
||||
|
||||
RevoSettingsConnectCallback(&settingsUpdatedCb);
|
||||
|
||||
HomeLocationConnectCallback(&homeLocationUpdatedCb);
|
||||
|
||||
GyroSensorConnectCallback(&sensorUpdatedCb);
|
||||
AccelSensorConnectCallback(&sensorUpdatedCb);
|
||||
MagSensorConnectCallback(&sensorUpdatedCb);
|
||||
@ -258,6 +294,7 @@ int32_t StateEstimationInitialize(void)
|
||||
uint32_t stack_required = STACK_SIZE_BYTES;
|
||||
// Initialize Filters
|
||||
stack_required = maxint32_t(stack_required, filterMagInitialize(&magFilter));
|
||||
stack_required = maxint32_t(stack_required, filterBaroiInitialize(&baroiFilter));
|
||||
stack_required = maxint32_t(stack_required, filterBaroInitialize(&baroFilter));
|
||||
stack_required = maxint32_t(stack_required, filterAltitudeInitialize(&altitudeFilter));
|
||||
stack_required = maxint32_t(stack_required, filterAirInitialize(&airFilter));
|
||||
@ -299,7 +336,7 @@ static void StateEstimationCb(void)
|
||||
static int8_t alarm = 0;
|
||||
static int8_t lastAlarm = -1;
|
||||
static uint16_t alarmcounter = 0;
|
||||
static filterPipeline *current;
|
||||
static const filterPipeline *current;
|
||||
static stateEstimation states;
|
||||
static uint32_t last_time;
|
||||
static uint16_t bootDelay = 64;
|
||||
@ -329,26 +366,29 @@ static void StateEstimationCb(void)
|
||||
if (fusionAlgorithm != revoSettings.FusionAlgorithm) {
|
||||
FlightStatusData fs;
|
||||
FlightStatusGet(&fs);
|
||||
if (fs.Armed == FLIGHTSTATUS_ARMED_DISARMED || fusionAlgorithm == -1) {
|
||||
if (fs.Armed == FLIGHTSTATUS_ARMED_DISARMED || fusionAlgorithm == FILTER_INIT_FORCE) {
|
||||
const filterPipeline *newFilterChain;
|
||||
switch (revoSettings.FusionAlgorithm) {
|
||||
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARY:
|
||||
newFilterChain = cfQueue;
|
||||
break;
|
||||
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARYMAG:
|
||||
newFilterChain = cfmiQueue;
|
||||
break;
|
||||
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARYMAGGPSOUTDOOR:
|
||||
newFilterChain = cfmQueue;
|
||||
break;
|
||||
case REVOSETTINGS_FUSIONALGORITHM_INS13INDOOR:
|
||||
newFilterChain = ekf13iQueue;
|
||||
break;
|
||||
case REVOSETTINGS_FUSIONALGORITHM_INS13OUTDOOR:
|
||||
case REVOSETTINGS_FUSIONALGORITHM_INS13GPSOUTDOOR:
|
||||
newFilterChain = ekf13Queue;
|
||||
break;
|
||||
default:
|
||||
newFilterChain = NULL;
|
||||
}
|
||||
// initialize filters in chain
|
||||
current = (filterPipeline *)newFilterChain;
|
||||
current = newFilterChain;
|
||||
bool error = 0;
|
||||
while (current != NULL) {
|
||||
int32_t result = current->filter->init((stateFilter *)current->filter);
|
||||
@ -363,7 +403,7 @@ static void StateEstimationCb(void)
|
||||
return;
|
||||
} else {
|
||||
// set new fusion algortithm
|
||||
filterChain = (filterPipeline *)newFilterChain;
|
||||
filterChain = newFilterChain;
|
||||
fusionAlgorithm = revoSettings.FusionAlgorithm;
|
||||
}
|
||||
}
|
||||
@ -379,14 +419,14 @@ static void StateEstimationCb(void)
|
||||
FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_3_DIMENSIONS(MagSensor, mag, x, y, z);
|
||||
FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_3_DIMENSIONS(GPSVelocitySensor, vel, North, East, Down);
|
||||
FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_1_DIMENSION_WITH_CUSTOM_EXTRA_CHECK(BaroSensor, baro, Altitude, true);
|
||||
FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_1_DIMENSION_WITH_CUSTOM_EXTRA_CHECK(AirspeedSensor, airspeed, CalibratedAirspeed, s.SensorConnected == AIRSPEEDSENSOR_SENSORCONNECTED_TRUE);
|
||||
states.airspeed[1] = 0.0f; // sensor does not provide true airspeed, needs to be calculated by filter, set to zero for now
|
||||
FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_2_DIMENSION_WITH_CUSTOM_EXTRA_CHECK(AirspeedSensor, airspeed, CalibratedAirspeed, TrueAirspeed, s.SensorConnected == AIRSPEEDSENSOR_SENSORCONNECTED_TRUE);
|
||||
|
||||
// GPS position data (LLA) is not fetched here since it does not contain floats. The filter must do all checks itself
|
||||
|
||||
// at this point sensor state is stored in "states" with some rudimentary filtering applied
|
||||
|
||||
// apply all filters in the current filter chain
|
||||
current = (filterPipeline *)filterChain;
|
||||
current = filterChain;
|
||||
|
||||
// we are not done, re-dispatch self execution
|
||||
runState = RUNSTATE_FILTER;
|
||||
@ -477,6 +517,17 @@ static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
RevoSettingsGet((RevoSettingsData *)&revoSettings);
|
||||
}
|
||||
|
||||
/**
|
||||
* Callback for eventdispatcher when HomeLocation has been updated
|
||||
*/
|
||||
static void homeLocationUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
// Ask for a filter init (necessary for LLA filter)
|
||||
// Only possible if disarmed
|
||||
fusionAlgorithm = FILTER_INIT_IF_POSSIBLE;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Callback for eventdispatcher when any sensor UAVObject has been updated
|
||||
* updates the list of "recently updated UAVObjects" and dispatches the state estimator callback
|
||||
|
@ -40,20 +40,37 @@
|
||||
#include "taskinfo.h"
|
||||
|
||||
// Private constants
|
||||
#define MAX_QUEUE_SIZE TELEM_QUEUE_SIZE
|
||||
#define STACK_SIZE_BYTES PIOS_TELEM_STACK_SIZE
|
||||
#define TASK_PRIORITY_RX (tskIDLE_PRIORITY + 2)
|
||||
#define TASK_PRIORITY_TX (tskIDLE_PRIORITY + 2)
|
||||
#define TASK_PRIORITY_RADRX (tskIDLE_PRIORITY + 2)
|
||||
#define REQ_TIMEOUT_MS 250
|
||||
#define MAX_RETRIES 2
|
||||
#define STATS_UPDATE_PERIOD_MS 4000
|
||||
#define CONNECTION_TIMEOUT_MS 8000
|
||||
#define MAX_QUEUE_SIZE TELEM_QUEUE_SIZE
|
||||
// Three different stack size parameter are accepted for Telemetry(RX PIOS_TELEM_RX_STACK_SIZE)
|
||||
// Tx(PIOS_TELEM_TX_STACK_SIZE) and Radio RX(PIOS_TELEM_RADIO_RX_STACK_SIZE)
|
||||
#ifdef PIOS_TELEM_RX_STACK_SIZE
|
||||
#define STACK_SIZE_RX_BYTES PIOS_TELEM_RX_STACK_SIZE
|
||||
#define STACK_SIZE_TX_BYTES PIOS_TELEM_TX_STACK_SIZE
|
||||
#else
|
||||
#define STACK_SIZE_RX_BYTES PIOS_TELEM_STACK_SIZE
|
||||
#define STACK_SIZE_TX_BYTES PIOS_TELEM_STACK_SIZE
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_TELEM_RADIO_RX_STACK_SIZE
|
||||
#define STACK_SIZE_RADIO_RX_BYTES PIOS_TELEM_RADIO_RX_STACK_SIZE
|
||||
#else
|
||||
#define STACK_SIZE_RADIO_RX_BYTES STACK_SIZE_RX_BYTES
|
||||
#endif
|
||||
#define TASK_PRIORITY_RX (tskIDLE_PRIORITY + 2)
|
||||
#define TASK_PRIORITY_TX (tskIDLE_PRIORITY + 2)
|
||||
#define TASK_PRIORITY_RADRX (tskIDLE_PRIORITY + 2)
|
||||
#define REQ_TIMEOUT_MS 250
|
||||
#define MAX_RETRIES 2
|
||||
#define STATS_UPDATE_PERIOD_MS 4000
|
||||
#define CONNECTION_TIMEOUT_MS 8000
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static uint32_t telemetryPort;
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
static uint32_t radioPort;
|
||||
#endif
|
||||
static xQueueHandle queue;
|
||||
|
||||
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
|
||||
@ -80,6 +97,7 @@ static void telemetryTxTask(void *parameters);
|
||||
static void telemetryRxTask(void *parameters);
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
static void radioRxTask(void *parameters);
|
||||
static int32_t transmitRadioData(uint8_t *data, int32_t length);
|
||||
#endif
|
||||
static int32_t transmitData(uint8_t *data, int32_t length);
|
||||
static void registerObject(UAVObjHandle obj);
|
||||
@ -106,13 +124,13 @@ int32_t TelemetryStart(void)
|
||||
GCSTelemetryStatsConnectQueue(priorityQueue);
|
||||
|
||||
// Start telemetry tasks
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_TX_BYTES / 4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
|
||||
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_TELEMETRYTX, telemetryTxTaskHandle);
|
||||
xTaskCreate(telemetryRxTask, (signed char *)"TelRx", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
|
||||
xTaskCreate(telemetryRxTask, (signed char *)"TelRx", STACK_SIZE_RX_BYTES / 4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
|
||||
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_TELEMETRYRX, telemetryRxTaskHandle);
|
||||
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
xTaskCreate(radioRxTask, (signed char *)"RadioRx", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY_RADRX, &radioRxTaskHandle);
|
||||
xTaskCreate(radioRxTask, (signed char *)"RadioRx", STACK_SIZE_RADIO_RX_BYTES / 4, NULL, TASK_PRIORITY_RADRX, &radioRxTaskHandle);
|
||||
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_RADIORX, radioRxTaskHandle);
|
||||
#endif
|
||||
|
||||
@ -140,13 +158,16 @@ int32_t TelemetryInitialize(void)
|
||||
|
||||
// Update telemetry settings
|
||||
telemetryPort = PIOS_COM_TELEM_RF;
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
radioPort = PIOS_COM_RF;
|
||||
#endif
|
||||
HwSettingsInitialize();
|
||||
updateSettings();
|
||||
|
||||
// Initialise UAVTalk
|
||||
uavTalkCon = UAVTalkInitialize(&transmitData);
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
radioUavTalkCon = UAVTalkInitialize(&transmitData);
|
||||
radioUavTalkCon = UAVTalkInitialize(&transmitRadioData);
|
||||
#endif
|
||||
|
||||
// Create periodic event that will be used to update the telemetry stats
|
||||
@ -375,17 +396,27 @@ static void telemetryTxTask(__attribute__((unused)) void *parameters)
|
||||
* Tries to empty the high priority queue before handling any standard priority item
|
||||
*/
|
||||
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
|
||||
// Loop forever
|
||||
while (xQueueReceive(priorityQueue, &ev, 1) == pdTRUE) {
|
||||
// empty priority queue, non-blocking
|
||||
while (xQueueReceive(priorityQueue, &ev, 0) == pdTRUE) {
|
||||
// Process event
|
||||
processObjEvent(&ev);
|
||||
}
|
||||
#endif
|
||||
// Wait for queue message
|
||||
// check regular queue and process update - non-blocking
|
||||
if (xQueueReceive(queue, &ev, 0) == pdTRUE) {
|
||||
// Process event
|
||||
processObjEvent(&ev);
|
||||
// if both queues are empty, wait on priority queue for updates (1 tick) then repeat cycle
|
||||
} else if (xQueueReceive(priorityQueue, &ev, 1) == pdTRUE) {
|
||||
// Process event
|
||||
processObjEvent(&ev);
|
||||
}
|
||||
#else
|
||||
// wait on queue for updates (1 tick) then repeat cycle
|
||||
if (xQueueReceive(queue, &ev, 1) == pdTRUE) {
|
||||
// Process event
|
||||
processObjEvent(&ev);
|
||||
}
|
||||
#endif /* if defined(PIOS_TELEM_PRIORITY_QUEUE) */
|
||||
}
|
||||
}
|
||||
|
||||
@ -424,12 +455,12 @@ static void radioRxTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
// Task loop
|
||||
while (1) {
|
||||
if (telemetryPort) {
|
||||
if (radioPort) {
|
||||
// Block until data are available
|
||||
uint8_t serial_data[1];
|
||||
uint16_t bytes_to_process;
|
||||
|
||||
bytes_to_process = PIOS_COM_ReceiveBuffer(telemetryPort, serial_data, sizeof(serial_data), 500);
|
||||
bytes_to_process = PIOS_COM_ReceiveBuffer(radioPort, serial_data, sizeof(serial_data), 500);
|
||||
if (bytes_to_process > 0) {
|
||||
for (uint8_t i = 0; i < bytes_to_process; i++) {
|
||||
UAVTalkProcessInputStream(radioUavTalkCon, serial_data[i]);
|
||||
@ -440,6 +471,21 @@ static void radioRxTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Transmit data buffer to the radioport.
|
||||
* \param[in] data Data buffer to send
|
||||
* \param[in] length Length of buffer
|
||||
* \return -1 on failure
|
||||
* \return number of bytes transmitted on success
|
||||
*/
|
||||
static int32_t transmitRadioData(uint8_t *data, int32_t length)
|
||||
{
|
||||
if (radioPort) {
|
||||
return PIOS_COM_SendBuffer(radioPort, data, length);
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
/**
|
||||
@ -544,12 +590,10 @@ static void updateTelemetryStats()
|
||||
uint32_t timeNow;
|
||||
|
||||
// Get stats
|
||||
UAVTalkGetStats(uavTalkCon, &utalkStats);
|
||||
UAVTalkGetStats(uavTalkCon, &utalkStats, true);
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
UAVTalkAddStats(radioUavTalkCon, &utalkStats);
|
||||
UAVTalkResetStats(radioUavTalkCon);
|
||||
UAVTalkAddStats(radioUavTalkCon, &utalkStats, true);
|
||||
#endif
|
||||
UAVTalkResetStats(uavTalkCon);
|
||||
|
||||
// Get object data
|
||||
FlightTelemetryStatsGet(&flightStats);
|
||||
@ -678,17 +722,25 @@ static void updateSettings()
|
||||
* Determine input/output com port as highest priority available
|
||||
* @param[in] input Returns the approproate input com port if true, else the appropriate output com port
|
||||
*/
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
static uint32_t getComPort(bool input)
|
||||
{
|
||||
#ifndef PIOS_INCLUDE_RFM22B
|
||||
input = false;
|
||||
#else
|
||||
static uint32_t getComPort(__attribute__((unused)) bool input)
|
||||
#endif
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
// if USB is connected, USB takes precedence for telemetry
|
||||
if (PIOS_COM_Available(PIOS_COM_TELEM_USB)) {
|
||||
return PIOS_COM_TELEM_USB;
|
||||
} else
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
if (!input && PIOS_COM_Available(telemetryPort)) {
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
// PIOS_COM_RF input is handled by a separate RX thread and therefore must be ignored
|
||||
if (input && telemetryPort == PIOS_COM_RF) {
|
||||
return 0;
|
||||
} else
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
if (PIOS_COM_Available(telemetryPort)) {
|
||||
return telemetryPort;
|
||||
} else {
|
||||
return 0;
|
||||
|
@ -327,7 +327,7 @@ static void updatePIDs(UAVObjEvent *ev)
|
||||
break;
|
||||
|
||||
case 2:
|
||||
StabilizationSettingsBank2Set((StabilizationSettingsBank2Data *)&bank);
|
||||
StabilizationSettingsBank3Set((StabilizationSettingsBank3Data *)&bank);
|
||||
break;
|
||||
|
||||
default:
|
||||
|
@ -470,48 +470,14 @@ void updateEndpointVelocity()
|
||||
float eastCommand;
|
||||
float downCommand;
|
||||
|
||||
float northPos = 0, eastPos = 0, downPos = 0;
|
||||
switch (vtolpathfollowerSettings.PositionSource) {
|
||||
case VTOLPATHFOLLOWERSETTINGS_POSITIONSOURCE_EKF:
|
||||
northPos = positionState.North;
|
||||
eastPos = positionState.East;
|
||||
downPos = positionState.Down;
|
||||
break;
|
||||
case VTOLPATHFOLLOWERSETTINGS_POSITIONSOURCE_GPSPOS:
|
||||
{
|
||||
// this used to work with the NEDposition UAVObject
|
||||
// however this UAVObject has been removed
|
||||
GPSPositionSensorData gpsPosition;
|
||||
GPSPositionSensorGet(&gpsPosition);
|
||||
HomeLocationData homeLocation;
|
||||
HomeLocationGet(&homeLocation);
|
||||
float lat = DEG2RAD(homeLocation.Latitude / 10.0e6f);
|
||||
float alt = homeLocation.Altitude;
|
||||
float T[3] = { alt + 6.378137E6f,
|
||||
cosf(lat) * (alt + 6.378137E6f),
|
||||
-1.0f };
|
||||
float NED[3] = { T[0] * (DEG2RAD((gpsPosition.Latitude - homeLocation.Latitude) / 10.0e6f)),
|
||||
T[1] * (DEG2RAD((gpsPosition.Longitude - homeLocation.Longitude) / 10.0e6f)),
|
||||
T[2] * ((gpsPosition.Altitude + gpsPosition.GeoidSeparation - homeLocation.Altitude)) };
|
||||
|
||||
northPos = NED[0];
|
||||
eastPos = NED[1];
|
||||
downPos = NED[2];
|
||||
}
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
|
||||
// Compute desired north command
|
||||
northError = pathDesired.End.North - northPos;
|
||||
northError = pathDesired.End.North - positionState.North;
|
||||
northPosIntegral = bound(northPosIntegral + northError * dT * vtolpathfollowerSettings.HorizontalPosPI.Ki,
|
||||
-vtolpathfollowerSettings.HorizontalPosPI.ILimit,
|
||||
vtolpathfollowerSettings.HorizontalPosPI.ILimit);
|
||||
northCommand = (northError * vtolpathfollowerSettings.HorizontalPosPI.Kp + northPosIntegral);
|
||||
|
||||
eastError = pathDesired.End.East - eastPos;
|
||||
eastError = pathDesired.End.East - positionState.East;
|
||||
eastPosIntegral = bound(eastPosIntegral + eastError * dT * vtolpathfollowerSettings.HorizontalPosPI.Ki,
|
||||
-vtolpathfollowerSettings.HorizontalPosPI.ILimit,
|
||||
vtolpathfollowerSettings.HorizontalPosPI.ILimit);
|
||||
@ -527,7 +493,7 @@ void updateEndpointVelocity()
|
||||
velocityDesired.North = northCommand * scale;
|
||||
velocityDesired.East = eastCommand * scale;
|
||||
|
||||
downError = pathDesired.End.Down - downPos;
|
||||
downError = pathDesired.End.Down - positionState.Down;
|
||||
downPosIntegral = bound(downPosIntegral + downError * dT * vtolpathfollowerSettings.VerticalPosPI.Ki,
|
||||
-vtolpathfollowerSettings.VerticalPosPI.ILimit,
|
||||
vtolpathfollowerSettings.VerticalPosPI.ILimit);
|
||||
@ -595,12 +561,12 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
|
||||
|
||||
float northVel = 0, eastVel = 0, downVel = 0;
|
||||
switch (vtolpathfollowerSettings.VelocitySource) {
|
||||
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_EKF:
|
||||
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_STATE_ESTIMATION:
|
||||
northVel = velocityState.North;
|
||||
eastVel = velocityState.East;
|
||||
downVel = velocityState.Down;
|
||||
break;
|
||||
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_NEDVEL:
|
||||
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_GPS_VELNED:
|
||||
{
|
||||
GPSVelocitySensorData gpsVelocity;
|
||||
GPSVelocitySensorGet(&gpsVelocity);
|
||||
@ -609,7 +575,7 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
|
||||
downVel = gpsVelocity.Down;
|
||||
}
|
||||
break;
|
||||
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_GPSPOS:
|
||||
case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_GPS_GROUNDSPEED:
|
||||
{
|
||||
GPSPositionSensorData gpsPosition;
|
||||
GPSPositionSensorGet(&gpsPosition);
|
||||
|
@ -33,7 +33,7 @@
|
||||
|
||||
// Private constants
|
||||
#define STACK_SAFETYCOUNT 16
|
||||
#define STACK_SIZE (384 + STACK_SAFETYSIZE)
|
||||
#define STACK_SIZE (190 + STACK_SAFETYSIZE)
|
||||
#define STACK_SAFETYSIZE 8
|
||||
#define MAX_SLEEP 1000
|
||||
|
||||
|
84
flight/pios/common/pios_ms4525do.c
Normal file
84
flight/pios/common/pios_ms4525do.c
Normal file
@ -0,0 +1,84 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_MS4525DO MS4525DO Functions
|
||||
* @brief Hardware functions to deal with the PixHawk Airspeed Sensor based on MS4525DO
|
||||
* @{
|
||||
*
|
||||
* @file pios_ms4525do.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief PixHawk MS4525DO Airspeed Sensor Driver
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
******************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#include "pios.h"
|
||||
|
||||
#ifdef PIOS_INCLUDE_MS4525DO
|
||||
|
||||
/* Local Defs and Variables */
|
||||
|
||||
|
||||
static int8_t PIOS_MS4525DO_ReadI2C(uint8_t *buffer, uint8_t len)
|
||||
{
|
||||
const struct pios_i2c_txn txn_list[] = {
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = MS4525DO_I2C_ADDR,
|
||||
.rw = PIOS_I2C_TXN_READ,
|
||||
.len = len,
|
||||
.buf = buffer,
|
||||
}
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MS4525DO_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
|
||||
// values has to ba an arrray with two elements
|
||||
// values stay untouched on error
|
||||
int8_t PIOS_MS4525DO_Read(uint16_t *values)
|
||||
{
|
||||
uint8_t data[4];
|
||||
int8_t retVal = PIOS_MS4525DO_ReadI2C(data, sizeof(data));
|
||||
|
||||
uint8_t status = data[0] & 0xC0;
|
||||
|
||||
if (status == 0x80) {
|
||||
/* stale data */
|
||||
return -5;
|
||||
} else if (status == 0xC0) {
|
||||
/* device probably broken */
|
||||
return -6;
|
||||
}
|
||||
|
||||
/* differential pressure */
|
||||
values[0] = (data[0] << 8);
|
||||
values[0] += data[1];
|
||||
|
||||
/* temperature */
|
||||
values[1] = (data[2] << 8);
|
||||
values[1] += data[3];
|
||||
values[1] = (values[1] >> 5);
|
||||
|
||||
return retVal;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_MS4525DO */
|
@ -139,7 +139,11 @@ static const uint8_t FULL_PREAMBLE[FIFO_SIZE] = {
|
||||
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE,
|
||||
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE
|
||||
}; // 64 bytes
|
||||
static const uint8_t HEADER[(TX_PREAMBLE_NIBBLES + 1) / 2 + 2] = { PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, SYNC_BYTE_1, SYNC_BYTE_2 };
|
||||
|
||||
static const uint8_t HEADER[(TX_PREAMBLE_NIBBLES + 1) / 2 + 2] = {
|
||||
PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, SYNC_BYTE_1, SYNC_BYTE_2
|
||||
};
|
||||
|
||||
static const uint8_t OUT_FF[64] = {
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
@ -150,8 +154,21 @@ static const uint8_t OUT_FF[64] = {
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF
|
||||
};
|
||||
|
||||
// The randomized channel list.
|
||||
static const uint8_t channel_list[] = { 68, 34, 2, 184, 166, 94, 204, 18, 47, 118, 239, 176, 5, 213, 218, 186, 104, 160, 199, 209, 231, 197, 92, 191, 88, 129, 40, 19, 93, 200, 156, 14, 247, 182, 193, 194, 208, 210, 248, 76, 244, 48, 179, 105, 25, 74, 155, 203, 39, 97, 195, 81, 83, 180, 134, 172, 235, 132, 198, 119, 207, 154, 0, 61, 140, 171, 245, 26, 95, 3, 22, 62, 169, 55, 127, 144, 45, 33, 170, 91, 158, 167, 63, 201, 41, 21, 190, 51, 103, 49, 189, 205, 240, 89, 181, 149, 6, 157, 249, 230, 115, 72, 163, 17, 29, 99, 28, 117, 219, 73, 78, 53, 69, 216, 161, 124, 110, 242, 214, 145, 13, 11, 220, 113, 138, 58, 54, 162, 237, 37, 152, 187, 232, 77, 126, 85, 38, 238, 173, 23, 188, 100, 131, 226, 31, 9, 114, 106, 221, 42, 233, 139, 4, 241, 96, 211, 8, 98, 121, 147, 24, 217, 27, 87, 122, 125, 135, 148, 178, 71, 206, 57, 141, 35, 30, 246, 159, 16, 32, 15, 229, 20, 12, 223, 150, 101, 79, 56, 102, 111, 174, 236, 137, 143, 52, 225, 64, 224, 112, 168, 243, 130, 108, 202, 123, 146, 228, 75, 46, 153, 7, 192, 175, 151, 222, 59, 82, 90, 1, 65, 109, 44, 165, 84, 43, 36, 128, 196, 67, 80, 136, 86, 70, 234, 66, 185, 10, 164, 177, 116, 50, 107, 183, 215, 212, 60, 227, 133, 120, 142 };
|
||||
static const uint8_t channel_list[] = {
|
||||
68, 34, 2, 184, 166, 94, 204, 18, 47, 118, 239, 176, 5, 213, 218, 186, 104, 160, 199, 209, 231, 197, 92,
|
||||
191, 88, 129, 40, 19, 93, 200, 156, 14, 247, 182, 193, 194, 208, 210, 248, 76, 244, 48, 179, 105, 25, 74,
|
||||
155, 203, 39, 97, 195, 81, 83, 180, 134, 172, 235, 132, 198, 119, 207, 154, 0, 61, 140, 171, 245, 26, 95,
|
||||
3, 22, 62, 169, 55, 127, 144, 45, 33, 170, 91, 158, 167, 63, 201, 41, 21, 190, 51, 103, 49, 189, 205,
|
||||
240, 89, 181, 149, 6, 157, 249, 230, 115, 72, 163, 17, 29, 99, 28, 117, 219, 73, 78, 53, 69, 216, 161,
|
||||
124, 110, 242, 214, 145, 13, 11, 220, 113, 138, 58, 54, 162, 237, 37, 152, 187, 232, 77, 126, 85, 38, 238,
|
||||
173, 23, 188, 100, 131, 226, 31, 9, 114, 106, 221, 42, 233, 139, 4, 241, 96, 211, 8, 98, 121, 147, 24,
|
||||
217, 27, 87, 122, 125, 135, 148, 178, 71, 206, 57, 141, 35, 30, 246, 159, 16, 32, 15, 229, 20, 12, 223,
|
||||
150, 101, 79, 56, 102, 111, 174, 236, 137, 143, 52, 225, 64, 224, 112, 168, 243, 130, 108, 202, 123, 146, 228,
|
||||
75, 46, 153, 7, 192, 175, 151, 222, 59, 82, 90, 1, 65, 109, 44, 165, 84, 43, 36, 128, 196, 67, 80,
|
||||
136, 86, 70, 234, 66, 185, 10, 164, 177, 116, 50, 107, 183, 215, 212, 60, 227, 133, 120, 14
|
||||
};
|
||||
|
||||
/* Local function forwared declarations */
|
||||
static void pios_rfm22_task(void *parameters);
|
||||
|
@ -92,8 +92,12 @@ struct pios_i2c_adapter {
|
||||
uint8_t busy;
|
||||
#endif
|
||||
|
||||
bool bus_error;
|
||||
bool nack;
|
||||
/* variables for transfer timeouts */
|
||||
uint32_t transfer_delay_uS; // approx time to transfer one byte, calculated later basen on setting use here time based on 100 kbits/s
|
||||
uint32_t transfer_timeout_ticks; // take something tha makes sense for small transaction, calculated later based upon transmission desired
|
||||
|
||||
bool bus_error;
|
||||
bool nack;
|
||||
|
||||
volatile enum i2c_adapter_state curr_state;
|
||||
const struct pios_i2c_txn *first_txn;
|
||||
|
45
flight/pios/inc/pios_ms4525do.h
Normal file
45
flight/pios/inc/pios_ms4525do.h
Normal file
@ -0,0 +1,45 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_MS4525DO MS4525DO Functions
|
||||
* @brief Hardware functions to deal with the PixHawk Airspeed Sensor based on MS4525DO
|
||||
* @{
|
||||
*
|
||||
* @file pios_ms4525do.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief PixHawk MS4525DO Airspeed Sensor Driver
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
******************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_MS4525DO_H
|
||||
#define PIOS_MS4525DO_H
|
||||
|
||||
// Interface Type I chip
|
||||
#define MS4525DO_I2C_ADDR 0x28
|
||||
// Interface Type J chip
|
||||
/* #define MS4525DO_I2C_ADDR 0x36 */
|
||||
// Interface Type K chip
|
||||
/* #define MS4525DO_I2C_ADDR 0x46 */
|
||||
|
||||
|
||||
extern int8_t PIOS_MS4525DO_Request(void);
|
||||
extern int8_t PIOS_MS4525DO_Read(uint16_t *values);
|
||||
|
||||
#endif /* PIOS_MS4525DO_H */
|
@ -229,6 +229,12 @@
|
||||
#include <pios_etasv3.h>
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_MS4525DO
|
||||
/* PixHawk Airspeed Sensor based on MS4525DO */
|
||||
#include <pios_ms4525do.h>
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef PIOS_INCLUDE_HCSR04
|
||||
/* HC-SR04 Ultrasonic Sensor */
|
||||
#include <pios_hcsr04.h>
|
||||
|
@ -29,27 +29,24 @@
|
||||
/* -------------- Buffer Description Table -----------------*/
|
||||
/*-------------------------------------------------------------*/
|
||||
/* buffer table base address */
|
||||
/* buffer table base address */
|
||||
#define BTABLE_ADDRESS (0x00)
|
||||
|
||||
/* EP0 */
|
||||
/* EP0 (Control) */
|
||||
/* rx/tx buffer base address */
|
||||
#define ENDP0_RXADDR (0x20)
|
||||
#define ENDP0_TXADDR (0x40)
|
||||
|
||||
/* EP1 */
|
||||
/* EP1 (HID) */
|
||||
/* rx/tx buffer base address */
|
||||
#define ENDP1_TXADDR (0x60)
|
||||
// fix the F1 USB issue
|
||||
//#define ENDP1_RXADDR (0x80)
|
||||
#define ENDP1_RXADDR (0xa0)
|
||||
#define ENDP1_RXADDR (0xA0)
|
||||
|
||||
/* EP2 */
|
||||
/* EP2 (CDC Call Control) */
|
||||
/* rx/tx buffer base address */
|
||||
#define ENDP2_TXADDR (0x100)
|
||||
#define ENDP2_RXADDR (0x140)
|
||||
|
||||
/* EP3 */
|
||||
/* EP3 (CDC Data) */
|
||||
/* rx/tx buffer base address */
|
||||
#define ENDP3_TXADDR (0x180)
|
||||
#define ENDP3_RXADDR (0x1C0)
|
@ -404,8 +404,17 @@ static void go_starting(struct pios_i2c_adapter *i2c_adapter)
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn >= i2c_adapter->first_txn);
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn);
|
||||
|
||||
i2c_adapter->active_byte = &(i2c_adapter->active_txn->buf[0]);
|
||||
i2c_adapter->last_byte = &(i2c_adapter->active_txn->buf[i2c_adapter->active_txn->len - 1]);
|
||||
// check for an empty read/write
|
||||
if (i2c_adapter->active_txn->buf != NULL && i2c_adapter->active_txn->len != 0) {
|
||||
// Data available
|
||||
i2c_adapter->active_byte = &(i2c_adapter->active_txn->buf[0]);
|
||||
i2c_adapter->last_byte = &(i2c_adapter->active_txn->buf[i2c_adapter->active_txn->len - 1]);
|
||||
} else {
|
||||
// No Data available => Empty read/write
|
||||
i2c_adapter->last_byte = NULL;
|
||||
i2c_adapter->active_byte = i2c_adapter->last_byte + 1;
|
||||
}
|
||||
|
||||
|
||||
I2C_GenerateSTART(i2c_adapter->cfg->regs, ENABLE);
|
||||
if (i2c_adapter->active_txn->rw == PIOS_I2C_TXN_READ) {
|
||||
@ -924,9 +933,9 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
if (!PIOS_I2C_validate(i2c_adapter)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
PIOS_DEBUG_Assert(txn_list);
|
||||
PIOS_DEBUG_Assert(num_txns);
|
||||
@ -968,6 +977,14 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
|
||||
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
|
||||
#endif
|
||||
|
||||
// Estimate bytes of transmission. Per txns: 1 adress byte + length
|
||||
i2c_adapter->transfer_timeout_ticks = num_txns;
|
||||
for (uint32_t i = 0; i < num_txns; i++) {
|
||||
i2c_adapter->transfer_timeout_ticks += txn_list[i].len;
|
||||
}
|
||||
// timeout if it takes eight times the expected time
|
||||
i2c_adapter->transfer_timeout_ticks <<= 3;
|
||||
|
||||
i2c_adapter->bus_error = false;
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START);
|
||||
|
||||
@ -983,7 +1000,15 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
|
||||
|
||||
/* Spin waiting for the transfer to finish */
|
||||
while (!i2c_adapter_fsm_terminated(i2c_adapter)) {
|
||||
;
|
||||
/* sleep 9 clock ticks (1 byte), because FSM can't be faster than one byte
|
||||
FIXME: clock streching could make problems, but citing NPX: alsmost no slave device implements clock stretching
|
||||
three times the expected time should cover clock delay */
|
||||
PIOS_DELAY_WaituS(i2c_adapter->transfer_delay_uS);
|
||||
|
||||
i2c_adapter->transfer_timeout_ticks--;
|
||||
if (i2c_adapter->transfer_timeout_ticks == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (i2c_adapter_wait_for_stopped(i2c_adapter)) {
|
||||
@ -1010,9 +1035,9 @@ void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id)
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
if (!PIOS_I2C_validate(i2c_adapter)) {
|
||||
return;
|
||||
}
|
||||
|
||||
uint32_t event = I2C_GetLastEvent(i2c_adapter->cfg->regs);
|
||||
|
||||
@ -1136,9 +1161,10 @@ void PIOS_I2C_ER_IRQ_Handler(uint32_t i2c_id)
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
if (!PIOS_I2C_validate(i2c_adapter)) {
|
||||
return;
|
||||
}
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
uint32_t event = I2C_GetLastEvent(i2c_adapter->cfg->regs);
|
||||
|
@ -32,8 +32,6 @@
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "stm32f4xx.h"
|
||||
|
||||
#include "usb_conf.h"
|
||||
|
||||
/** @addtogroup USB_OTG_DRIVER
|
||||
* @{
|
||||
*/
|
||||
|
@ -94,26 +94,19 @@ static void go_bus_error(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_stopping(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_stopped(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_starting(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_any_txn_addr(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_more_txn_pre_one(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_any_txn_pre_first(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_any_txn_pre_middle(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_more_txn_pre_last(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_any_txn_post_last(struct pios_i2c_adapter *i2c_adapter);
|
||||
|
||||
static void go_r_any_txn_addr(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_more_txn_pre_one(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_last_txn_pre_one(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_any_txn_pre_first(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_any_txn_pre_middle(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_last_txn_pre_last(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_more_txn_pre_last(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_r_any_txn_post_last(struct pios_i2c_adapter *i2c_adapter);
|
||||
|
||||
static void go_w_any_txn_addr(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_w_any_txn_middle(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_w_more_txn_last(struct pios_i2c_adapter *i2c_adapter);
|
||||
|
||||
static void go_w_any_txn_addr(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_w_any_txn_middle(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void go_w_last_txn_last(struct pios_i2c_adapter *i2c_adapter);
|
||||
|
||||
static void go_nack(struct pios_i2c_adapter *i2c_adapter);
|
||||
@ -414,8 +407,16 @@ static void go_starting(struct pios_i2c_adapter *i2c_adapter)
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn >= i2c_adapter->first_txn);
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn);
|
||||
|
||||
i2c_adapter->active_byte = &(i2c_adapter->active_txn->buf[0]);
|
||||
i2c_adapter->last_byte = &(i2c_adapter->active_txn->buf[i2c_adapter->active_txn->len - 1]);
|
||||
// check for an empty read/write
|
||||
if (i2c_adapter->active_txn->buf != NULL && i2c_adapter->active_txn->len != 0) {
|
||||
// Data available
|
||||
i2c_adapter->active_byte = &(i2c_adapter->active_txn->buf[0]);
|
||||
i2c_adapter->last_byte = &(i2c_adapter->active_txn->buf[i2c_adapter->active_txn->len - 1]);
|
||||
} else {
|
||||
// No Data available => Empty read/write
|
||||
i2c_adapter->last_byte = NULL;
|
||||
i2c_adapter->active_byte = i2c_adapter->last_byte + 1;
|
||||
}
|
||||
|
||||
I2C_GenerateSTART(i2c_adapter->cfg->regs, ENABLE);
|
||||
if (i2c_adapter->active_txn->rw == PIOS_I2C_TXN_READ) {
|
||||
@ -753,6 +754,11 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
|
||||
/* Initialize the I2C block */
|
||||
I2C_Init(i2c_adapter->cfg->regs, (I2C_InitTypeDef *)&(i2c_adapter->cfg->init));
|
||||
|
||||
// for delays during transfer timeouts
|
||||
// one tick correspond to transmission of 1 byte i.e. 9 clock ticks
|
||||
i2c_adapter->transfer_delay_uS = 9000000 / (((I2C_InitTypeDef *)&(i2c_adapter->cfg->init))->I2C_ClockSpeed);
|
||||
|
||||
|
||||
if (i2c_adapter->cfg->regs->SR2 & I2C_FLAG_BUSY) {
|
||||
/* Reset the I2C block */
|
||||
I2C_SoftwareResetCmd(i2c_adapter->cfg->regs, ENABLE);
|
||||
@ -760,7 +766,6 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
|
||||
}
|
||||
}
|
||||
|
||||
#include <pios_i2c_priv.h>
|
||||
|
||||
/* Return true if the FSM is in a terminal state */
|
||||
static bool i2c_adapter_fsm_terminated(struct pios_i2c_adapter *i2c_adapter)
|
||||
@ -788,9 +793,18 @@ static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter)
|
||||
xSemaphoreGive(i2c_adapter->sem_ready);
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
/* transfer_timeout_ticks is set by PIOS_I2C_Transfer_Callback */
|
||||
/* Spin waiting for the transfer to finish */
|
||||
while (!i2c_adapter_fsm_terminated(i2c_adapter)) {
|
||||
;
|
||||
// sleep 1 byte, as FSM can't be faster
|
||||
// FIXME: clock stretching could make problems, but citing NPX: alsmost no slave device implements clock stretching
|
||||
// three times the expected time should cover clock delay
|
||||
PIOS_DELAY_WaituS(i2c_adapter->transfer_delay_uS);
|
||||
|
||||
i2c_adapter->transfer_timeout_ticks--;
|
||||
if (i2c_adapter->transfer_timeout_ticks == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (i2c_adapter_wait_for_stopped(i2c_adapter)) {
|
||||
@ -956,6 +970,7 @@ int32_t PIOS_I2C_Init(uint32_t *i2c_id, const struct pios_i2c_adapter_cfg *cfg)
|
||||
NVIC_Init((NVIC_InitTypeDef *)&(i2c_adapter->cfg->event.init));
|
||||
NVIC_Init((NVIC_InitTypeDef *)&(i2c_adapter->cfg->error.init));
|
||||
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
|
||||
@ -967,9 +982,9 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
if (!PIOS_I2C_validate(i2c_adapter)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
PIOS_DEBUG_Assert(txn_list);
|
||||
PIOS_DEBUG_Assert(num_txns);
|
||||
@ -1001,12 +1016,20 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
/* Make sure the done/ready semaphore is consumed before we start */
|
||||
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
|
||||
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
|
||||
#endif
|
||||
|
||||
// Estimate bytes of transmission. Per txns: 1 adress byte + length
|
||||
i2c_adapter->transfer_timeout_ticks = num_txns;
|
||||
for (uint32_t i = 0; i < num_txns; i++) {
|
||||
i2c_adapter->transfer_timeout_ticks += txn_list[i].len;
|
||||
}
|
||||
// timeout if it takes eight times the expected time
|
||||
i2c_adapter->transfer_timeout_ticks <<= 3;
|
||||
|
||||
i2c_adapter->callback = NULL;
|
||||
i2c_adapter->bus_error = false;
|
||||
i2c_adapter->nack = false;
|
||||
i2c_adapter->nack = false;
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START);
|
||||
|
||||
/* Wait for the transfer to complete */
|
||||
@ -1017,7 +1040,15 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
|
||||
|
||||
/* Spin waiting for the transfer to finish */
|
||||
while (!i2c_adapter_fsm_terminated(i2c_adapter)) {
|
||||
;
|
||||
/* sleep 9 clock ticks (1 byte), because FSM can't be faster than one byte
|
||||
FIXME: clock stretching could make problems, but citing NPX: alsmost no slave device implements clock stretching
|
||||
three times the expected time should cover clock delay */
|
||||
PIOS_DELAY_WaituS(i2c_adapter->transfer_delay_uS);
|
||||
|
||||
i2c_adapter->transfer_timeout_ticks--;
|
||||
if (i2c_adapter->transfer_timeout_ticks == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (i2c_adapter_wait_for_stopped(i2c_adapter)) {
|
||||
@ -1048,9 +1079,10 @@ int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn tx
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
if (!PIOS_I2C_validate(i2c_adapter)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
PIOS_Assert(valid)
|
||||
PIOS_Assert(callback);
|
||||
|
||||
PIOS_DEBUG_Assert(txn_list);
|
||||
@ -1080,9 +1112,18 @@ int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn tx
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
/* Make sure the done/ready semaphore is consumed before we start */
|
||||
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
|
||||
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
|
||||
#endif
|
||||
|
||||
// used in the i2c_adapter_callback_handler function
|
||||
// Estimate bytes of transmission. Per txns: 1 adress byte + length
|
||||
i2c_adapter->transfer_timeout_ticks = num_txns;
|
||||
for (uint32_t i = 0; i < num_txns; i++) {
|
||||
i2c_adapter->transfer_timeout_ticks += txn_list[i].len;
|
||||
}
|
||||
// timeout if it takes eight times the expected time
|
||||
i2c_adapter->transfer_timeout_ticks <<= 3;
|
||||
|
||||
i2c_adapter->callback = callback;
|
||||
i2c_adapter->bus_error = false;
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START);
|
||||
@ -1094,9 +1135,9 @@ void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id)
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
if (!PIOS_I2C_validate(i2c_adapter)) {
|
||||
return;
|
||||
}
|
||||
|
||||
uint32_t event = I2C_GetLastEvent(i2c_adapter->cfg->regs);
|
||||
|
||||
@ -1204,9 +1245,9 @@ void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id)
|
||||
/* Ignore this event and wait for TRANSMITTED in case we can't keep up */
|
||||
goto skip_event;
|
||||
break;
|
||||
case 0x30084: /* Occurs between byte tranmistted and master mode selected */
|
||||
case 0x30000: /* Need to throw away this spurious event */
|
||||
case 0x30403 & EVENT_MASK: /* Detected this after got a NACK, probably stop bit */
|
||||
case 0x30084: /* BUSY + MSL + TXE + BFT Occurs between byte transmitted and master mode selected */
|
||||
case 0x30000: /* BUSY + MSL Need to throw away this spurious event */
|
||||
case 0x30403 & EVENT_MASK: /* BUSY + MSL + SB + ADDR Detected this after got a NACK, probably stop bit */
|
||||
goto skip_event;
|
||||
break;
|
||||
default:
|
||||
@ -1227,16 +1268,15 @@ void PIOS_I2C_ER_IRQ_Handler(uint32_t i2c_id)
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
if (!PIOS_I2C_validate(i2c_adapter)) {
|
||||
return;
|
||||
}
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
uint32_t event = I2C_GetLastEvent(i2c_adapter->cfg->regs);
|
||||
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_erirq_history[i2c_erirq_history_pointer] = event;
|
||||
i2c_erirq_history_pointer = (i2c_erirq_history_pointer + 1) % 5;
|
||||
|
||||
#endif
|
||||
|
||||
if (event & I2C_FLAG_AF) {
|
||||
|
@ -73,7 +73,7 @@ uint16_t PIOS_WDG_Init()
|
||||
delay = 0x0fff;
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_WDG)
|
||||
DBGMCU_Config(DBGMCU_IWDG_STOP, ENABLE); // make the watchdog stop counting in debug mode
|
||||
DBGMCU_APB1PeriphConfig(DBGMCU_IWDG_STOP, ENABLE); // OP-1272 : write in APB1 register
|
||||
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable);
|
||||
IWDG_SetPrescaler(IWDG_Prescaler_16);
|
||||
IWDG_SetReload(delay);
|
||||
|
@ -31,6 +31,7 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 2
|
||||
|
@ -23,7 +23,7 @@
|
||||
/* Notes: We use 5 task priorities */
|
||||
|
||||
#define configUSE_PREEMPTION 1
|
||||
#define configUSE_IDLE_HOOK 1
|
||||
#define configUSE_IDLE_HOOK 0
|
||||
#define configUSE_TICK_HOOK 0
|
||||
#define configUSE_MALLOC_FAILED_HOOK 1
|
||||
#define configCPU_CLOCK_HZ ((unsigned long)72000000)
|
||||
@ -31,7 +31,7 @@
|
||||
#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5)
|
||||
#define configMINIMAL_STACK_SIZE ((unsigned short)48)
|
||||
#define configTOTAL_HEAP_SIZE ((size_t)(53 * 256))
|
||||
#define configMAX_TASK_NAME_LEN (16)
|
||||
#define configMAX_TASK_NAME_LEN (6)
|
||||
#define configUSE_TRACE_FACILITY 0
|
||||
#define configUSE_16_BIT_TICKS 0
|
||||
#define configIDLE_SHOULD_YIELD 0
|
||||
@ -39,7 +39,7 @@
|
||||
#define configUSE_RECURSIVE_MUTEXES 1
|
||||
#define configUSE_COUNTING_SEMAPHORES 0
|
||||
#define configUSE_ALTERNATIVE_API 0
|
||||
#define configQUEUE_REGISTRY_SIZE 10
|
||||
#define configQUEUE_REGISTRY_SIZE 0
|
||||
|
||||
/* Co-routine definitions. */
|
||||
#define configUSE_CO_ROUTINES 0
|
||||
@ -52,10 +52,10 @@
|
||||
#define INCLUDE_uxTaskPriorityGet 1
|
||||
#define INCLUDE_vTaskDelete 1
|
||||
#define INCLUDE_vTaskCleanUpResources 0
|
||||
#define INCLUDE_vTaskSuspend 1
|
||||
#define INCLUDE_vTaskSuspend 0
|
||||
#define INCLUDE_vTaskDelayUntil 1
|
||||
#define INCLUDE_vTaskDelay 1
|
||||
#define INCLUDE_xTaskGetSchedulerState 1
|
||||
#define INCLUDE_xTaskGetSchedulerState 0
|
||||
#define INCLUDE_xTaskGetCurrentTaskHandle 1
|
||||
#define INCLUDE_uxTaskGetStackHighWaterMark 1
|
||||
|
||||
|
@ -144,7 +144,7 @@
|
||||
|
||||
/* Stabilization options */
|
||||
/* #define PIOS_QUATERNION_STABILIZATION */
|
||||
|
||||
#define PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
/* Performance counters */
|
||||
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998
|
||||
|
||||
@ -157,15 +157,19 @@
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
/* Task stack sizes */
|
||||
#define PIOS_ACTUATOR_STACK_SIZE 1020
|
||||
#define PIOS_MANUAL_STACK_SIZE 850
|
||||
#define PIOS_ACTUATOR_STACK_SIZE 820
|
||||
#define PIOS_MANUAL_STACK_SIZE 635
|
||||
#define PIOS_RECEIVER_STACK_SIZE 620
|
||||
#define PIOS_STABILIZATION_STACK_SIZE 780
|
||||
|
||||
#ifdef DIAG_TASKS
|
||||
#define PIOS_SYSTEM_STACK_SIZE 720
|
||||
#define PIOS_SYSTEM_STACK_SIZE 740
|
||||
#else
|
||||
#define PIOS_SYSTEM_STACK_SIZE 660
|
||||
#endif
|
||||
#define PIOS_TELEM_STACK_SIZE 540
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 160
|
||||
#define PIOS_TELEM_RX_STACK_SIZE 410
|
||||
#define PIOS_TELEM_TX_STACK_SIZE 560
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 95
|
||||
|
||||
/* This can't be too high to stop eventdispatcher thread overflowing */
|
||||
#define PIOS_EVENTDISAPTCHER_QUEUE 10
|
||||
|
@ -31,6 +31,7 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
|
||||
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
@ -31,6 +31,7 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 2
|
||||
|
@ -31,6 +31,7 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
|
||||
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
@ -31,6 +31,7 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 2
|
||||
|
@ -31,6 +31,7 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
|
||||
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
@ -31,6 +31,7 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 2
|
||||
|
@ -87,6 +87,8 @@
|
||||
#define PIOS_INCLUDE_MS5611
|
||||
#define PIOS_INCLUDE_MPXV
|
||||
#define PIOS_INCLUDE_ETASV3
|
||||
#define PIOS_INCLUDE_MS4525DO
|
||||
|
||||
/* #define PIOS_INCLUDE_HCSR04 */
|
||||
|
||||
/* PIOS receiver drivers */
|
||||
|
@ -31,6 +31,7 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
|
||||
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
@ -224,6 +224,7 @@ uint32_t pios_com_debug_id;
|
||||
uint32_t pios_com_gps_id = 0;
|
||||
uint32_t pios_com_telem_usb_id = 0;
|
||||
uint32_t pios_com_telem_rf_id = 0;
|
||||
uint32_t pios_com_rf_id = 0;
|
||||
uint32_t pios_com_bridge_id = 0;
|
||||
uint32_t pios_com_overo_id = 0;
|
||||
uint32_t pios_com_hkosd_id = 0;
|
||||
@ -231,7 +232,7 @@ uint32_t pios_com_hkosd_id = 0;
|
||||
uint32_t pios_com_vcp_id = 0;
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
#endif
|
||||
|
||||
uintptr_t pios_uavo_settings_fs_id;
|
||||
@ -753,11 +754,15 @@ void PIOS_Board_Init(void)
|
||||
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
|
||||
if (PIOS_COM_Init(&pios_com_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
|
||||
rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
/* Set Telemetry to use OPLinkMini if no other telemetry is configured (USB always overrides anyway) */
|
||||
if (!pios_com_telem_rf_id) {
|
||||
pios_com_telem_rf_id = pios_com_rf_id;
|
||||
}
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
|
||||
|
||||
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
|
||||
|
@ -119,12 +119,13 @@
|
||||
// PIOS_I2C
|
||||
// See also pios_board.c
|
||||
// ------------------------
|
||||
#define PIOS_I2C_MAX_DEVS 3
|
||||
#define PIOS_I2C_MAX_DEVS 3
|
||||
extern uint32_t pios_i2c_mag_pressure_adapter_id;
|
||||
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_pressure_adapter_id)
|
||||
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_pressure_adapter_id)
|
||||
extern uint32_t pios_i2c_flexiport_adapter_id;
|
||||
#define PIOS_I2C_FLEXI_ADAPTER (pios_i2c_flexiport_adapter_id)
|
||||
#define PIOS_I2C_ETASV3_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
|
||||
#define PIOS_I2C_FLEXI_ADAPTER (pios_i2c_flexiport_adapter_id)
|
||||
#define PIOS_I2C_ETASV3_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
|
||||
#define PIOS_I2C_MS4525DO_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
|
||||
|
||||
// -------------------------
|
||||
// PIOS_USART
|
||||
@ -140,6 +141,7 @@ extern uint32_t pios_i2c_flexiport_adapter_id;
|
||||
// -------------------------
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
extern uint32_t pios_com_telem_rf_id;
|
||||
extern uint32_t pios_com_rf_id;
|
||||
extern uint32_t pios_com_gps_id;
|
||||
extern uint32_t pios_com_telem_usb_id;
|
||||
extern uint32_t pios_com_bridge_id;
|
||||
@ -148,6 +150,7 @@ extern uint32_t pios_com_hkosd_id;
|
||||
#define PIOS_COM_GPS (pios_com_gps_id)
|
||||
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
|
||||
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
|
||||
#define PIOS_COM_RF (pios_com_rf_id)
|
||||
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
|
||||
#define PIOS_COM_VCP (pios_com_vcp_id)
|
||||
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
|
||||
|
@ -31,6 +31,7 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 2
|
||||
|
@ -29,25 +29,26 @@ USE_DSP_LIB ?= NO
|
||||
|
||||
# List of mandatory modules to include
|
||||
MODULES += Sensors
|
||||
MODULES += Attitude/revolution
|
||||
#MODULES += StateEstimation # use instead of Attitude
|
||||
#MODULES += Attitude/revolution
|
||||
MODULES += StateEstimation # use instead of Attitude
|
||||
MODULES += Altitude/revolution
|
||||
MODULES += Airspeed
|
||||
MODULES += AltitudeHold
|
||||
MODULES += Stabilization
|
||||
MODULES += Receiver
|
||||
MODULES += VtolPathFollower
|
||||
MODULES += ManualControl
|
||||
MODULES += Receiver
|
||||
MODULES += Actuator
|
||||
MODULES += GPS
|
||||
MODULES += TxPID
|
||||
MODULES += CameraStab
|
||||
MODULES += Battery
|
||||
MODULES += FirmwareIAP
|
||||
MODULES += PathPlanner
|
||||
MODULES += FixedWingPathFollower
|
||||
#MODULES += OveroSync ## OveroSync disabled until OP292 is fixed
|
||||
MODULES += Osd/osdoutout
|
||||
MODULES += Logging
|
||||
MODULES += Telemetry
|
||||
#MODULES += VtolPathFollower ## OP-700: VtolPathFollower disabled because its currently unsafe - remove this line once Sambas code has been merged
|
||||
#MODULES += Battery
|
||||
#MODULES += TxPID
|
||||
|
||||
OPTMODULES += ComUsbBridge
|
||||
|
||||
|
@ -1,9 +1,5 @@
|
||||
#####
|
||||
# Project: OpenPilot
|
||||
#
|
||||
# Makefile for OpenPilot UAVObject code
|
||||
#
|
||||
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011.
|
||||
# Copyright (c) 2009-2013, The OpenPilot Team, http://www.openpilot.org
|
||||
#
|
||||
# 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
|
||||
@ -18,11 +14,10 @@
|
||||
# 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
|
||||
#####
|
||||
#
|
||||
|
||||
# These are the UAVObjects supposed to be build as part of the OpenPilot target
|
||||
# (all architectures)
|
||||
|
||||
UAVOBJSRCFILENAMES =
|
||||
UAVOBJSRCFILENAMES += accelgyrosettings
|
||||
UAVOBJSRCFILENAMES += accessorydesired
|
||||
@ -35,12 +30,16 @@ UAVOBJSRCFILENAMES += gyrostate
|
||||
UAVOBJSRCFILENAMES += gyrosensor
|
||||
UAVOBJSRCFILENAMES += accelstate
|
||||
UAVOBJSRCFILENAMES += accelsensor
|
||||
UAVOBJSRCFILENAMES += magstate
|
||||
UAVOBJSRCFILENAMES += magsensor
|
||||
UAVOBJSRCFILENAMES += magstate
|
||||
UAVOBJSRCFILENAMES += barosensor
|
||||
UAVOBJSRCFILENAMES += airspeedsensor
|
||||
UAVOBJSRCFILENAMES += airspeedsettings
|
||||
UAVOBJSRCFILENAMES += airspeedstate
|
||||
UAVOBJSRCFILENAMES += debuglogsettings
|
||||
UAVOBJSRCFILENAMES += debuglogcontrol
|
||||
UAVOBJSRCFILENAMES += debuglogstatus
|
||||
UAVOBJSRCFILENAMES += debuglogentry
|
||||
UAVOBJSRCFILENAMES += flightbatterysettings
|
||||
UAVOBJSRCFILENAMES += firmwareiapobj
|
||||
UAVOBJSRCFILENAMES += flightbatterystate
|
||||
@ -67,6 +66,7 @@ UAVOBJSRCFILENAMES += mixersettings
|
||||
UAVOBJSRCFILENAMES += mixerstatus
|
||||
UAVOBJSRCFILENAMES += nedaccel
|
||||
UAVOBJSRCFILENAMES += objectpersistence
|
||||
UAVOBJSRCFILENAMES += oplinkreceiver
|
||||
UAVOBJSRCFILENAMES += overosyncstats
|
||||
UAVOBJSRCFILENAMES += overosyncsettings
|
||||
UAVOBJSRCFILENAMES += pathaction
|
||||
@ -102,6 +102,8 @@ UAVOBJSRCFILENAMES += receiveractivity
|
||||
UAVOBJSRCFILENAMES += cameradesired
|
||||
UAVOBJSRCFILENAMES += camerastabsettings
|
||||
UAVOBJSRCFILENAMES += altitudeholdsettings
|
||||
UAVOBJSRCFILENAMES += oplinksettings
|
||||
UAVOBJSRCFILENAMES += oplinkstatus
|
||||
UAVOBJSRCFILENAMES += altitudefiltersettings
|
||||
UAVOBJSRCFILENAMES += altitudeholddesired
|
||||
UAVOBJSRCFILENAMES += altitudeholdstatus
|
||||
@ -110,6 +112,7 @@ UAVOBJSRCFILENAMES += waypointactive
|
||||
UAVOBJSRCFILENAMES += poilocation
|
||||
UAVOBJSRCFILENAMES += poilearnsettings
|
||||
UAVOBJSRCFILENAMES += mpu6000settings
|
||||
UAVOBJSRCFILENAMES += txpidsettings
|
||||
|
||||
UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c )
|
||||
UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) )
|
||||
|
@ -31,6 +31,7 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
|
||||
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
@ -79,7 +79,6 @@ int32_t $(NAME)Initialize(void)
|
||||
void $(NAME)SetDefaults(UAVObjHandle obj, uint16_t instId)
|
||||
{
|
||||
$(NAME)Data data;
|
||||
UAVObjMetadata metadata;
|
||||
|
||||
// Initialize object fields to their default values
|
||||
UAVObjGetInstanceData(obj, instId, &data);
|
||||
@ -88,18 +87,21 @@ $(INITFIELDS)
|
||||
UAVObjSetInstanceData(obj, instId, &data);
|
||||
|
||||
// Initialize object metadata to their default values
|
||||
metadata.flags =
|
||||
$(FLIGHTACCESS) << UAVOBJ_ACCESS_SHIFT |
|
||||
$(GCSACCESS) << UAVOBJ_GCS_ACCESS_SHIFT |
|
||||
$(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT |
|
||||
$(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT |
|
||||
$(FLIGHTTELEM_UPDATEMODE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT |
|
||||
$(GCSTELEM_UPDATEMODE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT |
|
||||
$(LOGGING_UPDATEMODE) << UAVOBJ_LOGGING_UPDATE_MODE_SHIFT;
|
||||
metadata.telemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD);
|
||||
metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD);
|
||||
metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD);
|
||||
UAVObjSetMetadata(obj, &metadata);
|
||||
if ( instId == 0 ) {
|
||||
UAVObjMetadata metadata;
|
||||
metadata.flags =
|
||||
$(FLIGHTACCESS) << UAVOBJ_ACCESS_SHIFT |
|
||||
$(GCSACCESS) << UAVOBJ_GCS_ACCESS_SHIFT |
|
||||
$(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT |
|
||||
$(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT |
|
||||
$(FLIGHTTELEM_UPDATEMODE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT |
|
||||
$(GCSTELEM_UPDATEMODE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT |
|
||||
$(LOGGING_UPDATEMODE) << UAVOBJ_LOGGING_UPDATE_MODE_SHIFT;
|
||||
metadata.telemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD);
|
||||
metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD);
|
||||
metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD);
|
||||
UAVObjSetMetadata(obj, &metadata);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -59,10 +59,10 @@ int32_t UAVTalkSendObjectTimestamped(UAVTalkConnection connectionHandle, UAVObjH
|
||||
int32_t UAVTalkSendObjectRequest(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, int32_t timeoutMs);
|
||||
UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte);
|
||||
UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connection, uint8_t rxbyte);
|
||||
UAVTalkRxState UAVTalkRelayPacket(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle);
|
||||
int32_t UAVTalkRelayPacket(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle);
|
||||
int32_t UAVTalkReceiveObject(UAVTalkConnection connectionHandle);
|
||||
void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats);
|
||||
void UAVTalkAddStats(UAVTalkConnection connection, UAVTalkStats *stats);
|
||||
void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats, bool reset);
|
||||
void UAVTalkAddStats(UAVTalkConnection connection, UAVTalkStats *stats, bool reset);
|
||||
void UAVTalkResetStats(UAVTalkConnection connection);
|
||||
void UAVTalkGetLastTimestamp(UAVTalkConnection connection, uint16_t *timestamp);
|
||||
uint32_t UAVTalkGetPacketObjId(UAVTalkConnection connection);
|
||||
|
@ -133,7 +133,7 @@ UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connectionHandle)
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* @param[out] statsOut Statistics counters
|
||||
*/
|
||||
void UAVTalkGetStats(UAVTalkConnection connectionHandle, UAVTalkStats *statsOut)
|
||||
void UAVTalkGetStats(UAVTalkConnection connectionHandle, UAVTalkStats *statsOut, bool reset)
|
||||
{
|
||||
UAVTalkConnectionData *connection;
|
||||
|
||||
@ -145,6 +145,11 @@ void UAVTalkGetStats(UAVTalkConnection connectionHandle, UAVTalkStats *statsOut)
|
||||
// Copy stats
|
||||
memcpy(statsOut, &connection->stats, sizeof(UAVTalkStats));
|
||||
|
||||
if (reset) {
|
||||
// Clear stats
|
||||
memset(&connection->stats, 0, sizeof(UAVTalkStats));
|
||||
}
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
}
|
||||
@ -154,7 +159,7 @@ void UAVTalkGetStats(UAVTalkConnection connectionHandle, UAVTalkStats *statsOut)
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* @param[out] statsOut Statistics counters
|
||||
*/
|
||||
void UAVTalkAddStats(UAVTalkConnection connectionHandle, UAVTalkStats *statsOut)
|
||||
void UAVTalkAddStats(UAVTalkConnection connectionHandle, UAVTalkStats *statsOut, bool reset)
|
||||
{
|
||||
UAVTalkConnectionData *connection;
|
||||
|
||||
@ -175,6 +180,11 @@ void UAVTalkAddStats(UAVTalkConnection connectionHandle, UAVTalkStats *statsOut)
|
||||
statsOut->rxSyncErrors += connection->stats.rxSyncErrors;
|
||||
statsOut->rxCrcErrors += connection->stats.rxCrcErrors;
|
||||
|
||||
if (reset) {
|
||||
// Clear stats
|
||||
memset(&connection->stats, 0, sizeof(UAVTalkStats));
|
||||
}
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
}
|
||||
@ -589,7 +599,7 @@ UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uin
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
UAVTalkRxState UAVTalkRelayPacket(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle)
|
||||
int32_t UAVTalkRelayPacket(UAVTalkConnection inConnectionHandle, UAVTalkConnection outConnectionHandle)
|
||||
{
|
||||
UAVTalkConnectionData *inConnection;
|
||||
|
||||
@ -656,17 +666,17 @@ UAVTalkRxState UAVTalkRelayPacket(UAVTalkConnection inConnectionHandle, UAVTalkC
|
||||
outConnection->stats.txBytes += (rc > 0) ? rc : 0;
|
||||
|
||||
// evaluate return value before releasing the lock
|
||||
UAVTalkRxState rxState = 0;
|
||||
int32_t ret = 0;
|
||||
if (rc != (int32_t)(headerLength + inIproc->length + UAVTALK_CHECKSUM_LENGTH)) {
|
||||
outConnection->stats.txErrors++;
|
||||
rxState = -1;
|
||||
ret = -1;
|
||||
}
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(outConnection->lock);
|
||||
|
||||
// Done
|
||||
return rxState;
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -862,7 +872,7 @@ static int32_t sendObject(UAVTalkConnectionData *connection, uint8_t type, uint3
|
||||
{
|
||||
uint32_t numInst;
|
||||
uint32_t n;
|
||||
uint32_t ret = -1;
|
||||
int32_t ret = -1;
|
||||
|
||||
// Important note : obj can be null (when type is NACK for example) so protect all obj dereferences.
|
||||
|
||||
@ -880,8 +890,8 @@ static int32_t sendObject(UAVTalkConnectionData *connection, uint8_t type, uint3
|
||||
// This allows the receiver to detect when the last object has been received (i.e. when instance 0 is received)
|
||||
ret = 0;
|
||||
for (n = 0; n < numInst; ++n) {
|
||||
if (sendSingleObject(connection, type, objId, numInst - n - 1, obj) == -1) {
|
||||
ret = -1;
|
||||
ret = sendSingleObject(connection, type, objId, numInst - n - 1, obj);
|
||||
if (ret == -1) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -904,8 +914,7 @@ static int32_t sendObject(UAVTalkConnectionData *connection, uint8_t type, uint3
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] type Transaction type
|
||||
* \param[in] objId The object ID
|
||||
* \param[in] instId The instance ID (can NOT be UAVOBJ_ALL_INSTANCES, use
|
||||
() instead)
|
||||
* \param[in] instId The instance ID (can NOT be UAVOBJ_ALL_INSTANCES, use () instead)
|
||||
* \param[in] obj Object handle to send (null when type is NACK)
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
@ -982,7 +991,7 @@ static int32_t sendSingleObject(UAVTalkConnectionData *connection, uint8_t type,
|
||||
connection->stats.txBytes += tx_msg_len;
|
||||
} else {
|
||||
connection->stats.txErrors++;
|
||||
// TDOD rc == -1 connection not open, -2 buffer full should retry
|
||||
// TODO rc == -1 connection not open, -2 buffer full should retry
|
||||
connection->stats.txBytes += (rc > 0) ? rc : 0;
|
||||
return -1;
|
||||
}
|
||||
|
@ -28,12 +28,12 @@ GCS_LIBRARY_PATH
|
||||
libQt5MultimediaWidgets.so.5 \
|
||||
libQt5Quick.so.5 \
|
||||
libQt5Qml.so.5 \
|
||||
libQt5V8.so.5 \
|
||||
libQt5DBus.so.5 \
|
||||
libQt5QuickParticles.so.5 \
|
||||
libicui18n.so.51 \
|
||||
libicuuc.so.51 \
|
||||
libicudata.so.51
|
||||
libicudata.so.51 \
|
||||
libqgsttools_p.so.1
|
||||
|
||||
data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_QT_LIBRARY_PATH\") $$addNewline()
|
||||
for(lib, QT_LIBS) {
|
||||
@ -56,6 +56,8 @@ GCS_LIBRARY_PATH
|
||||
imageformats/libqmng.so \
|
||||
imageformats/libqsvg.so \
|
||||
imageformats/libqtiff.so \
|
||||
mediaservice/libgstaudiodecoder.so \
|
||||
mediaservice/libgstmediaplayer.so \
|
||||
platforms/libqxcb.so \
|
||||
sqldrivers/libqsqlite.so
|
||||
for(lib, QT_PLUGIN_LIBS) {
|
||||
@ -114,10 +116,8 @@ GCS_LIBRARY_PATH
|
||||
data_copy.target = FORCE
|
||||
QMAKE_EXTRA_TARGETS += data_copy
|
||||
}
|
||||
# Windows release only, no debug target DLLs ending with 'd'
|
||||
# It is assumed that SDL.dll can be found in the same directory as mingw32-make.exe
|
||||
win32 {
|
||||
|
||||
win32 {
|
||||
# set debug suffix if needed
|
||||
CONFIG(debug, debug|release):DS = "d"
|
||||
|
||||
@ -142,7 +142,6 @@ GCS_LIBRARY_PATH
|
||||
Qt5MultimediaWidgets$${DS}.dll \
|
||||
Qt5Quick$${DS}.dll \
|
||||
Qt5Qml$${DS}.dll \
|
||||
Qt5V8$${DS}.dll \
|
||||
icuin51.dll \
|
||||
icudt51.dll \
|
||||
icuuc51.dll
|
||||
@ -228,12 +227,6 @@ GCS_LIBRARY_PATH
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_QML]/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline()
|
||||
}
|
||||
|
||||
# copy MinGW DLLs
|
||||
MINGW_DLLS = SDL.dll
|
||||
for(dll, MINGW_DLLS) {
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(QTMINGW)/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline()
|
||||
}
|
||||
|
||||
# copy OpenSSL DLLs
|
||||
OPENSSL_DLLS = \
|
||||
ssleay32.dll \
|
||||
|
@ -1,2849 +0,0 @@
|
||||
<gcs>
|
||||
<General>
|
||||
<AutoConnect>true</AutoConnect>
|
||||
<AutoSelect>true</AutoSelect>
|
||||
<Description>Developer</Description>
|
||||
<Details>Developer mode configuration</Details>
|
||||
<ExpertMode>true</ExpertMode>
|
||||
<LastPreferenceCategory>OPMapGadget</LastPreferenceCategory>
|
||||
<LastPreferencePage>default</LastPreferencePage>
|
||||
<SaveSettingsOnExit>true</SaveSettingsOnExit>
|
||||
<SettingsWindowHeight>628</SettingsWindowHeight>
|
||||
<SettingsWindowWidth>697</SettingsWindowWidth>
|
||||
<StyleSheet>default</StyleSheet>
|
||||
<UDPMirror>false</UDPMirror>
|
||||
</General>
|
||||
<IPconnection>
|
||||
<Current>
|
||||
<arr_1>
|
||||
<Port>9000</Port>
|
||||
<UseTCP>0</UseTCP>
|
||||
</arr_1>
|
||||
<size>1</size>
|
||||
</Current>
|
||||
</IPconnection>
|
||||
<KeyBindings>
|
||||
<size>0</size>
|
||||
</KeyBindings>
|
||||
<MainWindow>
|
||||
<Color>#666666</Color>
|
||||
<FullScreen>false</FullScreen>
|
||||
<Maximized>true</Maximized>
|
||||
</MainWindow>
|
||||
<ModePriorities>
|
||||
<Mode1>91</Mode1>
|
||||
<Mode2>90</Mode2>
|
||||
<Mode3>89</Mode3>
|
||||
<Mode4>88</Mode4>
|
||||
<Mode5>87</Mode5>
|
||||
<Mode6>86</Mode6>
|
||||
<Welcome>100</Welcome>
|
||||
</ModePriorities>
|
||||
<Plugins>
|
||||
<SoundNotifyPlugin>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>1.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<Current>
|
||||
<arr_1>
|
||||
<CurrentLanguage>default</CurrentLanguage>
|
||||
<DataObject>AccelState</DataObject>
|
||||
<ExpireTimeout>0</ExpireTimeout>
|
||||
<Mute>false</Mute>
|
||||
<ObjectField></ObjectField>
|
||||
<RangeLimit>-1</RangeLimit>
|
||||
<Repeat>0</Repeat>
|
||||
<SayOrder>0</SayOrder>
|
||||
<Sound1></Sound1>
|
||||
<Sound2></Sound2>
|
||||
<Sound3></Sound3>
|
||||
<SoundCollectionPath>%%DATAPATH%%sounds</SoundCollectionPath>
|
||||
<Value1></Value1>
|
||||
<Value2>0</Value2>
|
||||
</arr_1>
|
||||
<size>1</size>
|
||||
</Current>
|
||||
<EnableSound>false</EnableSound>
|
||||
<listNotifies>
|
||||
<size>0</size>
|
||||
</listNotifies>
|
||||
</data>
|
||||
</SoundNotifyPlugin>
|
||||
</Plugins>
|
||||
<SerialConnection>
|
||||
<speed>57600</speed>
|
||||
</SerialConnection>
|
||||
<UAVGadgetConfigurations>
|
||||
<ConfigGadget>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
</default>
|
||||
</ConfigGadget>
|
||||
<DialGadget>
|
||||
<Attitude>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/attitude.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Roll</needle1ObjectField>
|
||||
<needle2DataObject>AttitudeState</needle2DataObject>
|
||||
<needle2Factor>75</needle2Factor>
|
||||
<needle2MaxValue>20</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Vertical</needle2Move>
|
||||
<needle2ObjectField>Pitch</needle2ObjectField>
|
||||
<needle3DataObject>AttitudeState</needle3DataObject>
|
||||
<needle3Factor>-1</needle3Factor>
|
||||
<needle3MaxValue>360</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Roll</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Attitude>
|
||||
<Baro__PCT__20Altimeter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/altimeter.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>10</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Altitude</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Baro__PCT__20Altimeter>
|
||||
<Barometer>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/barometer.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>10</needle1Factor>
|
||||
<needle1MaxValue>1120</needle1MaxValue>
|
||||
<needle1MinValue>1000</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Pressure</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Barometer>
|
||||
<Climbrate>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/vsi.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>VelocityState</needle1DataObject>
|
||||
<needle1Factor>0.01</needle1Factor>
|
||||
<needle1MaxValue>12</needle1MaxValue>
|
||||
<needle1MinValue>-12</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Down</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Climbrate>
|
||||
<Compass>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/compass.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Yaw</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Compass>
|
||||
<Deluxe__PCT__20Attitude>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/attitude.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Roll</needle1ObjectField>
|
||||
<needle2DataObject>AttitudeState</needle2DataObject>
|
||||
<needle2Factor>75</needle2Factor>
|
||||
<needle2MaxValue>20</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Vertical</needle2Move>
|
||||
<needle2ObjectField>Pitch</needle2ObjectField>
|
||||
<needle3DataObject>AttitudeState</needle3DataObject>
|
||||
<needle3Factor>-1</needle3Factor>
|
||||
<needle3MaxValue>360</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Roll</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Attitude>
|
||||
<Deluxe__PCT__20Baro__PCT__20Altimeter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/altimeter.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>10</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Altitude</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Baro__PCT__20Altimeter>
|
||||
<Deluxe__PCT__20Barometer>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/barometer.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>10</needle1Factor>
|
||||
<needle1MaxValue>1120</needle1MaxValue>
|
||||
<needle1MinValue>1000</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Pressure</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Barometer>
|
||||
<Deluxe__PCT__20Climbrate>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/vsi.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>VelocityState</needle1DataObject>
|
||||
<needle1Factor>0.01</needle1Factor>
|
||||
<needle1MaxValue>11.2</needle1MaxValue>
|
||||
<needle1MinValue>-11.2</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Down</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Climbrate>
|
||||
<Deluxe__PCT__20Compass>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/compass.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Yaw</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Compass>
|
||||
<Deluxe__PCT__20Groundspeed__PCT__20kph>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/speed.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>GPSPositionSensor</needle1DataObject>
|
||||
<needle1Factor>3.6</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Groundspeed</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Groundspeed__PCT__20kph>
|
||||
<Deluxe__PCT__20Temperature>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/thermometer.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Temperature</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Temperature>
|
||||
<Deluxe__PCT__20Turn__PCT__20Coordinator>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>/home/lafargue/OP/OpenPilot/trunk/artwork/Dials/deluxe/turncoordinator.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle2</dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Roll</needle1ObjectField>
|
||||
<needle2DataObject>AccelState</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>20</needle2MaxValue>
|
||||
<needle2MinValue>-20</needle2MinValue>
|
||||
<needle2Move>Horizontal</needle2Move>
|
||||
<needle2ObjectField>x</needle2ObjectField>
|
||||
<needle3DataObject>AccelState</needle3DataObject>
|
||||
<needle3Factor>-1</needle3Factor>
|
||||
<needle3MaxValue>360</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>x</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Turn__PCT__20Coordinator>
|
||||
<Groundspeed__PCT__20kph>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/speed.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>GPSPositionSensor</needle1DataObject>
|
||||
<needle1Factor>3.6</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Groundspeed</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Groundspeed__PCT__20kph>
|
||||
<HiContrast__PCT__20Attitude>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/attitude.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Roll</needle1ObjectField>
|
||||
<needle2DataObject>AttitudeState</needle2DataObject>
|
||||
<needle2Factor>75</needle2Factor>
|
||||
<needle2MaxValue>20</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Vertical</needle2Move>
|
||||
<needle2ObjectField>Pitch</needle2ObjectField>
|
||||
<needle3DataObject>AttitudeState</needle3DataObject>
|
||||
<needle3Factor>-1</needle3Factor>
|
||||
<needle3MaxValue>360</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Roll</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Attitude>
|
||||
<HiContrast__PCT__20Baro__PCT__20Altimeter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/altimeter.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>10</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Altitude</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Baro__PCT__20Altimeter>
|
||||
<HiContrast__PCT__20Barometer>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/barometer.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>10</needle1Factor>
|
||||
<needle1MaxValue>1120</needle1MaxValue>
|
||||
<needle1MinValue>1000</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Pressure</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Barometer>
|
||||
<HiContrast__PCT__20Climbrate>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/vsi.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>VelocityState</needle1DataObject>
|
||||
<needle1Factor>0.01</needle1Factor>
|
||||
<needle1MaxValue>12</needle1MaxValue>
|
||||
<needle1MinValue>-12</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Down</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Climbrate>
|
||||
<HiContrast__PCT__20Compass>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/compass.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Yaw</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Compass>
|
||||
<HiContrast__PCT__20Groundspeed__PCT__20kph>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/speed.svg</dialFile>
|
||||
<dialForegroundID></dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2></dialNeedleID2>
|
||||
<dialNeedleID3></dialNeedleID3>
|
||||
<font>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>GPSPositionSensor</needle1DataObject>
|
||||
<needle1Factor>3.6</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Groundspeed</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Groundspeed__PCT__20kph>
|
||||
<HiContrast__PCT__20Temperature>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<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>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Temperature</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Temperature>
|
||||
<Servo__PCT__20Channel__PCT__201>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<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>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>ManualControlCommand</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>2000</needle1MaxValue>
|
||||
<needle1MinValue>1000</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Channel-3</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Servo__PCT__20Channel__PCT__201>
|
||||
<Temperature>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<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>Lucida Grande,13,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Temperature</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Temperature>
|
||||
</DialGadget>
|
||||
<GCSControlGadget>
|
||||
<MS__PCT__20Sidewinder>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<button0Action>0</button0Action>
|
||||
<button0Amount>0</button0Amount>
|
||||
<button0Function>0</button0Function>
|
||||
<button1Action>0</button1Action>
|
||||
<button1Amount>0</button1Amount>
|
||||
<button1Function>0</button1Function>
|
||||
<button2Action>0</button2Action>
|
||||
<button2Amount>0.1</button2Amount>
|
||||
<button2Function>3</button2Function>
|
||||
<button3Action>0</button3Action>
|
||||
<button3Amount>0.1</button3Amount>
|
||||
<button3Function>3</button3Function>
|
||||
<button4Action>0</button4Action>
|
||||
<button4Amount>0</button4Amount>
|
||||
<button4Function>0</button4Function>
|
||||
<button5Action>0</button5Action>
|
||||
<button5Amount>0</button5Amount>
|
||||
<button5Function>0</button5Function>
|
||||
<button6Action>0</button6Action>
|
||||
<button6Amount>0</button6Amount>
|
||||
<button6Function>0</button6Function>
|
||||
<button7Action>0</button7Action>
|
||||
<button7Amount>0</button7Amount>
|
||||
<button7Function>0</button7Function>
|
||||
<channel0Reverse>false</channel0Reverse>
|
||||
<channel1Reverse>false</channel1Reverse>
|
||||
<channel2Reverse>true</channel2Reverse>
|
||||
<channel3Reverse>false</channel3Reverse>
|
||||
<channel4Reverse>false</channel4Reverse>
|
||||
<channel5Reverse>false</channel5Reverse>
|
||||
<channel6Reverse>false</channel6Reverse>
|
||||
<channel7Reverse>false</channel7Reverse>
|
||||
<controlHostUDP></controlHostUDP>
|
||||
<controlPortUDP>0</controlPortUDP>
|
||||
<controlsMode>2</controlsMode>
|
||||
<pitchChannel>1</pitchChannel>
|
||||
<rollChannel>0</rollChannel>
|
||||
<throttleChannel>2</throttleChannel>
|
||||
<yawChannel>3</yawChannel>
|
||||
</data>
|
||||
</MS__PCT__20Sidewinder>
|
||||
</GCSControlGadget>
|
||||
<GpsDisplayGadget>
|
||||
<Flight__PCT__20GPS>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<connectionMode>Telemetry</connectionMode>
|
||||
<defaultDataBits>3</defaultDataBits>
|
||||
<defaultFlow>0</defaultFlow>
|
||||
<defaultParity>0</defaultParity>
|
||||
<defaultPort>/dev/cu.Bluetooth-Modem</defaultPort>
|
||||
<defaultSpeed>11</defaultSpeed>
|
||||
<defaultStopBits>0</defaultStopBits>
|
||||
</data>
|
||||
</Flight__PCT__20GPS>
|
||||
<GPS__PCT__20Mouse>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<connectionMode>Serial</connectionMode>
|
||||
<defaultDataBits>3</defaultDataBits>
|
||||
<defaultFlow>0</defaultFlow>
|
||||
<defaultParity>0</defaultParity>
|
||||
<defaultPort>/dev/cu.Bluetooth-Modem</defaultPort>
|
||||
<defaultSpeed>17</defaultSpeed>
|
||||
<defaultStopBits>0</defaultStopBits>
|
||||
</data>
|
||||
</GPS__PCT__20Mouse>
|
||||
</GpsDisplayGadget>
|
||||
<HITL>
|
||||
<Flightgear__PCT__20HITL>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<binPath>\usr\games\fgfs</binPath>
|
||||
<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>
|
||||
<simulatorId>FG</simulatorId>
|
||||
<startSim>true</startSim>
|
||||
</data>
|
||||
</Flightgear__PCT__20HITL>
|
||||
<XPlane__PCT__20HITL>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<binPath>\home\lafargue\X-Plane 9\X-Plane-i686</binPath>
|
||||
<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>
|
||||
<simulatorId>X-Plane</simulatorId>
|
||||
<startSim>false</startSim>
|
||||
</data>
|
||||
</XPlane__PCT__20HITL>
|
||||
</HITL>
|
||||
<HITLv2>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<attActCalc>false</attActCalc>
|
||||
<attActHW>false</attActHW>
|
||||
<attActSim>true</attActSim>
|
||||
<attState>true</attState>
|
||||
<attRaw>true</attRaw>
|
||||
<attRawRate>20</attRawRate>
|
||||
<binPath></binPath>
|
||||
<dataPath></dataPath>
|
||||
<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>
|
||||
</HITLv2>
|
||||
<LineardialGadget>
|
||||
<Accel__PCT__20Horizontal__PCT__20X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,8,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>-9</greenMax>
|
||||
<greenMin>-10</greenMin>
|
||||
<maxValue>11</maxValue>
|
||||
<minValue>-11</minValue>
|
||||
<redMax>11</redMax>
|
||||
<redMin>-11</redMin>
|
||||
<sourceDataObject>AccelState</sourceDataObject>
|
||||
<sourceObjectField>x</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>-5</yellowMax>
|
||||
<yellowMin>-11</yellowMin>
|
||||
</data>
|
||||
</Accel__PCT__20Horizontal__PCT__20X>
|
||||
<Accel__PCT__20Horizontal__PCT__20Y>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,6,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>-9</greenMax>
|
||||
<greenMin>-10</greenMin>
|
||||
<maxValue>11</maxValue>
|
||||
<minValue>-11</minValue>
|
||||
<redMax>11</redMax>
|
||||
<redMin>-11</redMin>
|
||||
<sourceDataObject>AccelState</sourceDataObject>
|
||||
<sourceObjectField>y</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>-5</yellowMax>
|
||||
<yellowMin>-11</yellowMin>
|
||||
</data>
|
||||
</Accel__PCT__20Horizontal__PCT__20Y>
|
||||
<Accel__PCT__20Horizontal__PCT__20Z>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,8,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>-9</greenMax>
|
||||
<greenMin>-10</greenMin>
|
||||
<maxValue>11</maxValue>
|
||||
<minValue>-11</minValue>
|
||||
<redMax>11</redMax>
|
||||
<redMin>-11</redMin>
|
||||
<sourceDataObject>AccelState</sourceDataObject>
|
||||
<sourceObjectField>z</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>-5</yellowMax>
|
||||
<yellowMin>-11</yellowMin>
|
||||
</data>
|
||||
</Accel__PCT__20Horizontal__PCT__20Z>
|
||||
<Arm__PCT__20Status>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/arm-status.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>33</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>FlightStatus</sourceDataObject>
|
||||
<sourceObjectField>Armed</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>66</yellowMax>
|
||||
<yellowMin>33</yellowMin>
|
||||
</data>
|
||||
</Arm__PCT__20Status>
|
||||
<Flight__PCT__20Time>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/textonly.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>0.001</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>33</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>SystemStats</sourceDataObject>
|
||||
<sourceObjectField>FlightTime</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>66</yellowMax>
|
||||
<yellowMin>33</yellowMin>
|
||||
</data>
|
||||
</Flight__PCT__20Time>
|
||||
<Flight__PCT__20mode>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/flightmode-status.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>33</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>FlightStatus</sourceDataObject>
|
||||
<sourceObjectField>FlightMode</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>66</yellowMax>
|
||||
<yellowMin>33</yellowMin>
|
||||
</data>
|
||||
</Flight__PCT__20mode>
|
||||
<GPS__PCT__20Sats>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/gps-signal.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>0</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>12</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>0</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>GPSPositionSensor</sourceDataObject>
|
||||
<sourceObjectField>Satellites</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0</yellowMax>
|
||||
<yellowMin>0</yellowMin>
|
||||
</data>
|
||||
</GPS__PCT__20Sats>
|
||||
<GPS__PCT__20Status>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/gps-status.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>33</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>GPSPositionSensor</sourceDataObject>
|
||||
<sourceObjectField>Status</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>66</yellowMax>
|
||||
<yellowMin>33</yellowMin>
|
||||
</data>
|
||||
</GPS__PCT__20Status>
|
||||
<Mainboard__PCT__20CPU>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>90</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>100</redMax>
|
||||
<redMin>95</redMin>
|
||||
<sourceDataObject>SystemStats</sourceDataObject>
|
||||
<sourceObjectField>CPULoad</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>95</yellowMax>
|
||||
<yellowMin>90</yellowMin>
|
||||
</data>
|
||||
</Mainboard__PCT__20CPU>
|
||||
<Pitch__PCT__20Desired>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ActuatorDesired</sourceDataObject>
|
||||
<sourceObjectField>Pitch</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Pitch__PCT__20Desired>
|
||||
<Pitch>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ManualControlCommand</sourceDataObject>
|
||||
<sourceObjectField>Pitch</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Pitch>
|
||||
<PitchState>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.8</greenMax>
|
||||
<greenMin>0.3</greenMin>
|
||||
<maxValue>90</maxValue>
|
||||
<minValue>-90</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>AttitudeState</sourceDataObject>
|
||||
<sourceObjectField>Pitch</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.9</yellowMax>
|
||||
<yellowMin>0.1</yellowMin>
|
||||
</data>
|
||||
</PitchState>
|
||||
<Roll__PCT__20Desired>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ActuatorDesired</sourceDataObject>
|
||||
<sourceObjectField>Roll</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Roll__PCT__20Desired>
|
||||
<Roll>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ManualControlCommand</sourceDataObject>
|
||||
<sourceObjectField>Roll</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Roll>
|
||||
<Telemetry__PCT__20RX__PCT__20Rate__PCT__20Horizontal>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>650</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>1200</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>1200</redMax>
|
||||
<redMin>900</redMin>
|
||||
<sourceDataObject>GCSTelemetryStats</sourceDataObject>
|
||||
<sourceObjectField>RxDataRate</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>900</yellowMax>
|
||||
<yellowMin>650</yellowMin>
|
||||
</data>
|
||||
</Telemetry__PCT__20RX__PCT__20Rate__PCT__20Horizontal>
|
||||
<Telemetry__PCT__20TX__PCT__20Rate__PCT__20Horizontal>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>650</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>1200</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>1200</redMax>
|
||||
<redMin>900</redMin>
|
||||
<sourceDataObject>GCSTelemetryStats</sourceDataObject>
|
||||
<sourceObjectField>TxDataRate</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>900</yellowMax>
|
||||
<yellowMin>650</yellowMin>
|
||||
</data>
|
||||
</Telemetry__PCT__20TX__PCT__20Rate__PCT__20Horizontal>
|
||||
<Throttle>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>0.75</redMin>
|
||||
<sourceDataObject>ManualControlCommand</sourceDataObject>
|
||||
<sourceObjectField>Throttle</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.75</yellowMax>
|
||||
<yellowMin>0.5</yellowMin>
|
||||
</data>
|
||||
</Throttle>
|
||||
<Yaw__PCT__20Desired>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ActuatorDesired</sourceDataObject>
|
||||
<sourceObjectField>Yaw</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Yaw__PCT__20Desired>
|
||||
<Yaw>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ManualControlCommand</sourceDataObject>
|
||||
<sourceObjectField>Yaw</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Yaw>
|
||||
</LineardialGadget>
|
||||
<ModelViewGadget>
|
||||
<Aeroquad__PCT__20__PCT__2B>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/aeroquad/aeroquad_+.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Aeroquad__PCT__20__PCT__2B>
|
||||
<CC3D>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/boards/CC3D/CC3D.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</CC3D>
|
||||
<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>
|
||||
<Danker__PCT__27s__PCT__20Quad>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/dankers_quad/dankers_quad.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Danker__PCT__27s__PCT__20Quad>
|
||||
<Easyquad__PCT__20X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/easy_quad/easy_quad_X.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Easyquad__PCT__20X>
|
||||
<Easystar>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/planes/Easystar/easystar.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Easystar>
|
||||
<Firecracker>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/planes/firecracker/firecracker.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Firecracker>
|
||||
<Funjet>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/planes/funjet/funjet.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Funjet>
|
||||
<Gaui__PCT__20330X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/gaui_330x/gaui_330x.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Gaui__PCT__20330X>
|
||||
<Helicopter__PCT__20-__PCT__20TRex__PCT__20450>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/helis/t-rex/t-rex_450_xl.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Helicopter__PCT__20-__PCT__20TRex__PCT__20450>
|
||||
<Hexacopter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/mikrokopter/MK_Hexa.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Hexacopter>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-Q_+.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20X__PCT__20>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-Q_X.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20X__PCT__20>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-QT_+.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-QT_X.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20X>
|
||||
<MattL__PCT__27s__PCT__20Y6>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/mattL_Y6/mattL_Y6.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</MattL__PCT__27s__PCT__20Y6>
|
||||
<Quadcopter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/mikrokopter/MK_L4-ME.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<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>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/scorpion_tricopter/scorpion_tricopter.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Scorpion__PCT__20Tricopter>
|
||||
<Test__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/test_quad/test_quad_+.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Test__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<Test__PCT__20Quad__PCT__20X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/test_quad/test_quad_X.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Test__PCT__20Quad__PCT__20X>
|
||||
</ModelViewGadget>
|
||||
<OPMapGadget>
|
||||
<Google__PCT__20Sat>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<accessMode>ServerAndCache</accessMode>
|
||||
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
|
||||
<defaultLatitude>0</defaultLatitude>
|
||||
<defaultLongitude>0</defaultLongitude>
|
||||
<defaultZoom>2</defaultZoom>
|
||||
<mapProvider>GoogleSatellite</mapProvider>
|
||||
<maxUpdateRate>2000</maxUpdateRate>
|
||||
<overlayOpacity>1</overlayOpacity>
|
||||
<showTileGridLines>false</showTileGridLines>
|
||||
<uavSymbol>mapquad.png</uavSymbol>
|
||||
<useMemoryCache>true</useMemoryCache>
|
||||
<useOpenGL>false</useOpenGL>
|
||||
</data>
|
||||
</Google__PCT__20Sat>
|
||||
<Memory__PCT__20Only>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<accessMode>CacheOnly</accessMode>
|
||||
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
|
||||
<defaultLatitude>0</defaultLatitude>
|
||||
<defaultLongitude>0</defaultLongitude>
|
||||
<defaultZoom>2</defaultZoom>
|
||||
<mapProvider>GoogleMap</mapProvider>
|
||||
<maxUpdateRate>2000</maxUpdateRate>
|
||||
<overlayOpacity>1</overlayOpacity>
|
||||
<showTileGridLines>false</showTileGridLines>
|
||||
<uavSymbol>airplanepip.png</uavSymbol>
|
||||
<useMemoryCache>true</useMemoryCache>
|
||||
<useOpenGL>false</useOpenGL>
|
||||
</data>
|
||||
</Memory__PCT__20Only>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<accessMode>ServerAndCache</accessMode>
|
||||
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
|
||||
<defaultLatitude>29.97</defaultLatitude>
|
||||
<defaultLongitude>95.35</defaultLongitude>
|
||||
<defaultZoom>7</defaultZoom>
|
||||
<mapProvider>GoogleMap</mapProvider>
|
||||
<maxUpdateRate>2000</maxUpdateRate>
|
||||
<overlayOpacity>1</overlayOpacity>
|
||||
<showTileGridLines>false</showTileGridLines>
|
||||
<uavSymbol>mapquad.png</uavSymbol>
|
||||
<useMemoryCache>true</useMemoryCache>
|
||||
<useOpenGL>true</useOpenGL>
|
||||
</data>
|
||||
</default>
|
||||
</OPMapGadget>
|
||||
<PfdQmlGadget>
|
||||
<NoTerrain>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<actualPositionUsed>false</actualPositionUsed>
|
||||
<altitude>2000</altitude>
|
||||
<altitudeFactor>1</altitudeFactor>
|
||||
<cacheOnly>false</cacheOnly>
|
||||
<earthFile>%%DATAPATH%%pfd/default/readymap.earth</earthFile>
|
||||
<latitude>46.6715</latitude>
|
||||
<longitude>10.1589</longitude>
|
||||
<openGLEnabled>true</openGLEnabled>
|
||||
<qmlFile>%%DATAPATH%%pfd/default/Pfd.qml</qmlFile>
|
||||
<speedFactor>1</speedFactor>
|
||||
<terrainEnabled>false</terrainEnabled>
|
||||
</data>
|
||||
</NoTerrain>
|
||||
<Terrain>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<actualPositionUsed>false</actualPositionUsed>
|
||||
<altitude>2000</altitude>
|
||||
<cacheOnly>false</cacheOnly>
|
||||
<earthFile>%%DATAPATH%%pfd/default/readymap.earth</earthFile>
|
||||
<latitude>46.6715</latitude>
|
||||
<longitude>10.1589</longitude>
|
||||
<openGLEnabled>true</openGLEnabled>
|
||||
<qmlFile>%%DATAPATH%%pfd/default/Pfd.qml</qmlFile>
|
||||
<terrainEnabled>false</terrainEnabled>
|
||||
</data>
|
||||
</Terrain>
|
||||
</PfdQmlGadget>
|
||||
<QmlViewGadget>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dialFile>Unknown</dialFile>
|
||||
<useOpenGLFlag>true</useOpenGLFlag>
|
||||
</data>
|
||||
</default>
|
||||
</QmlViewGadget>
|
||||
<ScopeGadget>
|
||||
<Accel>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>6.92920863607354e-310</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>1.78017180972965e-306</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>9.34609790258712e-307</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>2.6501977682312e-318</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>6.92920723246466e-310</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>100</refreshInterval>
|
||||
</data>
|
||||
</Accel>
|
||||
<Actuators>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>20</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-4</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>1.72723371101889e-77</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>6.02760087926321e-322</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-5</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>3.55727265005698e-322</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>2.19822614387826e-314</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4289374847</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-6</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>1.72723371101889e-77</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>1.72723371101889e-77</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4289374847</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-7</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>6.92916505779426e-310</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>4.22277162500408e-312</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
<plotCurveCount>4</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>100</refreshInterval>
|
||||
</data>
|
||||
</Actuators>
|
||||
<Attitude>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4283760895</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Roll</uavField>
|
||||
<uavObject>AttitudeState</uavObject>
|
||||
<yMaximum>6.92921152826347e-310</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>6.92921152826031e-310</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4278233600</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Yaw</uavField>
|
||||
<uavObject>AttitudeState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Pitch</uavField>
|
||||
<uavObject>AttitudeState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>100</refreshInterval>
|
||||
</data>
|
||||
</Attitude>
|
||||
<Barometer>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4278190080</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Pressure</uavField>
|
||||
<uavObject>BaroSensor</uavObject>
|
||||
<yMaximum>1.72723371102043e-77</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>3.86203233966055e-312</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurveCount>1</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>1000</refreshInterval>
|
||||
</data>
|
||||
</Barometer>
|
||||
<Inputs>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>40</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4278190207</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-1</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-4</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>6.92916505599784e-310</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>7.21478569792807e-313</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-5</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>8.34448532677451e-308</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>1.78019353780608e-306</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-6</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>6.9291650571421e-310</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>4.22277162500408e-312</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
<plotCurve4>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-7</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>4.24399158193054e-314</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>4.172013484701e-309</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve4>
|
||||
<plotCurve5>
|
||||
<color>4283825920</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-2</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>1.72723371101889e-77</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>2.48782786590693e-310</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve5>
|
||||
<plotCurve6>
|
||||
<color>4294923520</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-3</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>6.92921442541857e-310</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>6.92921441189619e-310</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve6>
|
||||
<plotCurve7>
|
||||
<color>4294967040</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-0</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>6.92921439506975e-310</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>1.72723371101889e-77</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve7>
|
||||
<plotCurveCount>8</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>200</refreshInterval>
|
||||
</data>
|
||||
</Inputs>
|
||||
<Raw__PCT__20AccelState>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>500</refreshInterval>
|
||||
</data>
|
||||
</Raw__PCT__20AccelState>
|
||||
<Raw__PCT__20gyroState>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>gyroState</uavObject>
|
||||
<yMaximum>1.02360527502876e-306</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>6.92921152846347e-310</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>gyroState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>gyroState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>500</refreshInterval>
|
||||
</data>
|
||||
</Raw__PCT__20gyroState>
|
||||
<Raw__PCT__20magnetometers>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>MagState</uavObject>
|
||||
<yMaximum>6.92916505601691e-310</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>3.86203233966055e-312</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>MagState</uavObject>
|
||||
<yMaximum>1.72723371101889e-77</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>-1</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>MagState</uavObject>
|
||||
<yMaximum>1.72723371102028e-77</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>7.21478569792807e-313</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>500</refreshInterval>
|
||||
</data>
|
||||
</Raw__PCT__20magnetometers>
|
||||
<Stacks__PCT__20monitor>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>240</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-System</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-CallbackScheduler0</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4278190335</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-CallbackScheduler1</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4294967040</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<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>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Altitude</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve7>
|
||||
<plotCurve8>
|
||||
<color>4283760767</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve8>
|
||||
<plotCurve9>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve9>
|
||||
<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>
|
||||
</Stacks__PCT__20monitor>
|
||||
<Telemetry__PCT__20quality>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>20</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4289374847</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>TxFailures</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>RxFailures</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>TxRetries</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>100</refreshInterval>
|
||||
</data>
|
||||
</Telemetry__PCT__20quality>
|
||||
<Uptimes>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<LoggingPath></LoggingPath>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>240</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294945407</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>FlightTime</uavField>
|
||||
<uavObject>SystemStats</uavObject>
|
||||
<yMaximum>1.02360527502876e-306</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>6.92921153586022e-310</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>
|
||||
</data>
|
||||
</Uptimes>
|
||||
</ScopeGadget>
|
||||
<SystemHealthGadget>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<diagram>%%DATAPATH%%diagrams/default/system-health.svg</diagram>
|
||||
</data>
|
||||
</default>
|
||||
</SystemHealthGadget>
|
||||
<UAVObjectBrowser>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<CategorizedView>false</CategorizedView>
|
||||
<ScientificView>false</ScientificView>
|
||||
<manuallyChangedColor>#5baa56</manuallyChangedColor>
|
||||
<onlyHilightChangedValues>false</onlyHilightChangedValues>
|
||||
<recentlyUpdatedColor>#ff7957</recentlyUpdatedColor>
|
||||
<recentlyUpdatedTimeout>500</recentlyUpdatedTimeout>
|
||||
<showMetaData>false</showMetaData>
|
||||
</data>
|
||||
</default>
|
||||
</UAVObjectBrowser>
|
||||
<Uploader>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<defaultDataBits>3</defaultDataBits>
|
||||
<defaultFlow>0</defaultFlow>
|
||||
<defaultParity>0</defaultParity>
|
||||
<defaultPort>/dev/ttyS0</defaultPort>
|
||||
<defaultSpeed>14</defaultSpeed>
|
||||
<defaultStopBits>0</defaultStopBits>
|
||||
</data>
|
||||
</default>
|
||||
</Uploader>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>1.2.0</version>
|
||||
</configInfo>
|
||||
</UAVGadgetConfigurations>
|
||||
<UAVGadgetManager>
|
||||
<Mode1>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<side0>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight Time</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Arm Status</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight mode</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAYwAAAAIAAAB7)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAZgAAAAIAAADf)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>PFDGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>raw</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAG4)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>ModelViewGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Test Quad X</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>SystemHealthGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABIAAAAAIAAAFV)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAEf)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>OPMapGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Google Sat</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACdgAAAAIAAAMp)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode1>
|
||||
<Mode2>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<classId>ConfigGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>UAVObjectBrowser</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADRgAAAAIAAAJV)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode2>
|
||||
<Mode3>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<classId>UAVObjectBrowser</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>LoggingGadget</classId>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>GpsDisplayGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight GPS</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAcAAAAAIAAAHo)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>DebugGadget</classId>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB3wAAAAIAAAEp)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACJgAAAAIAAADo)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode3>
|
||||
<Mode4>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>ScopeGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Accel</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>ScopeGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Raw gyroState</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>ScopeGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Attitude</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>ScopeGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Uptimes</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAClQAAAAIAAAB3)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACjQAAAAIAAAKU)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode4>
|
||||
<Mode5>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>HITL</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>XPlane HITL</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>HITLv2</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>EmptyGadget</classId>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>GCSControlGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>MS Sidewinder</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB6AAAAAIAAADC)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADDAAAAAIAAAJJ)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode5>
|
||||
<Mode6>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<classId>Uploader</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight Time</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>SystemHealthGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABQgAAAAIAAAGM)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>DialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Deluxe Attitude</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>DialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Deluxe Baro Altimeter</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>DialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Deluxe Compass</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>DialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Deluxe Climbrate</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAAHf)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADVQAAAAIAAAJK)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode6>
|
||||
</UAVGadgetManager>
|
||||
<Workspace>
|
||||
<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/cog.png</Icon3>
|
||||
<Icon4>:/core/images/scopes.png</Icon4>
|
||||
<Icon5>:/core/images/joystick.png</Icon5>
|
||||
<Icon6>:/core/images/cpu.png</Icon6>
|
||||
<Icon7>:/core/images/openpilot_logo_64.png</Icon7>
|
||||
<Icon8>:/core/images/openpilot_logo_64.png</Icon8>
|
||||
<Icon9>:/core/images/openpilot_logo_64.png</Icon9>
|
||||
<NumberOfWorkspaces>6</NumberOfWorkspaces>
|
||||
<TabBarPlacementIndex>1</TabBarPlacementIndex>
|
||||
<Workspace1>Flight data</Workspace1>
|
||||
<Workspace10>Workspace10</Workspace10>
|
||||
<Workspace2>Configuration</Workspace2>
|
||||
<Workspace3>System</Workspace3>
|
||||
<Workspace4>Scopes</Workspace4>
|
||||
<Workspace5>HITL</Workspace5>
|
||||
<Workspace6>Firmware</Workspace6>
|
||||
<Workspace7>Workspace7</Workspace7>
|
||||
<Workspace8>Workspace8</Workspace8>
|
||||
<Workspace9>Workspace9</Workspace9>
|
||||
</Workspace>
|
||||
</gcs>
|
@ -1146,7 +1146,7 @@
|
||||
<dFile>%%DATAPATH%%dials/default/arm-status.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
@ -1169,7 +1169,7 @@
|
||||
<dFile>%%DATAPATH%%dials/default/textonly.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>0.001</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
@ -1192,7 +1192,7 @@
|
||||
<dFile>%%DATAPATH%%dials/default/flightmode-status.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
@ -1215,7 +1215,7 @@
|
||||
<dFile>%%DATAPATH%%dials/default/gps-signal.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>0</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>12</maxValue>
|
||||
@ -1238,7 +1238,7 @@
|
||||
<dFile>%%DATAPATH%%dials/default/gps-status.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<font>MS Shell Dlg 2,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
|
@ -1,2832 +0,0 @@
|
||||
<gcs>
|
||||
<General>
|
||||
<AutoConnect>true</AutoConnect>
|
||||
<AutoSelect>true</AutoSelect>
|
||||
<Description>Wide configuration</Description>
|
||||
<Details>Default configuration built for wide screens (17" and up)</Details>
|
||||
<ExpertMode>false</ExpertMode>
|
||||
<LastPreferenceCategory></LastPreferenceCategory>
|
||||
<LastPreferencePage></LastPreferencePage>
|
||||
<SaveSettingsOnExit>true</SaveSettingsOnExit>
|
||||
<SettingsWindowHeight>600</SettingsWindowHeight>
|
||||
<SettingsWindowWidth>800</SettingsWindowWidth>
|
||||
<StyleSheet>default</StyleSheet>
|
||||
<UDPMirror>false</UDPMirror>
|
||||
</General>
|
||||
<IPconnection>
|
||||
<Current>
|
||||
<arr_1>
|
||||
<Port>9000</Port>
|
||||
<UseTCP>0</UseTCP>
|
||||
</arr_1>
|
||||
<size>1</size>
|
||||
</Current>
|
||||
</IPconnection>
|
||||
<KeyBindings>
|
||||
<size>0</size>
|
||||
</KeyBindings>
|
||||
<MainWindow>
|
||||
<Color>#666666</Color>
|
||||
<FullScreen>false</FullScreen>
|
||||
<Maximized>true</Maximized>
|
||||
</MainWindow>
|
||||
<ModePriorities>
|
||||
<Mode1>91</Mode1>
|
||||
<Mode2>90</Mode2>
|
||||
<Mode3>89</Mode3>
|
||||
<Mode4>88</Mode4>
|
||||
<Mode5>87</Mode5>
|
||||
<Mode6>86</Mode6>
|
||||
<Welcome>100</Welcome>
|
||||
</ModePriorities>
|
||||
<Plugins>
|
||||
<SoundNotifyPlugin>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>1.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<Current>
|
||||
<arr_1>
|
||||
<CurrentLanguage>default</CurrentLanguage>
|
||||
<DataObject>FlightStatus</DataObject>
|
||||
<ExpireTimeout>0</ExpireTimeout>
|
||||
<Mute>false</Mute>
|
||||
<ObjectField>Armed</ObjectField>
|
||||
<RangeLimit>0</RangeLimit>
|
||||
<Repeat>0</Repeat>
|
||||
<SayOrder>0</SayOrder>
|
||||
<Sound1>armed</Sound1>
|
||||
<Sound2></Sound2>
|
||||
<Sound3></Sound3>
|
||||
<SoundCollectionPath>%%DATAPATH%%sounds</SoundCollectionPath>
|
||||
<Value1>Armed</Value1>
|
||||
<Value2>0</Value2>
|
||||
</arr_1>
|
||||
<size>1</size>
|
||||
</Current>
|
||||
<EnableSound>true</EnableSound>
|
||||
<listNotifies>
|
||||
<arr_1>
|
||||
<CurrentLanguage>default</CurrentLanguage>
|
||||
<DataObject>FlightStatus</DataObject>
|
||||
<ExpireTimeout>15</ExpireTimeout>
|
||||
<Mute>false</Mute>
|
||||
<ObjectField>Armed</ObjectField>
|
||||
<RangeLimit>0</RangeLimit>
|
||||
<Repeat>0</Repeat>
|
||||
<SayOrder>0</SayOrder>
|
||||
<Sound1>armed</Sound1>
|
||||
<Sound2></Sound2>
|
||||
<Sound3></Sound3>
|
||||
<SoundCollectionPath>%%DATAPATH%%sounds</SoundCollectionPath>
|
||||
<Value1>Armed</Value1>
|
||||
<Value2>0</Value2>
|
||||
</arr_1>
|
||||
<size>1</size>
|
||||
</listNotifies>
|
||||
</data>
|
||||
</SoundNotifyPlugin>
|
||||
</Plugins>
|
||||
<SerialConnection>
|
||||
<speed>57600</speed>
|
||||
</SerialConnection>
|
||||
<UAVGadgetConfigurations>
|
||||
<ConfigGadget>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
</default>
|
||||
</ConfigGadget>
|
||||
<DialGadget>
|
||||
<Attitude>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/attitude.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Roll</needle1ObjectField>
|
||||
<needle2DataObject>AttitudeState</needle2DataObject>
|
||||
<needle2Factor>75</needle2Factor>
|
||||
<needle2MaxValue>20</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Vertical</needle2Move>
|
||||
<needle2ObjectField>Pitch</needle2ObjectField>
|
||||
<needle3DataObject>AttitudeState</needle3DataObject>
|
||||
<needle3Factor>-1</needle3Factor>
|
||||
<needle3MaxValue>360</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Roll</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Attitude>
|
||||
<Baro__PCT__20Altimeter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/altimeter.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>10</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Altitude</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Baro__PCT__20Altimeter>
|
||||
<Barometer>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/barometer.svg</dialFile>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>10</needle1Factor>
|
||||
<needle1MaxValue>1120</needle1MaxValue>
|
||||
<needle1MinValue>1000</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Pressure</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Barometer>
|
||||
<Climbrate>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/vsi.svg</dialFile>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>VelocityState</needle1DataObject>
|
||||
<needle1Factor>0.01</needle1Factor>
|
||||
<needle1MaxValue>12</needle1MaxValue>
|
||||
<needle1MinValue>-12</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Down</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Climbrate>
|
||||
<Compass>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/compass.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Yaw</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Compass>
|
||||
<Deluxe__PCT__20Attitude>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/attitude.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Roll</needle1ObjectField>
|
||||
<needle2DataObject>AttitudeState</needle2DataObject>
|
||||
<needle2Factor>75</needle2Factor>
|
||||
<needle2MaxValue>20</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Vertical</needle2Move>
|
||||
<needle2ObjectField>Pitch</needle2ObjectField>
|
||||
<needle3DataObject>AttitudeState</needle3DataObject>
|
||||
<needle3Factor>-1</needle3Factor>
|
||||
<needle3MaxValue>360</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Roll</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Attitude>
|
||||
<Deluxe__PCT__20Baro__PCT__20Altimeter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/altimeter.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>10</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Altitude</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Baro__PCT__20Altimeter>
|
||||
<Deluxe__PCT__20Barometer>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/barometer.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>10</needle1Factor>
|
||||
<needle1MaxValue>1120</needle1MaxValue>
|
||||
<needle1MinValue>1000</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Pressure</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Barometer>
|
||||
<Deluxe__PCT__20Climbrate>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/vsi.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>VelocityState</needle1DataObject>
|
||||
<needle1Factor>0.01</needle1Factor>
|
||||
<needle1MaxValue>11.2</needle1MaxValue>
|
||||
<needle1MinValue>-11.2</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Down</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Climbrate>
|
||||
<Deluxe__PCT__20Compass>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/compass.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Yaw</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Compass>
|
||||
<Deluxe__PCT__20Groundspeed__PCT__20kph>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/speed.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>GPSPositionSensor</needle1DataObject>
|
||||
<needle1Factor>3.6</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Groundspeed</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Groundspeed__PCT__20kph>
|
||||
<Deluxe__PCT__20Temperature>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/deluxe/thermometer.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Temperature</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Temperature>
|
||||
<Deluxe__PCT__20Turn__PCT__20Coordinator>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>/home/lafargue/OP/OpenPilot/trunk/artwork/Dials/deluxe/turncoordinator.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle2</dialNeedleID3>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Roll</needle1ObjectField>
|
||||
<needle2DataObject>AccelState</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>20</needle2MaxValue>
|
||||
<needle2MinValue>-20</needle2MinValue>
|
||||
<needle2Move>Horizontal</needle2Move>
|
||||
<needle2ObjectField>x</needle2ObjectField>
|
||||
<needle3DataObject>AccelState</needle3DataObject>
|
||||
<needle3Factor>-1</needle3Factor>
|
||||
<needle3MaxValue>360</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>x</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Deluxe__PCT__20Turn__PCT__20Coordinator>
|
||||
<Groundspeed__PCT__20kph>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/speed.svg</dialFile>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>GPSPositionSensor</needle1DataObject>
|
||||
<needle1Factor>3.6</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Groundspeed</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Groundspeed__PCT__20kph>
|
||||
<HiContrast__PCT__20Attitude>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/attitude.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Roll</needle1ObjectField>
|
||||
<needle2DataObject>AttitudeState</needle2DataObject>
|
||||
<needle2Factor>75</needle2Factor>
|
||||
<needle2MaxValue>20</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Vertical</needle2Move>
|
||||
<needle2ObjectField>Pitch</needle2ObjectField>
|
||||
<needle3DataObject>AttitudeState</needle3DataObject>
|
||||
<needle3Factor>-1</needle3Factor>
|
||||
<needle3MaxValue>360</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Roll</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Attitude>
|
||||
<HiContrast__PCT__20Baro__PCT__20Altimeter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/altimeter.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>10</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Altitude</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Baro__PCT__20Altimeter>
|
||||
<HiContrast__PCT__20Barometer>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/barometer.svg</dialFile>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>10</needle1Factor>
|
||||
<needle1MaxValue>1120</needle1MaxValue>
|
||||
<needle1MinValue>1000</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Pressure</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Barometer>
|
||||
<HiContrast__PCT__20Climbrate>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/vsi.svg</dialFile>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>VelocityState</needle1DataObject>
|
||||
<needle1Factor>0.01</needle1Factor>
|
||||
<needle1MaxValue>12</needle1MaxValue>
|
||||
<needle1MinValue>-12</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Down</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Climbrate>
|
||||
<HiContrast__PCT__20Compass>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/compass.svg</dialFile>
|
||||
<dialForegroundID>foreground</dialForegroundID>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>AttitudeState</needle1DataObject>
|
||||
<needle1Factor>-1</needle1Factor>
|
||||
<needle1MaxValue>360</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Yaw</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Compass>
|
||||
<HiContrast__PCT__20Groundspeed__PCT__20kph>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/speed.svg</dialFile>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>GPSPositionSensor</needle1DataObject>
|
||||
<needle1Factor>3.6</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Groundspeed</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Groundspeed__PCT__20kph>
|
||||
<HiContrast__PCT__20Temperature>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/hi-contrast/thermometer.svg</dialFile>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Temperature</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</HiContrast__PCT__20Temperature>
|
||||
<Servo__PCT__20Channel__PCT__201>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/thermometer.svg</dialFile>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<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>
|
||||
<needle1MinValue>1000</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Channel-3</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Servo__PCT__20Channel__PCT__201>
|
||||
<Temperature>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<beSmooth>false</beSmooth>
|
||||
<dialBackgroundID>background</dialBackgroundID>
|
||||
<dialFile>%%DATAPATH%%dials/default/thermometer.svg</dialFile>
|
||||
<dialNeedleID1>needle</dialNeedleID1>
|
||||
<dialNeedleID2>needle2</dialNeedleID2>
|
||||
<dialNeedleID3>needle3</dialNeedleID3>
|
||||
<font>MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0</font>
|
||||
<needle1DataObject>BaroSensor</needle1DataObject>
|
||||
<needle1Factor>1</needle1Factor>
|
||||
<needle1MaxValue>120</needle1MaxValue>
|
||||
<needle1MinValue>0</needle1MinValue>
|
||||
<needle1Move>Rotate</needle1Move>
|
||||
<needle1ObjectField>Temperature</needle1ObjectField>
|
||||
<needle2DataObject>BaroSensor</needle2DataObject>
|
||||
<needle2Factor>1</needle2Factor>
|
||||
<needle2MaxValue>100</needle2MaxValue>
|
||||
<needle2MinValue>0</needle2MinValue>
|
||||
<needle2Move>Rotate</needle2Move>
|
||||
<needle2ObjectField>Altitude</needle2ObjectField>
|
||||
<needle3DataObject>BaroSensor</needle3DataObject>
|
||||
<needle3Factor>1</needle3Factor>
|
||||
<needle3MaxValue>1000</needle3MaxValue>
|
||||
<needle3MinValue>0</needle3MinValue>
|
||||
<needle3Move>Rotate</needle3Move>
|
||||
<needle3ObjectField>Altitude</needle3ObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
</data>
|
||||
</Temperature>
|
||||
</DialGadget>
|
||||
<GCSControlGadget>
|
||||
<MS__PCT__20Sidewinder>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<button0Action>0</button0Action>
|
||||
<button0Amount>0</button0Amount>
|
||||
<button0Function>0</button0Function>
|
||||
<button1Action>0</button1Action>
|
||||
<button1Amount>0</button1Amount>
|
||||
<button1Function>0</button1Function>
|
||||
<button2Action>0</button2Action>
|
||||
<button2Amount>0.1</button2Amount>
|
||||
<button2Function>3</button2Function>
|
||||
<button3Action>0</button3Action>
|
||||
<button3Amount>0.1</button3Amount>
|
||||
<button3Function>3</button3Function>
|
||||
<button4Action>0</button4Action>
|
||||
<button4Amount>0</button4Amount>
|
||||
<button4Function>0</button4Function>
|
||||
<button5Action>0</button5Action>
|
||||
<button5Amount>0</button5Amount>
|
||||
<button5Function>0</button5Function>
|
||||
<button6Action>0</button6Action>
|
||||
<button6Amount>0</button6Amount>
|
||||
<button6Function>0</button6Function>
|
||||
<button7Action>0</button7Action>
|
||||
<button7Amount>0</button7Amount>
|
||||
<button7Function>0</button7Function>
|
||||
<channel0Reverse>false</channel0Reverse>
|
||||
<channel1Reverse>false</channel1Reverse>
|
||||
<channel2Reverse>true</channel2Reverse>
|
||||
<channel3Reverse>false</channel3Reverse>
|
||||
<channel4Reverse>false</channel4Reverse>
|
||||
<channel5Reverse>false</channel5Reverse>
|
||||
<channel6Reverse>false</channel6Reverse>
|
||||
<channel7Reverse>false</channel7Reverse>
|
||||
<controlPortUDP>0</controlPortUDP>
|
||||
<controlsMode>2</controlsMode>
|
||||
<pitchChannel>1</pitchChannel>
|
||||
<rollChannel>0</rollChannel>
|
||||
<throttleChannel>2</throttleChannel>
|
||||
<yawChannel>3</yawChannel>
|
||||
</data>
|
||||
</MS__PCT__20Sidewinder>
|
||||
</GCSControlGadget>
|
||||
<GpsDisplayGadget>
|
||||
<Flight__PCT__20GPS>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<connectionMode>Telemetry</connectionMode>
|
||||
<defaultDataBits>3</defaultDataBits>
|
||||
<defaultFlow>0</defaultFlow>
|
||||
<defaultParity>0</defaultParity>
|
||||
<defaultPort>Communications Port (COM1)</defaultPort>
|
||||
<defaultSpeed>11</defaultSpeed>
|
||||
<defaultStopBits>0</defaultStopBits>
|
||||
</data>
|
||||
</Flight__PCT__20GPS>
|
||||
<GPS__PCT__20Mouse>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<connectionMode>Serial</connectionMode>
|
||||
<defaultDataBits>3</defaultDataBits>
|
||||
<defaultFlow>0</defaultFlow>
|
||||
<defaultParity>0</defaultParity>
|
||||
<defaultPort>Communications Port (COM1)</defaultPort>
|
||||
<defaultSpeed>17</defaultSpeed>
|
||||
<defaultStopBits>0</defaultStopBits>
|
||||
</data>
|
||||
</GPS__PCT__20Mouse>
|
||||
</GpsDisplayGadget>
|
||||
<HITL>
|
||||
<AeroSimRC__PCT__20HITL>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<addNoise>false</addNoise>
|
||||
<attActCalc>false</attActCalc>
|
||||
<attActHW>false</attActHW>
|
||||
<attActSim>true</attActSim>
|
||||
<attStateEnabled>true</attStateEnabled>
|
||||
<attRawEnabled>true</attRawEnabled>
|
||||
<attRawRate>20</attRawRate>
|
||||
<baroAltRate>50</baroAltRate>
|
||||
<baroAltitudeEnabled>false</baroAltitudeEnabled>
|
||||
<binPath></binPath>
|
||||
<dataPath></dataPath>
|
||||
<gcsReceiverEnabled>true</gcsReceiverEnabled>
|
||||
<gpsPosRate>100</gpsPosRate>
|
||||
<gpsPositionEnabled>false</gpsPositionEnabled>
|
||||
<groundTruthEnabled>true</groundTruthEnabled>
|
||||
<groundTruthRate>100</groundTruthRate>
|
||||
<hostAddress>0.0.0.0</hostAddress>
|
||||
<inPort>40100</inPort>
|
||||
<inputCommand>true</inputCommand>
|
||||
<latitude></latitude>
|
||||
<longitude></longitude>
|
||||
<manualControlEnabled>false</manualControlEnabled>
|
||||
<manualOutput>false</manualOutput>
|
||||
<minOutputPeriod>40</minOutputPeriod>
|
||||
<outPort>40200</outPort>
|
||||
<remoteAddress>127.0.0.1</remoteAddress>
|
||||
<simulatorId>ASimRC</simulatorId>
|
||||
<startSim>false</startSim>
|
||||
</data>
|
||||
</AeroSimRC__PCT__20HITL>
|
||||
<Flightgear__PCT__20HITL>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<addNoise>false</addNoise>
|
||||
<attActCalc>false</attActCalc>
|
||||
<attActHW>false</attActHW>
|
||||
<attActSim>true</attActSim>
|
||||
<attStateEnabled>true</attStateEnabled>
|
||||
<attRawEnabled>true</attRawEnabled>
|
||||
<attRawRate>20</attRawRate>
|
||||
<baroAltRate>50</baroAltRate>
|
||||
<baroAltitudeEnabled>false</baroAltitudeEnabled>
|
||||
<binPath>\usr\games\fgfs</binPath>
|
||||
<dataPath>\usr\share\games\FlightGear</dataPath>
|
||||
<gcsReceiverEnabled>false</gcsReceiverEnabled>
|
||||
<gpsPosRate>100</gpsPosRate>
|
||||
<gpsPositionEnabled>false</gpsPositionEnabled>
|
||||
<groundTruthEnabled>true</groundTruthEnabled>
|
||||
<groundTruthRate>100</groundTruthRate>
|
||||
<hostAddress>127.0.0.1</hostAddress>
|
||||
<inPort>9009</inPort>
|
||||
<inputCommand>true</inputCommand>
|
||||
<latitude></latitude>
|
||||
<longitude></longitude>
|
||||
<manualControlEnabled>true</manualControlEnabled>
|
||||
<manualOutput>false</manualOutput>
|
||||
<minOutputPeriod>40</minOutputPeriod>
|
||||
<outPort>9010</outPort>
|
||||
<remoteAddress>127.0.0.1</remoteAddress>
|
||||
<simulatorId>FG</simulatorId>
|
||||
<startSim>true</startSim>
|
||||
</data>
|
||||
</Flightgear__PCT__20HITL>
|
||||
<XPlane__PCT__20HITL>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<addNoise>false</addNoise>
|
||||
<attActCalc>false</attActCalc>
|
||||
<attActHW>false</attActHW>
|
||||
<attActSim>true</attActSim>
|
||||
<attStateEnabled>true</attStateEnabled>
|
||||
<attRawEnabled>true</attRawEnabled>
|
||||
<attRawRate>20</attRawRate>
|
||||
<baroAltRate>50</baroAltRate>
|
||||
<baroAltitudeEnabled>false</baroAltitudeEnabled>
|
||||
<binPath></binPath>
|
||||
<dataPath></dataPath>
|
||||
<gcsReceiverEnabled>false</gcsReceiverEnabled>
|
||||
<gpsPosRate>100</gpsPosRate>
|
||||
<gpsPositionEnabled>false</gpsPositionEnabled>
|
||||
<groundTruthEnabled>true</groundTruthEnabled>
|
||||
<groundTruthRate>100</groundTruthRate>
|
||||
<hostAddress>0.0.0.0</hostAddress>
|
||||
<inPort>6756</inPort>
|
||||
<inputCommand>true</inputCommand>
|
||||
<latitude></latitude>
|
||||
<longitude></longitude>
|
||||
<manualControlEnabled>true</manualControlEnabled>
|
||||
<manualOutput>false</manualOutput>
|
||||
<minOutputPeriod>40</minOutputPeriod>
|
||||
<outPort>49000</outPort>
|
||||
<remoteAddress>127.0.0.1</remoteAddress>
|
||||
<simulatorId>X-Plane</simulatorId>
|
||||
<startSim>false</startSim>
|
||||
</data>
|
||||
</XPlane__PCT__20HITL>
|
||||
</HITL>
|
||||
<LineardialGadget>
|
||||
<Accel__PCT__20Horizontal__PCT__20X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,8,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>-9</greenMax>
|
||||
<greenMin>-10</greenMin>
|
||||
<maxValue>11</maxValue>
|
||||
<minValue>-11</minValue>
|
||||
<redMax>11</redMax>
|
||||
<redMin>-11</redMin>
|
||||
<sourceDataObject>AccelState</sourceDataObject>
|
||||
<sourceObjectField>x</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>-5</yellowMax>
|
||||
<yellowMin>-11</yellowMin>
|
||||
</data>
|
||||
</Accel__PCT__20Horizontal__PCT__20X>
|
||||
<Accel__PCT__20Horizontal__PCT__20Y>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,6,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>-9</greenMax>
|
||||
<greenMin>-10</greenMin>
|
||||
<maxValue>11</maxValue>
|
||||
<minValue>-11</minValue>
|
||||
<redMax>11</redMax>
|
||||
<redMin>-11</redMin>
|
||||
<sourceDataObject>AccelState</sourceDataObject>
|
||||
<sourceObjectField>y</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>-5</yellowMax>
|
||||
<yellowMin>-11</yellowMin>
|
||||
</data>
|
||||
</Accel__PCT__20Horizontal__PCT__20Y>
|
||||
<Accel__PCT__20Horizontal__PCT__20Z>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,8,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>-9</greenMax>
|
||||
<greenMin>-10</greenMin>
|
||||
<maxValue>11</maxValue>
|
||||
<minValue>-11</minValue>
|
||||
<redMax>11</redMax>
|
||||
<redMin>-11</redMin>
|
||||
<sourceDataObject>AccelState</sourceDataObject>
|
||||
<sourceObjectField>z</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>-5</yellowMax>
|
||||
<yellowMin>-11</yellowMin>
|
||||
</data>
|
||||
</Accel__PCT__20Horizontal__PCT__20Z>
|
||||
<Arm__PCT__20Status>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/arm-status.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>33</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>FlightStatus</sourceDataObject>
|
||||
<sourceObjectField>Armed</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>66</yellowMax>
|
||||
<yellowMin>33</yellowMin>
|
||||
</data>
|
||||
</Arm__PCT__20Status>
|
||||
<Flight__PCT__20Time>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/textonly.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>0.001</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>33</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>SystemStats</sourceDataObject>
|
||||
<sourceObjectField>FlightTime</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>66</yellowMax>
|
||||
<yellowMin>33</yellowMin>
|
||||
</data>
|
||||
</Flight__PCT__20Time>
|
||||
<Flight__PCT__20mode>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/flightmode-status.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>33</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>FlightStatus</sourceDataObject>
|
||||
<sourceObjectField>FlightMode</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>66</yellowMax>
|
||||
<yellowMin>33</yellowMin>
|
||||
</data>
|
||||
</Flight__PCT__20mode>
|
||||
<GPS__PCT__20Sats>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/gps-signal.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>0</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>12</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>0</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>GPSPositionSensor</sourceDataObject>
|
||||
<sourceObjectField>Satellites</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0</yellowMax>
|
||||
<yellowMin>0</yellowMin>
|
||||
</data>
|
||||
</GPS__PCT__20Sats>
|
||||
<GPS__PCT__20Status>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/default/gps-status.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>,12,-1,5,50,0,0,0,0,0</font>
|
||||
<greenMax>100</greenMax>
|
||||
<greenMin>66</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>33</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>GPSPositionSensor</sourceDataObject>
|
||||
<sourceObjectField>Status</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>66</yellowMax>
|
||||
<yellowMin>33</yellowMin>
|
||||
</data>
|
||||
</GPS__PCT__20Status>
|
||||
<Mainboard__PCT__20CPU>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>90</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>100</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>100</redMax>
|
||||
<redMin>95</redMin>
|
||||
<sourceDataObject>SystemStats</sourceDataObject>
|
||||
<sourceObjectField>CPULoad</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>95</yellowMax>
|
||||
<yellowMin>90</yellowMin>
|
||||
</data>
|
||||
</Mainboard__PCT__20CPU>
|
||||
<Pitch__PCT__20Desired>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ActuatorDesired</sourceDataObject>
|
||||
<sourceObjectField>Pitch</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Pitch__PCT__20Desired>
|
||||
<Pitch>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ManualControlCommand</sourceDataObject>
|
||||
<sourceObjectField>Pitch</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Pitch>
|
||||
<PitchState>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.8</greenMax>
|
||||
<greenMin>0.3</greenMin>
|
||||
<maxValue>90</maxValue>
|
||||
<minValue>-90</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>0</redMin>
|
||||
<sourceDataObject>AttitudeState</sourceDataObject>
|
||||
<sourceObjectField>Pitch</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.9</yellowMax>
|
||||
<yellowMin>0.1</yellowMin>
|
||||
</data>
|
||||
</PitchState>
|
||||
<Roll__PCT__20Desired>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ActuatorDesired</sourceDataObject>
|
||||
<sourceObjectField>Roll</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Roll__PCT__20Desired>
|
||||
<Roll>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ManualControlCommand</sourceDataObject>
|
||||
<sourceObjectField>Roll</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Roll>
|
||||
<Telemetry__PCT__20RX__PCT__20Rate__PCT__20Horizontal>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>650</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>1200</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>1200</redMax>
|
||||
<redMin>900</redMin>
|
||||
<sourceDataObject>GCSTelemetryStats</sourceDataObject>
|
||||
<sourceObjectField>RxDataRate</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>900</yellowMax>
|
||||
<yellowMin>650</yellowMin>
|
||||
</data>
|
||||
</Telemetry__PCT__20RX__PCT__20Rate__PCT__20Horizontal>
|
||||
<Telemetry__PCT__20TX__PCT__20Rate__PCT__20Horizontal>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-horizontal.svg</dFile>
|
||||
<decimalPlaces>0</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>650</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>1200</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>1200</redMax>
|
||||
<redMin>900</redMin>
|
||||
<sourceDataObject>GCSTelemetryStats</sourceDataObject>
|
||||
<sourceObjectField>TxDataRate</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>900</yellowMax>
|
||||
<yellowMin>650</yellowMin>
|
||||
</data>
|
||||
</Telemetry__PCT__20TX__PCT__20Rate__PCT__20Horizontal>
|
||||
<Throttle>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>0</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>0</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>0.75</redMin>
|
||||
<sourceDataObject>ManualControlCommand</sourceDataObject>
|
||||
<sourceObjectField>Throttle</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.75</yellowMax>
|
||||
<yellowMin>0.5</yellowMin>
|
||||
</data>
|
||||
</Throttle>
|
||||
<Yaw__PCT__20Desired>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ActuatorDesired</sourceDataObject>
|
||||
<sourceObjectField>Yaw</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Yaw__PCT__20Desired>
|
||||
<Yaw>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dFile>%%DATAPATH%%dials/deluxe/lineardial-vertical.svg</dFile>
|
||||
<decimalPlaces>2</decimalPlaces>
|
||||
<factor>1</factor>
|
||||
<font>Andale Mono,12,-1,5,75,0,0,0,0,0</font>
|
||||
<greenMax>0.5</greenMax>
|
||||
<greenMin>-0.5</greenMin>
|
||||
<maxValue>1</maxValue>
|
||||
<minValue>-1</minValue>
|
||||
<redMax>1</redMax>
|
||||
<redMin>-1</redMin>
|
||||
<sourceDataObject>ManualControlCommand</sourceDataObject>
|
||||
<sourceObjectField>Yaw</sourceObjectField>
|
||||
<useOpenGLFlag>false</useOpenGLFlag>
|
||||
<yellowMax>0.8</yellowMax>
|
||||
<yellowMin>-0.8</yellowMin>
|
||||
</data>
|
||||
</Yaw>
|
||||
</LineardialGadget>
|
||||
<ModelViewGadget>
|
||||
<Aeroquad__PCT__20__PCT__2B>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/aeroquad/aeroquad_+.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Aeroquad__PCT__20__PCT__2B>
|
||||
<CC3D>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/boards/CC3D/CC3D.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</CC3D>
|
||||
<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>
|
||||
<Danker__PCT__27s__PCT__20Quad>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/dankers_quad/dankers_quad.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Danker__PCT__27s__PCT__20Quad>
|
||||
<Easyquad__PCT__20X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/easy_quad/easy_quad_X.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Easyquad__PCT__20X>
|
||||
<Easystar>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/planes/Easystar/easystar.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Easystar>
|
||||
<Firecracker>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/planes/firecracker/firecracker.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Firecracker>
|
||||
<Funjet>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/planes/funjet/funjet.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Funjet>
|
||||
<Gaui__PCT__20330X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/gaui_330x/gaui_330x.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Gaui__PCT__20330X>
|
||||
<Helicopter__PCT__20-__PCT__20TRex__PCT__20450>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/helis/t-rex/t-rex_450_xl.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Helicopter__PCT__20-__PCT__20TRex__PCT__20450>
|
||||
<Hexacopter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/mikrokopter/MK_Hexa.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Hexacopter>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-Q_+.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20X__PCT__20>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-Q_X.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20X__PCT__20>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-QT_+.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-QT_X.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20X>
|
||||
<MattL__PCT__27s__PCT__20Y6>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/mattL_Y6/mattL_Y6.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</MattL__PCT__27s__PCT__20Y6>
|
||||
<Quadcopter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/mikrokopter/MK_L4-ME.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<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>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/scorpion_tricopter/scorpion_tricopter.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Scorpion__PCT__20Tricopter>
|
||||
<Test__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/test_quad/test_quad_+.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Test__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<Test__PCT__20Quad__PCT__20X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/test_quad/test_quad_X.3ds</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Test__PCT__20Quad__PCT__20X>
|
||||
</ModelViewGadget>
|
||||
<OPMapGadget>
|
||||
<Google__PCT__20Sat>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<accessMode>ServerAndCache</accessMode>
|
||||
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
|
||||
<defaultLatitude>0</defaultLatitude>
|
||||
<defaultLongitude>0</defaultLongitude>
|
||||
<defaultZoom>2</defaultZoom>
|
||||
<mapProvider>GoogleSatellite</mapProvider>
|
||||
<maxUpdateRate>2000</maxUpdateRate>
|
||||
<overlayOpacity>1</overlayOpacity>
|
||||
<showTileGridLines>false</showTileGridLines>
|
||||
<uavSymbol>mapquad.png</uavSymbol>
|
||||
<useMemoryCache>true</useMemoryCache>
|
||||
<useOpenGL>true</useOpenGL>
|
||||
</data>
|
||||
</Google__PCT__20Sat>
|
||||
<Memory__PCT__20Only>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<accessMode>CacheOnly</accessMode>
|
||||
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
|
||||
<defaultLatitude>0</defaultLatitude>
|
||||
<defaultLongitude>0</defaultLongitude>
|
||||
<defaultZoom>2</defaultZoom>
|
||||
<mapProvider>GoogleMap</mapProvider>
|
||||
<maxUpdateRate>2000</maxUpdateRate>
|
||||
<overlayOpacity>1</overlayOpacity>
|
||||
<showTileGridLines>false</showTileGridLines>
|
||||
<uavSymbol>airplanepip.png</uavSymbol>
|
||||
<useMemoryCache>true</useMemoryCache>
|
||||
<useOpenGL>true</useOpenGL>
|
||||
</data>
|
||||
</Memory__PCT__20Only>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<accessMode>ServerAndCache</accessMode>
|
||||
<cacheLocation>%%STOREPATH%%mapscache/</cacheLocation>
|
||||
<defaultLatitude>0</defaultLatitude>
|
||||
<defaultLongitude>0</defaultLongitude>
|
||||
<defaultZoom>2</defaultZoom>
|
||||
<mapProvider>GoogleMap</mapProvider>
|
||||
<maxUpdateRate>2000</maxUpdateRate>
|
||||
<overlayOpacity>1</overlayOpacity>
|
||||
<showTileGridLines>false</showTileGridLines>
|
||||
<uavSymbol>mapquad.png</uavSymbol>
|
||||
<useMemoryCache>true</useMemoryCache>
|
||||
<useOpenGL>true</useOpenGL>
|
||||
</data>
|
||||
</default>
|
||||
</OPMapGadget>
|
||||
<PfdQmlGadget>
|
||||
<NoTerrain>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<actualPositionUsed>false</actualPositionUsed>
|
||||
<altitude>2000</altitude>
|
||||
<altitudeFactor>1</altitudeFactor>
|
||||
<cacheOnly>false</cacheOnly>
|
||||
<earthFile>%%DATAPATH%%pfd/default/readymap.earth</earthFile>
|
||||
<latitude>46.6715</latitude>
|
||||
<longitude>10.1589</longitude>
|
||||
<openGLEnabled>true</openGLEnabled>
|
||||
<qmlFile>%%DATAPATH%%pfd/default/Pfd.qml</qmlFile>
|
||||
<speedFactor>1</speedFactor>
|
||||
<terrainEnabled>false</terrainEnabled>
|
||||
</data>
|
||||
</NoTerrain>
|
||||
<Terrain>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<actualPositionUsed>false</actualPositionUsed>
|
||||
<altitude>2000</altitude>
|
||||
<cacheOnly>false</cacheOnly>
|
||||
<earthFile>%%DATAPATH%%pfd/default/readymap.earth</earthFile>
|
||||
<latitude>46.6715</latitude>
|
||||
<longitude>10.1589</longitude>
|
||||
<openGLEnabled>true</openGLEnabled>
|
||||
<qmlFile>%%DATAPATH%%pfd/default/Pfd.qml</qmlFile>
|
||||
<terrainEnabled>false</terrainEnabled>
|
||||
</data>
|
||||
</Terrain>
|
||||
</PfdQmlGadget>
|
||||
<QmlViewGadget>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<dialFile>Unknown</dialFile>
|
||||
<useOpenGLFlag>true</useOpenGLFlag>
|
||||
</data>
|
||||
</default>
|
||||
</QmlViewGadget>
|
||||
<ScopeGadget>
|
||||
<Accel>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>100</refreshInterval>
|
||||
</data>
|
||||
</Accel>
|
||||
<Actuators>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>20</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-4</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-5</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4289374847</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-6</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4289374847</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-7</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
<plotCurveCount>4</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>100</refreshInterval>
|
||||
</data>
|
||||
</Actuators>
|
||||
<Attitude>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4283760895</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Roll</uavField>
|
||||
<uavObject>AttitudeState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4278233600</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Yaw</uavField>
|
||||
<uavObject>AttitudeState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Pitch</uavField>
|
||||
<uavObject>AttitudeState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>100</refreshInterval>
|
||||
</data>
|
||||
</Attitude>
|
||||
<Barometer>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4278190080</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Pressure</uavField>
|
||||
<uavObject>BaroSensor</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurveCount>1</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>1000</refreshInterval>
|
||||
</data>
|
||||
</Barometer>
|
||||
<Inputs>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>40</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4278190207</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-1</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-4</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-5</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-6</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
<plotCurve4>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-7</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve4>
|
||||
<plotCurve5>
|
||||
<color>4283825920</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-2</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve5>
|
||||
<plotCurve6>
|
||||
<color>4294923520</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-3</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve6>
|
||||
<plotCurve7>
|
||||
<color>4294967040</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-0</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve7>
|
||||
<plotCurveCount>8</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>200</refreshInterval>
|
||||
</data>
|
||||
</Inputs>
|
||||
<Raw__PCT__20AccelState>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>AccelState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>500</refreshInterval>
|
||||
</data>
|
||||
</Raw__PCT__20AccelState>
|
||||
<Raw__PCT__20GyroState>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>GyroState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>GyroState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>GyroState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>500</refreshInterval>
|
||||
</data>
|
||||
</Raw__PCT__20GyroState>
|
||||
<Raw__PCT__20magnetometers>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>MagState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>MagState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>MagState</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>500</refreshInterval>
|
||||
</data>
|
||||
</Raw__PCT__20magnetometers>
|
||||
<Stacks__PCT__20monitor>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>240</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-System</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-CallbackScheduler0</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4278190335</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-CallbackScheduler1</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4294967040</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<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>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Altitude</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve7>
|
||||
<plotCurve8>
|
||||
<color>4283760767</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve8>
|
||||
<plotCurve9>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve9>
|
||||
<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>
|
||||
</Stacks__PCT__20monitor>
|
||||
<Telemetry__PCT__20quality>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>20</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4289374847</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>TxFailures</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>RxFailures</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>TxRetries</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurveCount>3</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>100</refreshInterval>
|
||||
</data>
|
||||
</Telemetry__PCT__20quality>
|
||||
<Uptimes>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<LoggingEnabled>false</LoggingEnabled>
|
||||
<LoggingNewFileOnConnect>false</LoggingNewFileOnConnect>
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>240</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294945407</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>FlightTime</uavField>
|
||||
<uavObject>SystemStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve0>
|
||||
<plotCurveCount>1</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>800</refreshInterval>
|
||||
</data>
|
||||
</Uptimes>
|
||||
</ScopeGadget>
|
||||
<SystemHealthGadget>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<diagram>%%DATAPATH%%diagrams/default/system-health.svg</diagram>
|
||||
</data>
|
||||
</default>
|
||||
</SystemHealthGadget>
|
||||
<UAVObjectBrowser>
|
||||
<default>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<CategorizedView>false</CategorizedView>
|
||||
<ScientificView>false</ScientificView>
|
||||
<manuallyChangedColor>#5baa56</manuallyChangedColor>
|
||||
<onlyHilightChangedValues>false</onlyHilightChangedValues>
|
||||
<recentlyUpdatedColor>#ff7957</recentlyUpdatedColor>
|
||||
<recentlyUpdatedTimeout>500</recentlyUpdatedTimeout>
|
||||
<showMetaData>false</showMetaData>
|
||||
</data>
|
||||
</default>
|
||||
</UAVObjectBrowser>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>1.2.0</version>
|
||||
</configInfo>
|
||||
</UAVGadgetConfigurations>
|
||||
<UAVGadgetManager>
|
||||
<Mode1>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<side0>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight Time</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Arm Status</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight mode</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAYwAAAAIAAAB7)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAZgAAAAIAAADf)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>PfdQmlGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>NoTerrain</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAG4)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>ModelViewGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Test Quad X</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>SystemHealthGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB1AAAAAIAAAGI)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACegAAAAIAAAFC)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>OPMapGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Google Sat</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADXgAAAAIAAAQd)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode1>
|
||||
<Mode2>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<classId>ConfigGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>UAVObjectBrowser</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAEeQAAAAIAAAMC)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode2>
|
||||
<Mode3>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<classId>UAVObjectBrowser</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>LoggingGadget</classId>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>GpsDisplayGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight GPS</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAVAAAAAIAAAGu)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAEvwAAAAIAAAK8)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode3>
|
||||
<Mode4>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>ScopeGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Accel</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>ScopeGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Raw GyroState</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>ScopeGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Attitude</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>ScopeGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Uptimes</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABhAAAAAIAAAGE)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACjQAAAAIAAAKU)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode4>
|
||||
<Mode5>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>HITL</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>XPlane HITL</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>HITLv2</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>PfdQmlGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>NoTerrain</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>MagicWaypointGadget</classId>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAGU)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>GCSControlGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>MS Sidewinder</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADhAAAAAIAAAIX)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADDAAAAAIAAAJJ)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode5>
|
||||
<Mode6>
|
||||
<showToolbars>false</showToolbars>
|
||||
<splitter>
|
||||
<side0>
|
||||
<classId>Uploader</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>LineardialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Flight Time</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>SystemHealthGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>default</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABQgAAAAIAAAGM)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<side0>
|
||||
<classId>DialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Deluxe Attitude</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>DialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Deluxe Baro Altimeter</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<side0>
|
||||
<classId>DialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Deluxe Compass</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side0>
|
||||
<side1>
|
||||
<classId>DialGadget</classId>
|
||||
<gadget>
|
||||
<activeConfiguration>Deluxe Climbrate</activeConfiguration>
|
||||
</gadget>
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAAHf)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADVQAAAAIAAAJK)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</splitter>
|
||||
<version>UAVGadgetManagerV1</version>
|
||||
</Mode6>
|
||||
</UAVGadgetManager>
|
||||
<Workspace>
|
||||
<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/cog.png</Icon3>
|
||||
<Icon4>:/core/images/scopes.png</Icon4>
|
||||
<Icon5>:/core/images/joystick.png</Icon5>
|
||||
<Icon6>:/core/images/cpu.png</Icon6>
|
||||
<Icon7>:/core/images/openpilot_logo_64.png</Icon7>
|
||||
<Icon8>:/core/images/openpilot_logo_64.png</Icon8>
|
||||
<Icon9>:/core/images/openpilot_logo_64.png</Icon9>
|
||||
<NumberOfWorkspaces>6</NumberOfWorkspaces>
|
||||
<TabBarPlacementIndex>1</TabBarPlacementIndex>
|
||||
<Workspace1>Flight data</Workspace1>
|
||||
<Workspace10>Workspace10</Workspace10>
|
||||
<Workspace2>Configuration</Workspace2>
|
||||
<Workspace3>System</Workspace3>
|
||||
<Workspace4>Scopes</Workspace4>
|
||||
<Workspace5>HITL</Workspace5>
|
||||
<Workspace6>Firmware</Workspace6>
|
||||
<Workspace7>Workspace7</Workspace7>
|
||||
<Workspace8>Workspace8</Workspace8>
|
||||
<Workspace9>Workspace9</Workspace9>
|
||||
</Workspace>
|
||||
</gcs>
|
@ -14,8 +14,8 @@
|
||||
height="79.57505"
|
||||
id="svg3604"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.2 r9819"
|
||||
sodipodi:docname="system-health.svg"
|
||||
inkscape:version="0.48.4 r9939"
|
||||
sodipodi:docname="system-health-mod.svg"
|
||||
inkscape:export-filename="C:\NoBackup\OpenPilot\mainboard-health.png"
|
||||
inkscape:export-xdpi="269.53"
|
||||
inkscape:export-ydpi="269.53"
|
||||
@ -27,16 +27,16 @@
|
||||
borderopacity="1.0"
|
||||
inkscape:pageopacity="0.0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:zoom="9.3551549"
|
||||
inkscape:cx="42.866204"
|
||||
inkscape:cy="35.940147"
|
||||
inkscape:current-layer="g4794"
|
||||
inkscape:zoom="10.554213"
|
||||
inkscape:cx="47.1292"
|
||||
inkscape:cy="39.787519"
|
||||
inkscape:current-layer="svg3604"
|
||||
id="namedview3608"
|
||||
showgrid="false"
|
||||
inkscape:window-width="1920"
|
||||
inkscape:window-height="1178"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="0"
|
||||
inkscape:window-height="1025"
|
||||
inkscape:window-x="-2"
|
||||
inkscape:window-y="-3"
|
||||
inkscape:window-maximized="1"
|
||||
showguides="true"
|
||||
inkscape:guide-bbox="true">
|
||||
@ -656,39 +656,48 @@
|
||||
<path
|
||||
id="path4061"
|
||||
style="font-size:9px;fill:#ffffff"
|
||||
d="m 524.3844,367.59399 1.32275,0 1.67432,4.46485 1.68311,-4.46485 1.32275,0 0,6.56104 -0.86572,0 0,-5.76123 -1.6919,4.5 -0.89209,0 -1.69189,-4.5 0,5.76123 -0.86133,0 0,-6.56104" />
|
||||
d="m 524.3844,367.59399 1.32275,0 1.67432,4.46485 1.68311,-4.46485 1.32275,0 0,6.56104 -0.86572,0 0,-5.76123 -1.6919,4.5 -0.89209,0 -1.69189,-4.5 0,5.76123 -0.86133,0 0,-6.56104"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path4063"
|
||||
style="font-size:9px;fill:#ffffff"
|
||||
d="m 534.35559,371.68091 c -0.65332,0 -1.10596,0.0747 -1.35791,0.22412 -0.25195,0.14942 -0.37793,0.4043 -0.37793,0.76465 0,0.28711 0.0937,0.51562 0.28125,0.68554 0.19043,0.167 0.44824,0.25049 0.77344,0.25049 0.44824,0 0.80712,-0.1582 1.07666,-0.47461 0.27246,-0.31933 0.40869,-0.74267 0.40869,-1.27002 l 0,-0.18017 -0.8042,0 m 1.61279,-0.33399 0,2.80811 -0.80859,0 0,-0.74707 c -0.18457,0.29883 -0.41455,0.52002 -0.68994,0.66357 -0.27539,0.14063 -0.61231,0.21094 -1.01074,0.21094 -0.50391,0 -0.90528,-0.14062 -1.20411,-0.42187 -0.29589,-0.28418 -0.44384,-0.66358 -0.44384,-1.13819 0,-0.55371 0.18457,-0.97119 0.55371,-1.25244 0.37207,-0.28125 0.92578,-0.42187 1.66113,-0.42187 l 1.13379,0 0,-0.0791 c 0,-0.37206 -0.12305,-0.65917 -0.36914,-0.86132 -0.24317,-0.20508 -0.58594,-0.30762 -1.02832,-0.30762 -0.28125,0 -0.55518,0.0337 -0.82178,0.10107 -0.2666,0.0674 -0.52295,0.16846 -0.76904,0.30323 l 0,-0.74707 c 0.2959,-0.11426 0.58301,-0.19922 0.86133,-0.25489 0.27832,-0.0586 0.54931,-0.0879 0.81299,-0.0879 0.71191,10e-6 1.24364,0.18458 1.59521,0.55371 0.35156,0.36915 0.52734,0.92872 0.52734,1.67871" />
|
||||
d="m 534.35559,371.68091 c -0.65332,0 -1.10596,0.0747 -1.35791,0.22412 -0.25195,0.14942 -0.37793,0.4043 -0.37793,0.76465 0,0.28711 0.0937,0.51562 0.28125,0.68554 0.19043,0.167 0.44824,0.25049 0.77344,0.25049 0.44824,0 0.80712,-0.1582 1.07666,-0.47461 0.27246,-0.31933 0.40869,-0.74267 0.40869,-1.27002 l 0,-0.18017 -0.8042,0 m 1.61279,-0.33399 0,2.80811 -0.80859,0 0,-0.74707 c -0.18457,0.29883 -0.41455,0.52002 -0.68994,0.66357 -0.27539,0.14063 -0.61231,0.21094 -1.01074,0.21094 -0.50391,0 -0.90528,-0.14062 -1.20411,-0.42187 -0.29589,-0.28418 -0.44384,-0.66358 -0.44384,-1.13819 0,-0.55371 0.18457,-0.97119 0.55371,-1.25244 0.37207,-0.28125 0.92578,-0.42187 1.66113,-0.42187 l 1.13379,0 0,-0.0791 c 0,-0.37206 -0.12305,-0.65917 -0.36914,-0.86132 -0.24317,-0.20508 -0.58594,-0.30762 -1.02832,-0.30762 -0.28125,0 -0.55518,0.0337 -0.82178,0.10107 -0.2666,0.0674 -0.52295,0.16846 -0.76904,0.30323 l 0,-0.74707 c 0.2959,-0.11426 0.58301,-0.19922 0.86133,-0.25489 0.27832,-0.0586 0.54931,-0.0879 0.81299,-0.0879 0.71191,10e-6 1.24364,0.18458 1.59521,0.55371 0.35156,0.36915 0.52734,0.92872 0.52734,1.67871"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path4065"
|
||||
style="font-size:9px;fill:#ffffff"
|
||||
d="m 537.63831,369.23315 0.80859,0 0,4.92188 -0.80859,0 0,-4.92188 m 0,-1.91601 0.80859,0 0,1.02392 -0.80859,0 0,-1.02392" />
|
||||
d="m 537.63831,369.23315 0.80859,0 0,4.92188 -0.80859,0 0,-4.92188 m 0,-1.91601 0.80859,0 0,1.02392 -0.80859,0 0,-1.02392"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path4067"
|
||||
style="font-size:9px;fill:#ffffff"
|
||||
d="m 544.22571,371.18433 0,2.9707 -0.8086,0 0,-2.94434 c 0,-0.46581 -0.0908,-0.81445 -0.27246,-1.0459 -0.18164,-0.23144 -0.4541,-0.34716 -0.81738,-0.34716 -0.43653,0 -0.78076,0.13916 -1.03271,0.41748 -0.25196,0.27832 -0.37794,0.65772 -0.37793,1.13818 l 0,2.78174 -0.81299,0 0,-4.92188 0.81299,0 0,0.76465 c 0.19335,-0.29589 0.4204,-0.51708 0.68115,-0.66357 0.26367,-0.14648 0.56689,-0.21972 0.90967,-0.21973 0.56542,10e-6 0.99316,0.17579 1.2832,0.52735 0.29003,0.34863 0.43505,0.86279 0.43506,1.54248" />
|
||||
d="m 544.22571,371.18433 0,2.9707 -0.8086,0 0,-2.94434 c 0,-0.46581 -0.0908,-0.81445 -0.27246,-1.0459 -0.18164,-0.23144 -0.4541,-0.34716 -0.81738,-0.34716 -0.43653,0 -0.78076,0.13916 -1.03271,0.41748 -0.25196,0.27832 -0.37794,0.65772 -0.37793,1.13818 l 0,2.78174 -0.81299,0 0,-4.92188 0.81299,0 0,0.76465 c 0.19335,-0.29589 0.4204,-0.51708 0.68115,-0.66357 0.26367,-0.14648 0.56689,-0.21972 0.90967,-0.21973 0.56542,10e-6 0.99316,0.17579 1.2832,0.52735 0.29003,0.34863 0.43505,0.86279 0.43506,1.54248"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path4069"
|
||||
style="font-size:9px;fill:#ffffff"
|
||||
d="m 549.38049,371.69849 c 0,-0.59473 -0.12305,-1.06055 -0.36914,-1.39746 -0.24317,-0.33984 -0.57861,-0.50977 -1.00635,-0.50977 -0.42773,0 -0.76465,0.16993 -1.01074,0.50977 -0.24316,0.33691 -0.36475,0.80273 -0.36474,1.39746 -10e-6,0.59472 0.12158,1.06201 0.36474,1.40185 0.24609,0.33692 0.58301,0.50537 1.01074,0.50537 0.42774,0 0.76318,-0.16845 1.00635,-0.50537 0.24609,-0.33984 0.36914,-0.80713 0.36914,-1.40185 m -2.75097,-1.71827 c 0.16992,-0.29296 0.38378,-0.50976 0.6416,-0.65039 0.26074,-0.14355 0.57128,-0.21532 0.93164,-0.21533 0.59765,10e-6 1.08251,0.23731 1.45459,0.71192 0.37499,0.47461 0.56249,1.09863 0.5625,1.87207 -10e-6,0.77344 -0.18751,1.39746 -0.5625,1.87207 -0.37208,0.47461 -0.85694,0.71191 -1.45459,0.71191 -0.36036,0 -0.6709,-0.0703 -0.93164,-0.21094 -0.25782,-0.14355 -0.47168,-0.36181 -0.6416,-0.65478 l 0,0.73828 -0.81299,0 0,-6.83789 0.81299,0 0,2.66308" />
|
||||
d="m 549.38049,371.69849 c 0,-0.59473 -0.12305,-1.06055 -0.36914,-1.39746 -0.24317,-0.33984 -0.57861,-0.50977 -1.00635,-0.50977 -0.42773,0 -0.76465,0.16993 -1.01074,0.50977 -0.24316,0.33691 -0.36475,0.80273 -0.36474,1.39746 -10e-6,0.59472 0.12158,1.06201 0.36474,1.40185 0.24609,0.33692 0.58301,0.50537 1.01074,0.50537 0.42774,0 0.76318,-0.16845 1.00635,-0.50537 0.24609,-0.33984 0.36914,-0.80713 0.36914,-1.40185 m -2.75097,-1.71827 c 0.16992,-0.29296 0.38378,-0.50976 0.6416,-0.65039 0.26074,-0.14355 0.57128,-0.21532 0.93164,-0.21533 0.59765,10e-6 1.08251,0.23731 1.45459,0.71192 0.37499,0.47461 0.56249,1.09863 0.5625,1.87207 -10e-6,0.77344 -0.18751,1.39746 -0.5625,1.87207 -0.37208,0.47461 -0.85694,0.71191 -1.45459,0.71191 -0.36036,0 -0.6709,-0.0703 -0.93164,-0.21094 -0.25782,-0.14355 -0.47168,-0.36181 -0.6416,-0.65478 l 0,0.73828 -0.81299,0 0,-6.83789 0.81299,0 0,2.66308"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path4071"
|
||||
style="font-size:9px;fill:#ffffff"
|
||||
d="m 553.46741,369.80005 c -0.4336,0 -0.77637,0.16992 -1.02832,0.50976 -0.25196,0.33692 -0.37793,0.79981 -0.37793,1.38868 0,0.58887 0.12451,1.05322 0.37353,1.39306 0.25195,0.33692 0.59619,0.50537 1.03272,0.50537 0.43066,0 0.77197,-0.16992 1.02392,-0.50976 0.25195,-0.33984 0.37793,-0.80273 0.37793,-1.38867 0,-0.58301 -0.12598,-1.04443 -0.37793,-1.38428 -0.25195,-0.34277 -0.59326,-0.51416 -1.02392,-0.51416 m 0,-0.68555 c 0.70312,10e-6 1.25536,0.22852 1.65674,0.68555 0.40136,0.45703 0.60204,1.08985 0.60205,1.89844 -10e-6,0.80566 -0.20069,1.43847 -0.60205,1.89843 -0.40138,0.45704 -0.95362,0.68555 -1.65674,0.68555 -0.70606,0 -1.25977,-0.22851 -1.66114,-0.68555 -0.39843,-0.45996 -0.59765,-1.09277 -0.59765,-1.89843 0,-0.80859 0.19922,-1.44141 0.59765,-1.89844 0.40137,-0.45703 0.95508,-0.68554 1.66114,-0.68555" />
|
||||
d="m 553.46741,369.80005 c -0.4336,0 -0.77637,0.16992 -1.02832,0.50976 -0.25196,0.33692 -0.37793,0.79981 -0.37793,1.38868 0,0.58887 0.12451,1.05322 0.37353,1.39306 0.25195,0.33692 0.59619,0.50537 1.03272,0.50537 0.43066,0 0.77197,-0.16992 1.02392,-0.50976 0.25195,-0.33984 0.37793,-0.80273 0.37793,-1.38867 0,-0.58301 -0.12598,-1.04443 -0.37793,-1.38428 -0.25195,-0.34277 -0.59326,-0.51416 -1.02392,-0.51416 m 0,-0.68555 c 0.70312,10e-6 1.25536,0.22852 1.65674,0.68555 0.40136,0.45703 0.60204,1.08985 0.60205,1.89844 -10e-6,0.80566 -0.20069,1.43847 -0.60205,1.89843 -0.40138,0.45704 -0.95362,0.68555 -1.65674,0.68555 -0.70606,0 -1.25977,-0.22851 -1.66114,-0.68555 -0.39843,-0.45996 -0.59765,-1.09277 -0.59765,-1.89843 0,-0.80859 0.19922,-1.44141 0.59765,-1.89844 0.40137,-0.45703 0.95508,-0.68554 1.66114,-0.68555"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path4073"
|
||||
style="font-size:9px;fill:#ffffff"
|
||||
d="m 559.29895,371.68091 c -0.65332,0 -1.10596,0.0747 -1.35791,0.22412 -0.25195,0.14942 -0.37793,0.4043 -0.37793,0.76465 0,0.28711 0.0937,0.51562 0.28125,0.68554 0.19043,0.167 0.44824,0.25049 0.77344,0.25049 0.44824,0 0.80712,-0.1582 1.07666,-0.47461 0.27246,-0.31933 0.40869,-0.74267 0.40869,-1.27002 l 0,-0.18017 -0.8042,0 m 1.61279,-0.33399 0,2.80811 -0.80859,0 0,-0.74707 c -0.18457,0.29883 -0.41455,0.52002 -0.68994,0.66357 -0.2754,0.14063 -0.61231,0.21094 -1.01074,0.21094 -0.50391,0 -0.90528,-0.14062 -1.20411,-0.42187 -0.29589,-0.28418 -0.44384,-0.66358 -0.44384,-1.13819 0,-0.55371 0.18457,-0.97119 0.55371,-1.25244 0.37207,-0.28125 0.92578,-0.42187 1.66113,-0.42187 l 1.13379,0 0,-0.0791 c 0,-0.37206 -0.12305,-0.65917 -0.36914,-0.86132 -0.24317,-0.20508 -0.58594,-0.30762 -1.02832,-0.30762 -0.28125,0 -0.55518,0.0337 -0.82178,0.10107 -0.2666,0.0674 -0.52295,0.16846 -0.76904,0.30323 l 0,-0.74707 c 0.2959,-0.11426 0.583,-0.19922 0.86133,-0.25489 0.27831,-0.0586 0.54931,-0.0879 0.81298,-0.0879 0.71192,10e-6 1.24365,0.18458 1.59522,0.55371 0.35156,0.36915 0.52734,0.92872 0.52734,1.67871" />
|
||||
d="m 559.29895,371.68091 c -0.65332,0 -1.10596,0.0747 -1.35791,0.22412 -0.25195,0.14942 -0.37793,0.4043 -0.37793,0.76465 0,0.28711 0.0937,0.51562 0.28125,0.68554 0.19043,0.167 0.44824,0.25049 0.77344,0.25049 0.44824,0 0.80712,-0.1582 1.07666,-0.47461 0.27246,-0.31933 0.40869,-0.74267 0.40869,-1.27002 l 0,-0.18017 -0.8042,0 m 1.61279,-0.33399 0,2.80811 -0.80859,0 0,-0.74707 c -0.18457,0.29883 -0.41455,0.52002 -0.68994,0.66357 -0.2754,0.14063 -0.61231,0.21094 -1.01074,0.21094 -0.50391,0 -0.90528,-0.14062 -1.20411,-0.42187 -0.29589,-0.28418 -0.44384,-0.66358 -0.44384,-1.13819 0,-0.55371 0.18457,-0.97119 0.55371,-1.25244 0.37207,-0.28125 0.92578,-0.42187 1.66113,-0.42187 l 1.13379,0 0,-0.0791 c 0,-0.37206 -0.12305,-0.65917 -0.36914,-0.86132 -0.24317,-0.20508 -0.58594,-0.30762 -1.02832,-0.30762 -0.28125,0 -0.55518,0.0337 -0.82178,0.10107 -0.2666,0.0674 -0.52295,0.16846 -0.76904,0.30323 l 0,-0.74707 c 0.2959,-0.11426 0.583,-0.19922 0.86133,-0.25489 0.27831,-0.0586 0.54931,-0.0879 0.81298,-0.0879 0.71192,10e-6 1.24365,0.18458 1.59522,0.55371 0.35156,0.36915 0.52734,0.92872 0.52734,1.67871"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path4075"
|
||||
style="font-size:9px;fill:#ffffff"
|
||||
d="m 565.43372,369.98901 c -0.0908,-0.0527 -0.19044,-0.0908 -0.29883,-0.11425 -0.10547,-0.0264 -0.22266,-0.0395 -0.35156,-0.0395 -0.45704,0 -0.8086,0.14941 -1.05469,0.44824 -0.24317,0.2959 -0.36475,0.72217 -0.36475,1.27881 l 0,2.59277 -0.81299,0 0,-4.92188 0.81299,0 0,0.76465 c 0.16992,-0.29882 0.39111,-0.52001 0.66358,-0.66357 0.27245,-0.14648 0.60351,-0.21972 0.99316,-0.21973 0.0557,10e-6 0.11718,0.004 0.18457,0.0132 0.0674,0.006 0.14209,0.0161 0.22412,0.0308 l 0.004,0.83056" />
|
||||
d="m 565.43372,369.98901 c -0.0908,-0.0527 -0.19044,-0.0908 -0.29883,-0.11425 -0.10547,-0.0264 -0.22266,-0.0395 -0.35156,-0.0395 -0.45704,0 -0.8086,0.14941 -1.05469,0.44824 -0.24317,0.2959 -0.36475,0.72217 -0.36475,1.27881 l 0,2.59277 -0.81299,0 0,-4.92188 0.81299,0 0,0.76465 c 0.16992,-0.29882 0.39111,-0.52001 0.66358,-0.66357 0.27245,-0.14648 0.60351,-0.21972 0.99316,-0.21973 0.0557,10e-6 0.11718,0.004 0.18457,0.0132 0.0674,0.006 0.14209,0.0161 0.22412,0.0308 l 0.004,0.83056"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
id="path4077"
|
||||
style="font-size:9px;fill:#ffffff"
|
||||
d="m 569.37122,369.98022 0,-2.66308 0.80859,0 0,6.83789 -0.80859,0 0,-0.73828 c -0.16993,0.29297 -0.38526,0.51123 -0.646,0.65478 -0.25782,0.14063 -0.56836,0.21094 -0.93164,0.21094 -0.59473,0 -1.07959,-0.2373 -1.45459,-0.71191 -0.37207,-0.47461 -0.55811,-1.09863 -0.55811,-1.87207 0,-0.77344 0.18604,-1.39746 0.55811,-1.87207 0.375,-0.47461 0.85986,-0.71191 1.45459,-0.71192 0.36328,10e-6 0.67382,0.0718 0.93164,0.21533 0.26074,0.14063 0.47607,0.35743 0.646,0.65039 m -2.75538,1.71827 c 0,0.59472 0.12159,1.06201 0.36475,1.40185 0.24609,0.33692 0.58301,0.50537 1.01074,0.50537 0.42773,0 0.76465,-0.16845 1.01075,-0.50537 0.24608,-0.33984 0.36913,-0.80713 0.36914,-1.40185 -10e-6,-0.59473 -0.12306,-1.06055 -0.36914,-1.39746 -0.2461,-0.33984 -0.58302,-0.50977 -1.01075,-0.50977 -0.42773,0 -0.76465,0.16993 -1.01074,0.50977 -0.24316,0.33691 -0.36475,0.80273 -0.36475,1.39746" />
|
||||
d="m 569.37122,369.98022 0,-2.66308 0.80859,0 0,6.83789 -0.80859,0 0,-0.73828 c -0.16993,0.29297 -0.38526,0.51123 -0.646,0.65478 -0.25782,0.14063 -0.56836,0.21094 -0.93164,0.21094 -0.59473,0 -1.07959,-0.2373 -1.45459,-0.71191 -0.37207,-0.47461 -0.55811,-1.09863 -0.55811,-1.87207 0,-0.77344 0.18604,-1.39746 0.55811,-1.87207 0.375,-0.47461 0.85986,-0.71191 1.45459,-0.71192 0.36328,10e-6 0.67382,0.0718 0.93164,0.21533 0.26074,0.14063 0.47607,0.35743 0.646,0.65039 m -2.75538,1.71827 c 0,0.59472 0.12159,1.06201 0.36475,1.40185 0.24609,0.33692 0.58301,0.50537 1.01074,0.50537 0.42773,0 0.76465,-0.16845 1.01075,-0.50537 0.24608,-0.33984 0.36913,-0.80713 0.36914,-1.40185 -10e-6,-0.59473 -0.12306,-1.06055 -0.36914,-1.39746 -0.2461,-0.33984 -0.58302,-0.50977 -1.01075,-0.50977 -0.42773,0 -0.76465,0.16993 -1.01074,0.50977 -0.24316,0.33691 -0.36475,0.80273 -0.36475,1.39746"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<rect
|
||||
inkscape:label="#rect4000-8-5"
|
||||
@ -712,7 +721,7 @@
|
||||
id="Power"
|
||||
width="18.023544"
|
||||
height="8.2846708"
|
||||
x="501.80048"
|
||||
x="499.24579"
|
||||
y="346.10165" />
|
||||
<rect
|
||||
inkscape:label="#rect4000-7-6-2-2111"
|
||||
@ -720,29 +729,37 @@
|
||||
id="Battery"
|
||||
width="18.023544"
|
||||
height="8.2846708"
|
||||
x="501.69357"
|
||||
x="499.13889"
|
||||
y="355.57822" />
|
||||
<rect
|
||||
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="Sensors"
|
||||
width="9.741457"
|
||||
width="8"
|
||||
height="20.208858"
|
||||
x="556.2887"
|
||||
x="551.89978"
|
||||
y="345.96741"
|
||||
inkscape:label="#Sensors" />
|
||||
<rect
|
||||
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="Airspeed"
|
||||
width="8"
|
||||
height="20.208858"
|
||||
x="562.37372"
|
||||
y="345.95883"
|
||||
inkscape:label="#Airspeed" />
|
||||
<rect
|
||||
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="I2C"
|
||||
width="18.023544"
|
||||
height="8.0567961"
|
||||
x="569.6358"
|
||||
y="346.10165" />
|
||||
x="572.51758"
|
||||
y="345.79932" />
|
||||
<rect
|
||||
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.51991701;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="Temp-Baro"
|
||||
width="18.036383"
|
||||
height="8.0690594"
|
||||
x="569.63025"
|
||||
x="572.60791"
|
||||
y="355.2207" />
|
||||
<rect
|
||||
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
@ -812,19 +829,18 @@
|
||||
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
inkscape:label="#rect4000-7-6-7-1" />
|
||||
<rect
|
||||
transform="translate(497.66563,344.28037)"
|
||||
style="fill:#332d2d;fill-opacity:1;stroke:#ffffff;stroke-width:0.55302167;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="USARTs"
|
||||
width="30.08411"
|
||||
height="20.040594"
|
||||
x="25.010578"
|
||||
y="1.9175365" />
|
||||
x="519.2749"
|
||||
y="346.19791" />
|
||||
<rect
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="Telemetry"
|
||||
width="23.347105"
|
||||
height="5.6002355"
|
||||
x="523.76398"
|
||||
x="520.36267"
|
||||
y="347.41809"
|
||||
inkscape:label="#rect4552-27" />
|
||||
<rect
|
||||
@ -849,7 +865,7 @@
|
||||
id="GPS"
|
||||
width="23.347105"
|
||||
height="5.6002355"
|
||||
x="523.76398"
|
||||
x="520.36267"
|
||||
y="353.41809" />
|
||||
<rect
|
||||
y="375.55762"
|
||||
@ -951,8 +967,8 @@
|
||||
id="I2C-OK"
|
||||
width="18.153212"
|
||||
height="8.1216154"
|
||||
x="71.970177"
|
||||
y="1.8212841"
|
||||
x="74.851883"
|
||||
y="1.5189452"
|
||||
inkscape:label="#rect8374" />
|
||||
</g>
|
||||
<g
|
||||
@ -961,8 +977,8 @@
|
||||
inkscape:label="I2C-Warning"
|
||||
style="display:none">
|
||||
<rect
|
||||
y="1.8212841"
|
||||
x="71.970177"
|
||||
y="1.5189452"
|
||||
x="74.851883"
|
||||
height="8.1216154"
|
||||
width="18.153212"
|
||||
id="I2C-Warning"
|
||||
@ -977,17 +993,19 @@
|
||||
<g
|
||||
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="I2C-Error"
|
||||
transform="translate(33.813538,-31.144609)"
|
||||
transform="translate(36.695254,-31.446948)"
|
||||
inkscape:label="#g4084">
|
||||
<path
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 38.076545,33.292974 56.14311,41.28257"
|
||||
id="path3156" />
|
||||
id="path3156"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 38.220502,41.354548 17.85063,-8.061574"
|
||||
id="path3158"
|
||||
inkscape:label="#path4088-8" />
|
||||
inkscape:label="#path4088-8"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
@ -1000,8 +1018,8 @@
|
||||
id="I2C-Critical"
|
||||
width="18.153212"
|
||||
height="8.1216154"
|
||||
x="71.970177"
|
||||
y="1.8212841"
|
||||
x="74.851883"
|
||||
y="1.5189452"
|
||||
inkscape:label="#rect4080" />
|
||||
</g>
|
||||
<g
|
||||
@ -1012,7 +1030,7 @@
|
||||
<rect
|
||||
inkscape:label="#rect8374"
|
||||
y="9.1076469"
|
||||
x="26.199663"
|
||||
x="22.798349"
|
||||
height="5.6002355"
|
||||
width="23.347105"
|
||||
id="GPS-OK"
|
||||
@ -1029,7 +1047,7 @@
|
||||
id="GPS-Warning"
|
||||
width="23.347105"
|
||||
height="5.6002355"
|
||||
x="26.199663"
|
||||
x="22.798349"
|
||||
y="9.1076469" />
|
||||
</g>
|
||||
<g
|
||||
@ -1039,18 +1057,20 @@
|
||||
inkscape:groupmode="layer">
|
||||
<g
|
||||
inkscape:label="#g4084"
|
||||
transform="matrix(1.2853162,0,0,0.64013573,-22.75,-11.845582)"
|
||||
id="GPS-Error"
|
||||
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline">
|
||||
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
transform="matrix(1.2853162,0,0,0.64013573,-26.151312,-11.845582)">
|
||||
<path
|
||||
id="path3176"
|
||||
d="M 38.076545,33.292974 56.14311,41.28257"
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 38,33.292974 17.85,8"
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
inkscape:label="#path4088-8"
|
||||
id="path3178"
|
||||
d="m 38.220502,41.354548 17.85063,-8.061574"
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
d="m 38,41.354548 17.85,-8"
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
@ -1061,12 +1081,78 @@
|
||||
<rect
|
||||
inkscape:label="#rect4080"
|
||||
y="9.1076469"
|
||||
x="26.199663"
|
||||
x="22.798349"
|
||||
height="5.6002355"
|
||||
width="23.347105"
|
||||
id="GPS-Critical"
|
||||
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.30000001;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer50"
|
||||
inkscape:label="Airspeed-OK"
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.40371776;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="Airspeed-OK"
|
||||
width="8"
|
||||
height="20.241537"
|
||||
x="64.72757"
|
||||
y="1.6625173"
|
||||
inkscape:label="#rect4552-27" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer20"
|
||||
inkscape:label="Airspeed-Warning"
|
||||
style="display:none">
|
||||
<rect
|
||||
inkscape:label="#rect4552-27"
|
||||
y="1.7688711"
|
||||
x="64.727081"
|
||||
height="20.135679"
|
||||
width="8"
|
||||
id="Airspeed-Warning"
|
||||
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.4026823;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer11"
|
||||
inkscape:label="Airspeed-Error"
|
||||
style="display:none">
|
||||
<g
|
||||
inkscape:label="#g5707"
|
||||
transform="matrix(0.98237131,0,0,1.3895115,61.95219,0.4046338)"
|
||||
id="Airspeed-Error"
|
||||
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline">
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
id="path5709-4"
|
||||
d="M 4.2641874,1.9700434 9.4,14.522849"
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
id="path5711-6"
|
||||
d="M 4.5521007,14.319264 9.4,1.9402289"
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer6"
|
||||
inkscape:label="Airspeed-Critical"
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.40371776;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="Airspeed-Critical"
|
||||
width="8"
|
||||
height="20.241537"
|
||||
x="64.72757"
|
||||
y="1.6625173"
|
||||
inkscape:label="#rect4552-27" />
|
||||
</g>
|
||||
<g
|
||||
style="display:none"
|
||||
inkscape:label="Sensors-OK"
|
||||
@ -1075,9 +1161,9 @@
|
||||
<rect
|
||||
style="fill:#04b629;fill-opacity:1;stroke:#ffffff;stroke-width:0.40371776;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="Sensors-OK"
|
||||
width="9.6456022"
|
||||
width="8"
|
||||
height="20.241537"
|
||||
x="58.617558"
|
||||
x="54.228596"
|
||||
y="1.586597"
|
||||
inkscape:label="#rect4552-27" />
|
||||
</g>
|
||||
@ -1089,9 +1175,9 @@
|
||||
<rect
|
||||
inkscape:label="#rect4552-27"
|
||||
y="1.6929722"
|
||||
x="58.617039"
|
||||
x="54.228077"
|
||||
height="20.135679"
|
||||
width="9.6466379"
|
||||
width="8"
|
||||
id="Sensors-Warning"
|
||||
style="fill:#f1b907;fill-opacity:1;stroke:#ffffff;stroke-width:0.4026823;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
@ -1102,19 +1188,19 @@
|
||||
inkscape:groupmode="layer">
|
||||
<g
|
||||
inkscape:label="#g5707"
|
||||
transform="matrix(0.98237131,0,0,1.3895115,55.842113,0.32873234)"
|
||||
transform="matrix(0.98237131,0,0,1.3895115,51.453151,0.32873234)"
|
||||
id="Sensors-Error"
|
||||
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline">
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
id="path5709"
|
||||
d="M 4.2641874,1.9700434 11.103735,14.522849"
|
||||
d="M 4.2641874,1.9700434 9.4,14.522849"
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
id="path5711"
|
||||
d="M 4.5521007,14.319264 11.235342,1.9402289"
|
||||
d="M 4.5521007,14.319264 9.4,1.9402289"
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
@ -1127,9 +1213,9 @@
|
||||
<rect
|
||||
style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.40371776;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="Sensors-Critical"
|
||||
width="9.6456032"
|
||||
width="8"
|
||||
height="20.241537"
|
||||
x="58.617558"
|
||||
x="54.228596"
|
||||
y="1.586597"
|
||||
inkscape:label="#rect4552-27" />
|
||||
</g>
|
||||
@ -1332,7 +1418,7 @@
|
||||
<rect
|
||||
inkscape:label="#rect4552-27"
|
||||
y="3.1377156"
|
||||
x="26.098318"
|
||||
x="22.697004"
|
||||
height="5.6002355"
|
||||
width="23.347105"
|
||||
id="Telemetry-OK"
|
||||
@ -1348,7 +1434,7 @@
|
||||
id="Telemetry-Warning"
|
||||
width="23.347105"
|
||||
height="5.6002355"
|
||||
x="26.098318"
|
||||
x="22.697004"
|
||||
y="3.1377156"
|
||||
inkscape:label="#rect4552-27" />
|
||||
</g>
|
||||
@ -1360,15 +1446,18 @@
|
||||
<g
|
||||
inkscape:label="#g4357"
|
||||
style="stroke:#cf0e0e;stroke-opacity:1;display:inline"
|
||||
id="Telemetry-Error">
|
||||
id="Telemetry-Error"
|
||||
transform="translate(-3.4013125,0)">
|
||||
<path
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="M 26.488031,3.4219598 49.017254,8.3164874"
|
||||
id="path4353" />
|
||||
id="path4353"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="M 49.089232,3.3499815 26.56001,8.3884657"
|
||||
id="path4355" />
|
||||
id="path4355"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
@ -1379,7 +1468,7 @@
|
||||
<rect
|
||||
inkscape:label="#rect4552-27"
|
||||
y="3.1377156"
|
||||
x="26.098318"
|
||||
x="22.697004"
|
||||
height="5.6002355"
|
||||
width="23.347105"
|
||||
id="Telemetry-Critical"
|
||||
@ -1592,7 +1681,7 @@
|
||||
<rect
|
||||
inkscape:label="#rect7370"
|
||||
y="1.8212841"
|
||||
x="4.1348462"
|
||||
x="1.5801588"
|
||||
height="8.2846708"
|
||||
width="18.023544"
|
||||
id="Power-OK"
|
||||
@ -1609,7 +1698,7 @@
|
||||
id="Power-Warning"
|
||||
width="18.023544"
|
||||
height="8.2846708"
|
||||
x="4.1348462"
|
||||
x="1.5801588"
|
||||
y="1.8212841" />
|
||||
</g>
|
||||
<g
|
||||
@ -1620,7 +1709,8 @@
|
||||
<g
|
||||
inkscape:label="#g4026"
|
||||
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="Power-Error">
|
||||
id="Power-Error"
|
||||
transform="translate(-1.9500095,0)">
|
||||
<path
|
||||
style="fill:none;stroke:#cf0e0e;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 3.9588091,1.7664579 22.097352,10.043968"
|
||||
@ -1641,7 +1731,7 @@
|
||||
<rect
|
||||
inkscape:label="#rect7437"
|
||||
y="1.8212841"
|
||||
x="4.1348462"
|
||||
x="1.5801588"
|
||||
height="8.2846708"
|
||||
width="18.023544"
|
||||
id="Power-Critical"
|
||||
@ -1657,7 +1747,7 @@
|
||||
id="Battery-OK"
|
||||
width="18.023544"
|
||||
height="8.2846708"
|
||||
x="4.0279531"
|
||||
x="1.4732658"
|
||||
y="11.334756"
|
||||
inkscape:label="#rect7370" />
|
||||
</g>
|
||||
@ -1668,7 +1758,7 @@
|
||||
style="display:none">
|
||||
<rect
|
||||
y="11.334756"
|
||||
x="4.0279531"
|
||||
x="1.4732658"
|
||||
height="8.2846708"
|
||||
width="18.023544"
|
||||
id="Battery-Warning"
|
||||
@ -1685,7 +1775,7 @@
|
||||
id="Battery-Critical"
|
||||
width="18.023544"
|
||||
height="8.2846708"
|
||||
x="4.1348462"
|
||||
x="1.5801588"
|
||||
y="11.344959"
|
||||
inkscape:label="#rect7437" />
|
||||
</g>
|
||||
@ -1698,7 +1788,7 @@
|
||||
id="Battery-Error"
|
||||
style="stroke:#cf0e0e;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
inkscape:label="#g4026"
|
||||
transform="translate(0,9.5134715)">
|
||||
transform="translate(-1.9500095,9.5134715)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4708"
|
||||
@ -1968,7 +2058,7 @@
|
||||
<g
|
||||
id="text4522-4"
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
|
||||
transform="translate(0.21378587,-0.20358251)">
|
||||
transform="translate(-2.3409014,-0.20358251)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3980"
|
||||
@ -1997,7 +2087,8 @@
|
||||
</g>
|
||||
<g
|
||||
id="I2C-Text"
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
|
||||
transform="translate(2.8817153,-0.30233889)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3924"
|
||||
@ -2016,7 +2107,8 @@
|
||||
</g>
|
||||
<g
|
||||
id="text4647-0-2-6"
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;text-align:center;text-anchor:middle;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans">
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;text-align:center;text-anchor:middle;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Bitstream Vera Sans"
|
||||
transform="translate(2.9776741,0)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3905"
|
||||
@ -2858,7 +2950,8 @@
|
||||
</g>
|
||||
<g
|
||||
id="text4548-7"
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans">
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans"
|
||||
transform="translate(-3.4013125,0)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3947"
|
||||
@ -2887,7 +2980,8 @@
|
||||
</g>
|
||||
<g
|
||||
id="text4554-61"
|
||||
style="font-size:35.79270172px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans">
|
||||
style="font-size:35.79270172px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans"
|
||||
transform="translate(-3.4013125,0)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3991"
|
||||
@ -2946,7 +3040,8 @@
|
||||
</g>
|
||||
<g
|
||||
id="text4554-7-2"
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans">
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans"
|
||||
transform="translate(-3.4013125,0)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3969"
|
||||
@ -2975,14 +3070,15 @@
|
||||
</g>
|
||||
<rect
|
||||
y="15.137716"
|
||||
x="26.098318"
|
||||
x="22.697004"
|
||||
height="5.6002355"
|
||||
width="23.347105"
|
||||
id="rect4122"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<g
|
||||
id="text4124"
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans">
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans"
|
||||
transform="translate(-3.4013125,0)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path3958"
|
||||
@ -3249,28 +3345,41 @@
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans"
|
||||
x="5.6416268"
|
||||
x="3.0869398"
|
||||
y="16.60899"
|
||||
id="text6573"
|
||||
sodipodi:linespacing="125%"><tspan
|
||||
id="tspan6575"
|
||||
sodipodi:role="line"
|
||||
x="5.6416268"
|
||||
x="3.0869398"
|
||||
y="16.60899"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans">Battery</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:18px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:80.00000119%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;font-family:Arial;-inkscape-font-specification:Sans Bold"
|
||||
x="4.2995572"
|
||||
y="-62.471176"
|
||||
x="4.3751421"
|
||||
y="-57.099613"
|
||||
id="text3565"
|
||||
sodipodi:linespacing="80.000001%"
|
||||
transform="matrix(0,1,-1,0,0,0)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan3567"
|
||||
x="4.2995572"
|
||||
y="-62.471176"
|
||||
x="4.3751421"
|
||||
y="-57.099613"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:80.00000119%;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;font-family:Arial;-inkscape-font-specification:Arial">Sensors</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:18px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:80.00000119%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Sans Bold"
|
||||
x="4.1748462"
|
||||
y="-67.598602"
|
||||
id="text3565-9"
|
||||
sodipodi:linespacing="80.000001%"
|
||||
transform="matrix(0,1,-1,0,0,0)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan3567-3"
|
||||
x="4.1748462"
|
||||
y="-67.598602"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:80.00000119%;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;font-family:Arial;-inkscape-font-specification:Arial">Airspeed</tspan></text>
|
||||
</g>
|
||||
<g
|
||||
style="display:none"
|
||||
|
Before Width: | Height: | Size: 235 KiB After Width: | Height: | Size: 239 KiB |
18
ground/openpilotgcs/src/libs/sdlgamepad/copydata.pro
Normal file
18
ground/openpilotgcs/src/libs/sdlgamepad/copydata.pro
Normal file
@ -0,0 +1,18 @@
|
||||
equals(copydata, 1) {
|
||||
|
||||
win32 {
|
||||
# copy SDL DLL
|
||||
SDL_DLLS = \
|
||||
SDL.dll
|
||||
for(dll, SDL_DLLS) {
|
||||
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(SDL_DIR)/bin/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline()
|
||||
}
|
||||
|
||||
# add make target
|
||||
POST_TARGETDEPS += copydata
|
||||
|
||||
data_copy.target = copydata
|
||||
QMAKE_EXTRA_TARGETS += data_copy
|
||||
}
|
||||
|
||||
}
|
@ -21,6 +21,22 @@
|
||||
/**********************************************************************/
|
||||
#include "sdlgamepad.h"
|
||||
|
||||
#include <SDL/SDL.h>
|
||||
// #undef main
|
||||
|
||||
class SDLGamepadPrivate {
|
||||
public:
|
||||
SDLGamepadPrivate() : gamepad(0)
|
||||
{}
|
||||
|
||||
/**
|
||||
* SDL_Joystick object.
|
||||
*
|
||||
* This represents the currently opened SDL_Joystick object.
|
||||
*/
|
||||
SDL_Joystick *gamepad;
|
||||
};
|
||||
|
||||
/**********************************************************************/
|
||||
SDLGamepad::SDLGamepad()
|
||||
{
|
||||
@ -29,7 +45,7 @@ SDLGamepad::SDLGamepad()
|
||||
index = -1;
|
||||
loop = false;
|
||||
tick = MIN_RATE;
|
||||
gamepad = 0;
|
||||
priv = new SDLGamepadPrivate;
|
||||
}
|
||||
|
||||
/**********************************************************************/
|
||||
@ -37,11 +53,13 @@ SDLGamepad::~SDLGamepad()
|
||||
{
|
||||
loop = false;
|
||||
|
||||
if (gamepad) {
|
||||
SDL_JoystickClose(gamepad);
|
||||
if (priv->gamepad) {
|
||||
SDL_JoystickClose(priv->gamepad);
|
||||
}
|
||||
|
||||
SDL_Quit();
|
||||
|
||||
delete priv;
|
||||
}
|
||||
|
||||
/**********************************************************************/
|
||||
@ -84,14 +102,14 @@ bool SDLGamepad::setGamepad(qint16 index)
|
||||
{
|
||||
if (index != this->index) {
|
||||
if (SDL_JoystickOpened(this->index)) {
|
||||
SDL_JoystickClose(gamepad);
|
||||
SDL_JoystickClose(priv->gamepad);
|
||||
}
|
||||
|
||||
gamepad = SDL_JoystickOpen(index);
|
||||
priv->gamepad = SDL_JoystickOpen(index);
|
||||
|
||||
if (gamepad) {
|
||||
buttons = SDL_JoystickNumButtons(gamepad);
|
||||
axes = SDL_JoystickNumAxes(gamepad);
|
||||
if (priv->gamepad) {
|
||||
buttons = SDL_JoystickNumButtons(priv->gamepad);
|
||||
axes = SDL_JoystickNumAxes(priv->gamepad);
|
||||
|
||||
if (axes >= 4) {
|
||||
this->index = index;
|
||||
@ -122,12 +140,12 @@ void SDLGamepad::setTickRate(qint16 ms)
|
||||
/**********************************************************************/
|
||||
void SDLGamepad::updateAxes()
|
||||
{
|
||||
if (gamepad) {
|
||||
if (priv->gamepad) {
|
||||
QListInt16 values;
|
||||
SDL_JoystickUpdate();
|
||||
|
||||
for (qint8 i = 0; i < axes; i++) {
|
||||
qint16 value = SDL_JoystickGetAxis(gamepad, i);
|
||||
qint16 value = SDL_JoystickGetAxis(priv->gamepad, i);
|
||||
|
||||
if (value > -NULL_RANGE && value < NULL_RANGE) {
|
||||
value = 0;
|
||||
@ -143,11 +161,11 @@ void SDLGamepad::updateAxes()
|
||||
/**********************************************************************/
|
||||
void SDLGamepad::updateButtons()
|
||||
{
|
||||
if (gamepad) {
|
||||
if (priv->gamepad) {
|
||||
SDL_JoystickUpdate();
|
||||
|
||||
for (qint8 i = 0; i < buttons; i++) {
|
||||
qint16 state = SDL_JoystickGetButton(gamepad, i);
|
||||
qint16 state = SDL_JoystickGetButton(priv->gamepad, i);
|
||||
|
||||
if (buttonStates.at(i) != state) {
|
||||
if (state > 0) {
|
||||
|
@ -20,18 +20,13 @@
|
||||
* mail.nalla@gmail.com
|
||||
*/
|
||||
|
||||
/**********************************************************************/
|
||||
#ifndef SDLGAMEPAD_H
|
||||
#define SDLGAMEPAD_H
|
||||
|
||||
/**********************************************************************/
|
||||
#include <SDL/SDL.h>
|
||||
#undef main
|
||||
|
||||
/**********************************************************************/
|
||||
#include <QThread>
|
||||
#include "sdlgamepad_global.h"
|
||||
|
||||
#include <QThread>
|
||||
|
||||
/**
|
||||
* The Axis range that is treated as null.
|
||||
*
|
||||
@ -114,6 +109,8 @@ enum ButtonNumber {
|
||||
*/
|
||||
typedef QList<qint16> QListInt16;
|
||||
|
||||
class SDLGamepadPrivate;
|
||||
|
||||
/**
|
||||
* A class for communication with a sdl gamepad.
|
||||
*
|
||||
@ -226,17 +223,6 @@ public slots:
|
||||
|
||||
private:
|
||||
|
||||
/**
|
||||
* Variable to control thread.
|
||||
*
|
||||
* This class member variable is false at construction time. If
|
||||
* the sdl init was successfull it will be set to true. The quit
|
||||
* slot will false it again.
|
||||
*
|
||||
* @see quit()
|
||||
*/
|
||||
bool loop;
|
||||
|
||||
/**
|
||||
* Get new axes information from the SDL system.
|
||||
*
|
||||
@ -261,6 +247,17 @@ private:
|
||||
*/
|
||||
void updateButtons();
|
||||
|
||||
/**
|
||||
* Variable to control thread.
|
||||
*
|
||||
* This class member variable is false at construction time. If
|
||||
* the SDL init was successful it will be set to true. The quit
|
||||
* slot will false it again.
|
||||
*
|
||||
* @see quit()
|
||||
*/
|
||||
bool loop;
|
||||
|
||||
/**
|
||||
* Number of buttons.
|
||||
*
|
||||
@ -295,20 +292,18 @@ private:
|
||||
*/
|
||||
qint16 index;
|
||||
|
||||
/**
|
||||
* SDL_Joystick object.
|
||||
*
|
||||
* This represents the currently opend SDL_Joystick object.
|
||||
*/
|
||||
SDL_Joystick *gamepad;
|
||||
|
||||
/**
|
||||
* A QList to store the current button states.
|
||||
*
|
||||
* This list stores the current states of all avaliable buttons.
|
||||
* This list stores the current states of all available buttons.
|
||||
*/
|
||||
QList<qint16> buttonStates;
|
||||
|
||||
/**
|
||||
* Variable that holds private members.
|
||||
*/
|
||||
SDLGamepadPrivate *priv;
|
||||
|
||||
signals:
|
||||
|
||||
/**
|
||||
@ -354,5 +349,4 @@ signals:
|
||||
void axesValues(QListInt16 values);
|
||||
};
|
||||
|
||||
/**********************************************************************/
|
||||
#endif // SDLGAMEPAD_H
|
||||
|
@ -18,11 +18,14 @@
|
||||
# mail.nalla@gmail.com
|
||||
#
|
||||
|
||||
TEMPLATE = lib
|
||||
TARGET = sdlgamepad
|
||||
DEFINES += SDLGAMEPAD_LIBRARY
|
||||
TEMPLATE = lib
|
||||
TARGET = sdlgamepad
|
||||
DEFINES += SDLGAMEPAD_LIBRARY
|
||||
|
||||
include(../../openpilotgcslibrary.pri)
|
||||
|
||||
macx {
|
||||
# Workaround to ensure that SDL framework and associated header files are found
|
||||
# Ensures that SDL framework and header files are found when compiled with Qt5.2.1
|
||||
INCLUDEPATH += /Library/Frameworks/SDL.framework/Headers
|
||||
SDL = -F/Library/Frameworks
|
||||
# Add SDL to CFLAGS fixes build problems on mac
|
||||
@ -30,18 +33,27 @@ macx {
|
||||
QMAKE_CXXFLAGS += $$SDL
|
||||
# Let the linker know where to find the frameworks
|
||||
LIBS += $$SDL
|
||||
LIBS += -framework OpenGL -framework SDL -framework Cocoa
|
||||
}
|
||||
|
||||
include(../../openpilotgcslibrary.pri)
|
||||
win32 {
|
||||
INCLUDEPATH += $(SDL_DIR)/include
|
||||
LIBS += -L$(SDL_DIR)/lib
|
||||
}
|
||||
|
||||
SOURCES += sdlgamepad.cpp
|
||||
HEADERS += sdlgamepad.h \
|
||||
sdlgamepad_global.h
|
||||
!mac:LIBS += -lSDL
|
||||
|
||||
macx:LIBS += -framework OpenGL -framework SDL -framework Cocoa
|
||||
!macx:LIBS += -lSDL
|
||||
SOURCES += \
|
||||
sdlgamepad.cpp
|
||||
|
||||
OTHER_FILES += COPYING \
|
||||
README \
|
||||
sdlgamepad.dox \
|
||||
sdlgamepad.doc
|
||||
HEADERS += \
|
||||
sdlgamepad.h \
|
||||
sdlgamepad_global.h
|
||||
|
||||
OTHER_FILES += \
|
||||
COPYING \
|
||||
README \
|
||||
sdlgamepad.dox \
|
||||
sdlgamepad.doc
|
||||
|
||||
include(copydata.pro)
|
||||
|
@ -119,9 +119,6 @@
|
||||
<height>50</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background:transparent</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
|
@ -116,8 +116,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>624</width>
|
||||
<height>516</height>
|
||||
<width>622</width>
|
||||
<height>519</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
@ -227,14 +227,14 @@
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="telemetrySpeedLabel">
|
||||
<property name="text">
|
||||
<string>Telemetry speed:</string>
|
||||
<item row="0" column="1">
|
||||
<widget class="QComboBox" name="telemetrySpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="GpsSpeedLabel">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
@ -247,7 +247,28 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="telemetrySpeedLabel">
|
||||
<property name="text">
|
||||
<string>Telemetry speed:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="comUsbBridgeSpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="gpsSpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="ComUsbBridgeSpeedLabel">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
@ -260,26 +281,15 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QComboBox" name="telemetrySpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="GpsProtocolLabel">
|
||||
<property name="text">
|
||||
<string>GPS protocol :</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="gpsSpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="comUsbBridgeSpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
<item row="3" column="1">
|
||||
<widget class="QComboBox" name="gpsProtocol"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
|
@ -26,7 +26,6 @@
|
||||
*/
|
||||
#include "config_cc_hw_widget.h"
|
||||
#include "hwsettings.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QStringList>
|
||||
#include <QWidget>
|
||||
@ -82,6 +81,18 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
addWidgetBinding("HwSettings", "USB_VCPPort", m_telemetry->cbUsbVcp);
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_telemetry->telemetrySpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_telemetry->gpsSpeed);
|
||||
// Add Gps protocol configuration
|
||||
|
||||
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
|
||||
HwSettings::DataFields hwSettingsData = hwSettings->getData();
|
||||
|
||||
if (hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_GPS] != HwSettings::OPTIONALMODULES_ENABLED) {
|
||||
m_telemetry->gpsProtocol->setEnabled(false);
|
||||
m_telemetry->gpsProtocol->setToolTip(tr("Enable GPS module and reboot the board to be able to select GPS protocol"));
|
||||
} else {
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_telemetry->gpsProtocol);
|
||||
}
|
||||
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_telemetry->comUsbBridgeSpeed);
|
||||
connect(m_telemetry->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
enableSaveButtons(false);
|
||||
|
@ -44,7 +44,6 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
|
||||
ui(new Ui_ccattitude)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
forceConnectedState(); // dynamic widgets don't recieve the connected signal
|
||||
connect(ui->zeroBias, SIGNAL(clicked()), this, SLOT(startAccelCalibration()));
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
@ -67,7 +66,9 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->pitchBias, AttitudeSettings::BOARDROTATION_PITCH);
|
||||
addWidgetBinding("AttitudeSettings", "BoardRotation", ui->yawBias, AttitudeSettings::BOARDROTATION_YAW);
|
||||
addWidget(ui->zeroBias);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
forceConnectedState();
|
||||
}
|
||||
|
||||
ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget()
|
||||
|
@ -65,6 +65,10 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
|
||||
|
||||
connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
setupCustomCombos();
|
||||
@ -191,6 +195,10 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
|
||||
m_ui->cbFlexiComSpeed->setVisible(false);
|
||||
m_ui->lblFlexiSpeed->setVisible(true);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
m_ui->cbFlexiGPSProtocol->setVisible(false);
|
||||
m_ui->lbFlexiGPSProtocol->setVisible(false);
|
||||
|
||||
switch (m_ui->cbFlexi->currentIndex()) {
|
||||
case HwSettings::RM_FLEXIPORT_TELEMETRY:
|
||||
m_ui->cbFlexiTelemSpeed->setVisible(true);
|
||||
@ -199,6 +207,10 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_FLEXIPORT_GPS:
|
||||
// Add Gps protocol configuration
|
||||
m_ui->cbFlexiGPSProtocol->setVisible(true);
|
||||
m_ui->lbFlexiGPSProtocol->setVisible(true);
|
||||
|
||||
m_ui->cbFlexiGPSSpeed->setVisible(true);
|
||||
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_GPS) {
|
||||
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
|
||||
@ -234,6 +246,10 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
|
||||
m_ui->cbMainComSpeed->setVisible(false);
|
||||
m_ui->lblMainSpeed->setVisible(true);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
m_ui->cbMainGPSProtocol->setVisible(false);
|
||||
m_ui->lbMainGPSProtocol->setVisible(false);
|
||||
|
||||
switch (m_ui->cbMain->currentIndex()) {
|
||||
case HwSettings::RM_MAINPORT_TELEMETRY:
|
||||
m_ui->cbMainTelemSpeed->setVisible(true);
|
||||
@ -242,6 +258,10 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_MAINPORT_GPS:
|
||||
// Add Gps protocol configuration
|
||||
m_ui->cbMainGPSProtocol->setVisible(true);
|
||||
m_ui->lbMainGPSProtocol->setVisible(true);
|
||||
|
||||
m_ui->cbMainGPSSpeed->setVisible(true);
|
||||
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_GPS) {
|
||||
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
|
@ -27,7 +27,16 @@
|
||||
<string>HW settings</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -113,16 +122,117 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>818</width>
|
||||
<height>673</height>
|
||||
<width>810</width>
|
||||
<height>665</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Changes on this page only take effect after board reset or power cycle</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<spacer name="verticalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<spacer name="horizontalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<spacer name="horizontalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
|
||||
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="sizePolicy">
|
||||
@ -155,27 +265,7 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="15" column="1">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiTelemSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiGPSSpeed"/>
|
||||
</item>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="16" column="1">
|
||||
<item row="19" column="1">
|
||||
<spacer name="horizontalSpacer_7">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
@ -191,13 +281,13 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="14" column="3">
|
||||
<widget class="QLabel" name="lblMainSpeed">
|
||||
<item row="16" column="3">
|
||||
<widget class="QLabel" name="lbMainGPSProtocol">
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
<string>Protocol</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
@ -232,10 +322,46 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="5">
|
||||
<spacer name="verticalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="15" column="1">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiTelemSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiGPSSpeed"/>
|
||||
</item>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="13" column="1">
|
||||
<widget class="QComboBox" name="cbFlexi"/>
|
||||
</item>
|
||||
<item row="16" column="4">
|
||||
<item row="19" column="4">
|
||||
<spacer name="horizontalSpacer_8">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
@ -271,22 +397,6 @@
|
||||
<item row="13" column="3">
|
||||
<widget class="QComboBox" name="cbMain"/>
|
||||
</item>
|
||||
<item row="10" column="5">
|
||||
<spacer name="verticalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="12" column="3">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="text">
|
||||
@ -471,7 +581,7 @@
|
||||
<item row="3" column="0">
|
||||
<widget class="QComboBox" name="cbRcvr"/>
|
||||
</item>
|
||||
<item row="16" column="3">
|
||||
<item row="19" column="3">
|
||||
<spacer name="horizontalSpacer_9">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
@ -551,7 +661,7 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="16" column="2">
|
||||
<item row="19" column="2">
|
||||
<spacer name="horizontalSpacer_10">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
@ -564,100 +674,37 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="14" column="3">
|
||||
<widget class="QLabel" name="lblMainSpeed">
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="16" column="1">
|
||||
<widget class="QLabel" name="lbFlexiGPSProtocol">
|
||||
<property name="text">
|
||||
<string>Protocol</string>
|
||||
</property>
|
||||
<property name="textFormat">
|
||||
<enum>Qt::PlainText</enum>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="18" column="3">
|
||||
<widget class="QComboBox" name="cbMainGPSProtocol"/>
|
||||
</item>
|
||||
<item row="18" column="1">
|
||||
<widget class="QComboBox" name="cbFlexiGPSProtocol"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Changes on this page only take effect after board reset or power cycle</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<spacer name="verticalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<spacer name="horizontalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<spacer name="horizontalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
|
@ -20,23 +20,28 @@ Rectangle {
|
||||
border.width: 1
|
||||
radius: 4
|
||||
ColumnLayout {
|
||||
id: exportTab
|
||||
anchors.margins: 10
|
||||
anchors.fill: parent
|
||||
visible: true
|
||||
Text {
|
||||
Layout.fillWidth: true
|
||||
text: "<b>" + qsTr("Log entries") + "</b>"
|
||||
font.pixelSize: 12
|
||||
}
|
||||
TableView {
|
||||
Layout.fillWidth: true
|
||||
Layout.fillHeight: true
|
||||
Layout.preferredHeight: 1000;
|
||||
model: logManager.logEntries
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
|
||||
rowDelegate: Rectangle {
|
||||
height: 22
|
||||
color: styleData.selected ? "#ccc" : (styleData.alternate ? "#fff" : "#eee")
|
||||
}
|
||||
|
||||
itemDelegate: Text {
|
||||
anchors.fill: parent
|
||||
anchors.margins: 2
|
||||
anchors.leftMargin: 5
|
||||
font.pixelSize: 12
|
||||
verticalAlignment: Text.AlignVCenter
|
||||
text: styleData.value
|
||||
}
|
||||
|
||||
@ -44,33 +49,24 @@ Rectangle {
|
||||
role: "Flight"; title: qsTr("Flight"); width: 50;
|
||||
delegate:
|
||||
Text {
|
||||
anchors.fill: parent
|
||||
anchors.margins: 2
|
||||
anchors.leftMargin: 5
|
||||
font.pixelSize: 12
|
||||
verticalAlignment: Text.AlignVCenter
|
||||
text: styleData.value + 1
|
||||
}
|
||||
|
||||
}
|
||||
TableViewColumn {
|
||||
role: "FlightTime"; title: qsTr("Time"); width: 80;
|
||||
role: "FlightTime"; title: qsTr("Time"); width: 100;
|
||||
delegate:
|
||||
Text {
|
||||
anchors.fill: parent
|
||||
anchors.margins: 2
|
||||
anchors.leftMargin: 5
|
||||
font.pixelSize: 12
|
||||
verticalAlignment: Text.AlignVCenter
|
||||
text: Functions.millisToTime(styleData.value)
|
||||
}
|
||||
}
|
||||
TableViewColumn {
|
||||
role: "Type"; title: "Type"; width: 50;
|
||||
role: "Type"; title: "Type"; width: 60;
|
||||
delegate:
|
||||
Text {
|
||||
anchors.fill: parent
|
||||
anchors.margins: 2
|
||||
anchors.leftMargin: 5
|
||||
font.pixelSize: 12
|
||||
verticalAlignment: Text.AlignVCenter
|
||||
text: {
|
||||
switch(styleData.value) {
|
||||
case 0 : text: qsTr("Empty"); break;
|
||||
@ -82,25 +78,39 @@ Rectangle {
|
||||
}
|
||||
|
||||
}
|
||||
TableViewColumn { role: "LogString"; title: qsTr("Data"); width: 280}
|
||||
TableViewColumn {
|
||||
role: "LogString";
|
||||
title: qsTr("Data");
|
||||
width: 280
|
||||
}
|
||||
}
|
||||
|
||||
RowLayout {
|
||||
anchors.margins: 10
|
||||
spacing: 10
|
||||
|
||||
ColumnLayout {
|
||||
spacing: 10
|
||||
Text {
|
||||
id: totalFlights
|
||||
font.pixelSize: 12
|
||||
text: "<b>" + qsTr("Flights recorded: ") + "</b>" + (logStatus.Flight + 1)
|
||||
}
|
||||
Text {
|
||||
id: totalEntries
|
||||
font.pixelSize: 12
|
||||
text: "<b>" + qsTr("Entries logged (free): ") + "</b>" +
|
||||
logStatus.UsedSlots + " (" + logStatus.FreeSlots + ")"
|
||||
}
|
||||
Rectangle {
|
||||
Layout.fillHeight: true
|
||||
}
|
||||
CheckBox {
|
||||
id: exportRelativeTimeCB
|
||||
enabled: !logManager.disableControls && !logManager.disableExport && logManager.boardConnected
|
||||
text: qsTr("Adjust timestamps")
|
||||
activeFocusOnPress: true
|
||||
checked: logManager.adjustExportedTimestamps
|
||||
onCheckedChanged: logManager.setAdjustExportedTimestamps(checked)
|
||||
}
|
||||
}
|
||||
Rectangle {
|
||||
Layout.fillWidth: true
|
||||
@ -112,29 +122,240 @@ Rectangle {
|
||||
Layout.fillWidth: true
|
||||
}
|
||||
Text {
|
||||
font.pixelSize: 12
|
||||
text: "<b>" + qsTr("Flight to download:") + "</b>"
|
||||
}
|
||||
|
||||
ComboBox {
|
||||
id: flightCombo
|
||||
enabled: !logManager.disableControls
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
model: logManager.flightEntries
|
||||
}
|
||||
}
|
||||
RowLayout {
|
||||
Layout.fillWidth: true
|
||||
Layout.fillHeight: true
|
||||
spacing: 10
|
||||
Rectangle {
|
||||
Layout.fillWidth: true
|
||||
}
|
||||
Button {
|
||||
text: qsTr("Download logs")
|
||||
enabled: !logManager.disableControls
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
activeFocusOnPress: true
|
||||
onClicked: logManager.retrieveLogs(flightCombo.currentIndex - 1)
|
||||
}
|
||||
}
|
||||
Rectangle {
|
||||
Layout.fillHeight: true
|
||||
}
|
||||
RowLayout {
|
||||
Rectangle {
|
||||
Layout.fillWidth: true
|
||||
}
|
||||
Button {
|
||||
id: clearButton
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
text: qsTr("Clear all logs")
|
||||
activeFocusOnPress: true
|
||||
onClicked: logManager.clearAllLogs()
|
||||
}
|
||||
Button {
|
||||
id: exportButton
|
||||
enabled: !logManager.disableControls && !logManager.disableExport && logManager.boardConnected
|
||||
text: qsTr("Export logs...")
|
||||
activeFocusOnPress: true
|
||||
onClicked: logManager.exportLogs()
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
ColumnLayout {
|
||||
id: settingsTab
|
||||
visible: false
|
||||
anchors.margins: 10
|
||||
anchors.fill: parent
|
||||
Text {
|
||||
Layout.fillWidth: true
|
||||
text: "<b>" + qsTr("Settings") + "</b>"
|
||||
}
|
||||
|
||||
RowLayout {
|
||||
Layout.fillWidth: true
|
||||
Layout.fillHeight: true
|
||||
Text {
|
||||
text: qsTr("When to log: ")
|
||||
}
|
||||
ComboBox {
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
model: logManager.logStatuses
|
||||
Layout.preferredWidth: 200
|
||||
currentIndex: logManager.loggingEnabled
|
||||
onCurrentIndexChanged: {
|
||||
logManager.setLoggingEnabled(currentIndex);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
Component {
|
||||
id: comboEditableDelegate
|
||||
Item {
|
||||
|
||||
Text {
|
||||
width: parent.width
|
||||
anchors.left: parent.left
|
||||
anchors.verticalCenter: parent.verticalCenter
|
||||
elide: styleData.elideMode
|
||||
text: styleData.value !== undefined ? logManager.logSettings[styleData.value] : ""
|
||||
color: logManager.uavoEntries[styleData.row].dirty ? "#f00" : styleData.textColor
|
||||
visible: !styleData.selected
|
||||
}
|
||||
Loader {
|
||||
id: loaderEditor
|
||||
anchors.fill: parent
|
||||
Connections {
|
||||
target: loaderEditor.item
|
||||
onCurrentIndexChanged: {
|
||||
logManager.uavoEntries[styleData.row].setting = loaderEditor.item.currentIndex
|
||||
}
|
||||
}
|
||||
sourceComponent: styleData.selected ? editor : null
|
||||
Component {
|
||||
id: editor
|
||||
ComboBox {
|
||||
id: combo
|
||||
model: logManager.logSettings
|
||||
currentIndex: styleData.value
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Component {
|
||||
id: spinnerEditableDelegate
|
||||
Item {
|
||||
|
||||
Text {
|
||||
width: parent.width
|
||||
anchors.left: parent.left
|
||||
anchors.verticalCenter: parent.verticalCenter
|
||||
elide: styleData.elideMode
|
||||
text: styleData.value !== undefined &&
|
||||
(logManager.uavoEntries[styleData.row].setting === 1 || logManager.uavoEntries[styleData.row].setting === 3) ?
|
||||
parseInt(logManager.uavoEntries[styleData.row].period) + " ms" : "-"
|
||||
color: logManager.uavoEntries[styleData.row].dirty ? "#f00" : styleData.textColor
|
||||
//visible: !styleData.selected && (logManager.uavoEntries[styleData.row].setting <= 1)
|
||||
enabled: (logManager.uavoEntries[styleData.row].setting > 1)
|
||||
}
|
||||
Loader {
|
||||
id: loaderEditor
|
||||
anchors.fill: parent
|
||||
Connections {
|
||||
target: loaderEditor.item
|
||||
onValueChanged: {
|
||||
logManager.uavoEntries[styleData.row].period = loaderEditor.item.value
|
||||
}
|
||||
}
|
||||
sourceComponent: styleData.selected &&
|
||||
(logManager.uavoEntries[styleData.row].setting === 1 || logManager.uavoEntries[styleData.row].setting === 3) ? editor : null
|
||||
Component {
|
||||
id: editor
|
||||
SpinBox {
|
||||
id: spinner
|
||||
decimals: 0
|
||||
minimumValue: 0
|
||||
maximumValue: 1000 * 60 * 60 //1h
|
||||
suffix: "ms"
|
||||
stepSize: 10
|
||||
value: styleData.value
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
TableView {
|
||||
id: settingsTable
|
||||
Layout.fillWidth: true
|
||||
Layout.fillHeight: true
|
||||
Layout.preferredHeight: 1000;
|
||||
model: logManager.uavoEntries
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
|
||||
rowDelegate: Rectangle {
|
||||
height: 22
|
||||
color: styleData.selected ? "#ccc" : (styleData.alternate ? "#fff" : "#eee")
|
||||
}
|
||||
|
||||
TableViewColumn {
|
||||
role: "name";
|
||||
title: qsTr("UAVObject");
|
||||
width: 250;
|
||||
delegate:
|
||||
Text {
|
||||
verticalAlignment: Text.AlignVCenter
|
||||
anchors.leftMargin: 5
|
||||
color: logManager.uavoEntries[styleData.row].dirty ? "#f00" : styleData.textColor
|
||||
text: styleData.value
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
TableViewColumn {
|
||||
role: "setting";
|
||||
title: qsTr("Settings");
|
||||
width: 160;
|
||||
delegate: comboEditableDelegate
|
||||
}
|
||||
|
||||
TableViewColumn {
|
||||
role: "period";
|
||||
title: qsTr("Period");
|
||||
width: 120;
|
||||
delegate: spinnerEditableDelegate
|
||||
}
|
||||
}
|
||||
RowLayout {
|
||||
Layout.fillWidth: true
|
||||
Layout.fillHeight: true
|
||||
|
||||
Button {
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
text: qsTr("Load...")
|
||||
tooltip: qsTr("Loads settings for all objects from a file.")
|
||||
activeFocusOnPress: true
|
||||
onClicked: logManager.loadSettings()
|
||||
}
|
||||
Button {
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
text: qsTr("Save...")
|
||||
tooltip: qsTr("Saves settings for all objects in a file.")
|
||||
activeFocusOnPress: true
|
||||
onClicked: logManager.saveSettings()
|
||||
}
|
||||
Button {
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
text: qsTr("Reset")
|
||||
tooltip: qsTr("Resets all settings to the values currently set on the board.")
|
||||
activeFocusOnPress: true
|
||||
onClicked: logManager.resetSettings(false)
|
||||
}
|
||||
Button {
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
text: qsTr("Clear")
|
||||
tooltip: qsTr("Clears all settings to default values.")
|
||||
activeFocusOnPress: true
|
||||
onClicked: logManager.resetSettings(true)
|
||||
}
|
||||
Rectangle {
|
||||
Layout.fillWidth: true
|
||||
}
|
||||
Button {
|
||||
enabled: !logManager.disableControls && logManager.boardConnected
|
||||
text: qsTr("Save to board")
|
||||
tooltip: qsTr("Saves the logging configurations to the boards flash memory.")
|
||||
activeFocusOnPress: true
|
||||
onClicked: logManager.saveSettingsToBoard()
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -144,27 +365,17 @@ Rectangle {
|
||||
Layout.fillWidth: true
|
||||
height: 40
|
||||
Button {
|
||||
id: exportButton
|
||||
enabled: !logManager.disableControls && !logManager.disableExport
|
||||
text: qsTr("Export...")
|
||||
activeFocusOnPress: true
|
||||
onClicked: logManager.exportLogs()
|
||||
}
|
||||
CheckBox {
|
||||
id: exportRelativeTimeCB
|
||||
enabled: !logManager.disableControls && !logManager.disableExport
|
||||
text: qsTr("Adjust timestamps")
|
||||
activeFocusOnPress: true
|
||||
checked: logManager.adjustExportedTimestamps
|
||||
onCheckedChanged: logManager.setAdjustExportedTimestamps(checked)
|
||||
}
|
||||
|
||||
Button {
|
||||
id: clearButton
|
||||
id: settingsButton
|
||||
enabled: !logManager.disableControls
|
||||
text: qsTr("Clear all logs")
|
||||
text: qsTr("Settings...")
|
||||
activeFocusOnPress: true
|
||||
onClicked: logManager.clearAllLogs()
|
||||
property bool showSettings: false
|
||||
onClicked: {
|
||||
showSettings = !showSettings;
|
||||
settingsTab.visible = showSettings;
|
||||
exportTab.visible = !showSettings;
|
||||
text = (showSettings ? qsTr("Logs...") : qsTr("Settings..."));
|
||||
}
|
||||
}
|
||||
Rectangle {
|
||||
Layout.fillWidth: true
|
||||
|
@ -6,6 +6,7 @@ QT += qml quick
|
||||
include(../../openpilotgcsplugin.pri)
|
||||
include(../../plugins/coreplugin/coreplugin.pri)
|
||||
include(../../plugins/uavobjects/uavobjects.pri)
|
||||
include(../../plugins/uavobjectutil/uavobjectutil.pri)
|
||||
include(../../plugins/uavtalk/uavtalk.pri)
|
||||
|
||||
HEADERS += flightlogplugin.h \
|
||||
|
@ -35,11 +35,13 @@
|
||||
#include <QQmlContext>
|
||||
|
||||
#include "flightlogmanager.h"
|
||||
#include "uavobject.h"
|
||||
|
||||
FlightLogDialog::FlightLogDialog(QWidget *parent, FlightLogManager *flightLogManager) :
|
||||
QDialog(parent)
|
||||
{
|
||||
qmlRegisterType<ExtendedDebugLogEntry>("org.openpilot", 1, 0, "DebugLogEntry");
|
||||
qmlRegisterType<UAVOLogSettingsWrapper>("org.openpilot", 1, 0, "UAVOLogSettingsWrapper");
|
||||
|
||||
setWindowIcon(QIcon(":/core/images/openpilot_logo_32.png"));
|
||||
setWindowTitle(tr("Manage flight side logs"));
|
||||
@ -49,6 +51,8 @@ FlightLogDialog::FlightLogDialog(QWidget *parent, FlightLogManager *flightLogMan
|
||||
QQuickView *view = new QQuickView();
|
||||
view->rootContext()->setContextProperty("dialog", this);
|
||||
view->rootContext()->setContextProperty("logStatus", flightLogManager->flightLogStatus());
|
||||
view->rootContext()->setContextProperty("logControl", flightLogManager->flightLogControl());
|
||||
view->rootContext()->setContextProperty("logSettings", flightLogManager->flightLogSettings());
|
||||
view->rootContext()->setContextProperty("logManager", flightLogManager);
|
||||
view->setResizeMode(QQuickView::SizeRootObjectToView);
|
||||
view->setSource(QUrl("qrc:/flightlog/FlightLogDialog.qml"));
|
||||
|
@ -30,33 +30,60 @@
|
||||
|
||||
#include <QApplication>
|
||||
#include <QFileDialog>
|
||||
#include <QXmlStreamReader>
|
||||
#include <QMessageBox>
|
||||
#include <QDebug>
|
||||
|
||||
#include "debuglogcontrol.h"
|
||||
#include "uavobjecthelper.h"
|
||||
#include "uavtalk/uavtalk.h"
|
||||
#include "utils/logfile.h"
|
||||
#include "uavdataobject.h"
|
||||
#include <uavobjectutil/uavobjectutilmanager.h>
|
||||
|
||||
FlightLogManager::FlightLogManager(QObject *parent) :
|
||||
QObject(parent), m_disableControls(false),
|
||||
m_disableExport(true), m_cancelDownload(false),
|
||||
m_adjustExportedTimestamps(true)
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
ExtensionSystem::PluginManager *pluginManager = ExtensionSystem::PluginManager::instance();
|
||||
|
||||
m_objectManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(pluginManager);
|
||||
|
||||
m_objectManager = pluginManager->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(m_objectManager);
|
||||
|
||||
m_flightLogControl = DebugLogControl::GetInstance(m_objectManager);
|
||||
m_telemtryManager = pluginManager->getObject<TelemetryManager>();
|
||||
Q_ASSERT(m_telemtryManager);
|
||||
|
||||
m_objectUtilManager = pluginManager->getObject<UAVObjectUtilManager>();
|
||||
Q_ASSERT(m_objectUtilManager);
|
||||
|
||||
m_flightLogControl = DebugLogControl::GetInstance(m_objectManager);
|
||||
Q_ASSERT(m_flightLogControl);
|
||||
|
||||
m_flightLogStatus = DebugLogStatus::GetInstance(m_objectManager);
|
||||
m_flightLogStatus = DebugLogStatus::GetInstance(m_objectManager);
|
||||
Q_ASSERT(m_flightLogStatus);
|
||||
connect(m_flightLogStatus, SIGNAL(FlightChanged(quint16)), this, SLOT(updateFlightEntries(quint16)));
|
||||
|
||||
m_flightLogEntry = DebugLogEntry::GetInstance(m_objectManager);
|
||||
m_flightLogEntry = DebugLogEntry::GetInstance(m_objectManager);
|
||||
Q_ASSERT(m_flightLogEntry);
|
||||
|
||||
m_flightLogSettings = DebugLogSettings::GetInstance(m_objectManager);
|
||||
Q_ASSERT(m_flightLogSettings);
|
||||
|
||||
m_objectPersistence = ObjectPersistence::GetInstance(m_objectManager);
|
||||
Q_ASSERT(m_objectPersistence);
|
||||
|
||||
updateFlightEntries(m_flightLogStatus->getFlight());
|
||||
|
||||
setupLogSettings();
|
||||
setupLogStatuses();
|
||||
setupUAVOWrappers();
|
||||
|
||||
connect(m_telemtryManager, SIGNAL(connected()), this, SLOT(connectionStatusChanged()));
|
||||
connect(m_telemtryManager, SIGNAL(disconnected()), this, SLOT(connectionStatusChanged()));
|
||||
connectionStatusChanged();
|
||||
}
|
||||
|
||||
FlightLogManager::~FlightLogManager()
|
||||
@ -64,6 +91,9 @@ FlightLogManager::~FlightLogManager()
|
||||
while (!m_logEntries.isEmpty()) {
|
||||
delete m_logEntries.takeFirst();
|
||||
}
|
||||
while (!m_uavoEntries.isEmpty()) {
|
||||
delete m_uavoEntries.takeFirst();
|
||||
}
|
||||
}
|
||||
|
||||
void addLogEntries(QQmlListProperty<ExtendedDebugLogEntry> *list, ExtendedDebugLogEntry *entry)
|
||||
@ -92,6 +122,32 @@ QQmlListProperty<ExtendedDebugLogEntry> FlightLogManager::logEntries()
|
||||
return QQmlListProperty<ExtendedDebugLogEntry>(this, &m_logEntries, &addLogEntries, &countLogEntries, &logEntryAt, &clearLogEntries);
|
||||
}
|
||||
|
||||
void addUAVOEntries(QQmlListProperty<UAVOLogSettingsWrapper> *list, UAVOLogSettingsWrapper *entry)
|
||||
{
|
||||
Q_UNUSED(list);
|
||||
Q_UNUSED(entry);
|
||||
}
|
||||
|
||||
int countUAVOEntries(QQmlListProperty<UAVOLogSettingsWrapper> *list)
|
||||
{
|
||||
return static_cast< QList<UAVOLogSettingsWrapper *> *>(list->data)->size();
|
||||
}
|
||||
|
||||
UAVOLogSettingsWrapper *uavoEntryAt(QQmlListProperty<UAVOLogSettingsWrapper> *list, int index)
|
||||
{
|
||||
return static_cast< QList<UAVOLogSettingsWrapper *> *>(list->data)->at(index);
|
||||
}
|
||||
|
||||
void clearUAVOEntries(QQmlListProperty<UAVOLogSettingsWrapper> *list)
|
||||
{
|
||||
return static_cast< QList<UAVOLogSettingsWrapper *> *>(list->data)->clear();
|
||||
}
|
||||
|
||||
QQmlListProperty<UAVOLogSettingsWrapper> FlightLogManager::uavoEntries()
|
||||
{
|
||||
return QQmlListProperty<UAVOLogSettingsWrapper>(this, &m_uavoEntries, &addUAVOEntries, &countUAVOEntries, &uavoEntryAt, &clearUAVOEntries);
|
||||
}
|
||||
|
||||
QStringList FlightLogManager::flightEntries()
|
||||
{
|
||||
return m_flightEntries;
|
||||
@ -305,8 +361,7 @@ void FlightLogManager::exportLogs()
|
||||
|
||||
QString selectedFilter = csvFilter;
|
||||
|
||||
QString fileName = QFileDialog::getSaveFileName(NULL, tr("Save Log Entries"),
|
||||
QString("OP-%1").arg(QDateTime::currentDateTime().toString("yyyy-MM-dd_hh-mm-ss")),
|
||||
QString fileName = QFileDialog::getSaveFileName(NULL, tr("Save Log Entries"), QDir::homePath(),
|
||||
QString("%1;;%2;;%3").arg(oplFilter, csvFilter, xmlFilter), &selectedFilter);
|
||||
if (!fileName.isEmpty()) {
|
||||
if (selectedFilter == oplFilter) {
|
||||
@ -336,6 +391,138 @@ void FlightLogManager::cancelExportLogs()
|
||||
m_cancelDownload = true;
|
||||
}
|
||||
|
||||
void FlightLogManager::loadSettings()
|
||||
{
|
||||
QString xmlFilter = tr("XML file %1").arg("(*.xml)");
|
||||
QString fileName = QFileDialog::getOpenFileName(NULL, tr("Load Log Settings"), QDir::homePath(), QString("%1").arg(xmlFilter));
|
||||
|
||||
if (!fileName.isEmpty()) {
|
||||
if (!fileName.endsWith(".xml")) {
|
||||
fileName.append(".xml");
|
||||
}
|
||||
QFile xmlFile(fileName);
|
||||
QString errorString;
|
||||
if (xmlFile.open(QFile::ReadOnly)) {
|
||||
QXmlStreamReader xmlReader(&xmlFile);
|
||||
while (xmlReader.readNextStartElement() && xmlReader.name() == "settings") {
|
||||
bool ok;
|
||||
|
||||
int version = xmlReader.attributes().value("version").toInt(&ok);
|
||||
if (!ok || version != LOG_SETTINGS_FILE_VERSION) {
|
||||
errorString = tr("The file has the wrong version or could not parse version information.");
|
||||
break;
|
||||
}
|
||||
|
||||
setLoggingEnabled(xmlReader.attributes().value("enabled").toInt(&ok));
|
||||
if (!ok) {
|
||||
errorString = tr("Could not parse enabled attribute.");
|
||||
break;
|
||||
}
|
||||
|
||||
while (xmlReader.readNextStartElement()) {
|
||||
if (xmlReader.name() == "setting") {
|
||||
QString name = xmlReader.attributes().value("name").toString();
|
||||
int level = xmlReader.attributes().value("level").toInt(&ok);
|
||||
if (ok) {
|
||||
int period = xmlReader.attributes().value("period").toInt(&ok);
|
||||
if (ok && updateLogWrapper(name, level, period)) {} else {
|
||||
errorString = tr("Could not parse period attribute, or object with name '%1' could not be found.").arg(name);
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
errorString = tr("Could not parse level attribute on setting '%1'").arg(name);
|
||||
break;
|
||||
}
|
||||
}
|
||||
xmlReader.skipCurrentElement();
|
||||
}
|
||||
xmlReader.skipCurrentElement();
|
||||
}
|
||||
if (!xmlReader.atEnd() && (xmlReader.hasError() || !errorString.isEmpty())) {
|
||||
QMessageBox::warning(NULL, tr("Settings file corrupt."),
|
||||
tr("The file loaded is not in the correct format.\nPlease check the file.\n%1")
|
||||
.arg(xmlReader.hasError() ? xmlReader.errorString() : errorString),
|
||||
QMessageBox::Ok);
|
||||
}
|
||||
}
|
||||
xmlFile.close();
|
||||
}
|
||||
}
|
||||
|
||||
void FlightLogManager::saveSettings()
|
||||
{
|
||||
QString xmlFilter = tr("XML file %1").arg("(*.xml)");
|
||||
QString fileName = QFileDialog::getSaveFileName(NULL, tr("Save Log Settings"),
|
||||
QDir::homePath(), QString("%1").arg(xmlFilter));
|
||||
|
||||
if (!fileName.isEmpty()) {
|
||||
if (!fileName.endsWith(".xml")) {
|
||||
fileName.append(".xml");
|
||||
}
|
||||
QFile xmlFile(fileName);
|
||||
|
||||
if (xmlFile.open(QFile::WriteOnly | QFile::Truncate)) {
|
||||
QXmlStreamWriter xmlWriter(&xmlFile);
|
||||
xmlWriter.setAutoFormatting(true);
|
||||
xmlWriter.setAutoFormattingIndent(4);
|
||||
|
||||
xmlWriter.writeStartDocument("1.0", true);
|
||||
xmlWriter.writeComment("This file was created by the flight log settings function in OpenPilot GCS.");
|
||||
xmlWriter.writeStartElement("settings");
|
||||
xmlWriter.writeAttribute("version", QString::number(LOG_SETTINGS_FILE_VERSION));
|
||||
xmlWriter.writeAttribute("enabled", QString::number(m_loggingEnabled));
|
||||
foreach(UAVOLogSettingsWrapper * wrapper, m_uavoEntries) {
|
||||
xmlWriter.writeStartElement("setting");
|
||||
xmlWriter.writeAttribute("name", wrapper->name());
|
||||
xmlWriter.writeAttribute("level", QString::number(wrapper->setting()));
|
||||
xmlWriter.writeAttribute("period", QString::number(wrapper->period()));
|
||||
xmlWriter.writeEndElement();
|
||||
}
|
||||
xmlWriter.writeEndElement();
|
||||
xmlWriter.writeEndDocument();
|
||||
xmlFile.flush();
|
||||
xmlFile.close();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void FlightLogManager::resetSettings(bool clear)
|
||||
{
|
||||
setLoggingEnabled(clear ? 0 : m_flightLogSettings->getLoggingEnabled());
|
||||
foreach(UAVOLogSettingsWrapper * wrapper, m_uavoEntries) {
|
||||
wrapper->reset(clear);
|
||||
}
|
||||
}
|
||||
|
||||
void FlightLogManager::saveSettingsToBoard()
|
||||
{
|
||||
m_flightLogSettings->setLoggingEnabled(m_loggingEnabled);
|
||||
m_flightLogSettings->updated();
|
||||
saveUAVObjectToFlash(m_flightLogSettings);
|
||||
|
||||
foreach(UAVOLogSettingsWrapper * wrapper, m_uavoEntries) {
|
||||
if (wrapper->dirty()) {
|
||||
UAVObject::Metadata meta = wrapper->object()->getMetadata();
|
||||
wrapper->object()->SetLoggingUpdateMode(meta, wrapper->settingAsUpdateMode());
|
||||
meta.loggingUpdatePeriod = wrapper->period();
|
||||
|
||||
// As metadata are set up to update via telemetry on change
|
||||
// this call will send the update to the board.
|
||||
wrapper->object()->setMetadata(meta);
|
||||
|
||||
if (saveUAVObjectToFlash(wrapper->object()->getMetaObject())) {
|
||||
wrapper->setDirty(false);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool FlightLogManager::saveUAVObjectToFlash(UAVObject *object)
|
||||
{
|
||||
m_objectUtilManager->saveObjectToSD(object);
|
||||
return true;
|
||||
}
|
||||
|
||||
void FlightLogManager::updateFlightEntries(quint16 currentFlight)
|
||||
{
|
||||
Q_UNUSED(currentFlight);
|
||||
@ -353,6 +540,65 @@ void FlightLogManager::updateFlightEntries(quint16 currentFlight)
|
||||
}
|
||||
}
|
||||
|
||||
void FlightLogManager::setupUAVOWrappers()
|
||||
{
|
||||
foreach(QList<UAVObject *> objectList, m_objectManager->getObjects()) {
|
||||
UAVObject *object = objectList.at(0);
|
||||
|
||||
if (!object->isMetaDataObject() && !object->isSettingsObject()) {
|
||||
UAVOLogSettingsWrapper *wrapper = new UAVOLogSettingsWrapper(qobject_cast<UAVDataObject *>(object));
|
||||
m_uavoEntries.append(wrapper);
|
||||
m_uavoEntriesHash[wrapper->name()] = wrapper;
|
||||
}
|
||||
}
|
||||
emit uavoEntriesChanged();
|
||||
}
|
||||
|
||||
void FlightLogManager::setupLogSettings()
|
||||
{
|
||||
// Corresponds to:
|
||||
// typedef enum {
|
||||
// UPDATEMODE_MANUAL = 0, /** Manually update object, by calling the updated() function */
|
||||
// UPDATEMODE_PERIODIC = 1, /** Automatically update object at periodic intervals */
|
||||
// UPDATEMODE_ONCHANGE = 2, /** Only update object when its data changes */
|
||||
// UPDATEMODE_THROTTLED = 3 /** Object is updated on change, but not more often than the interval time */
|
||||
// } UpdateMode;
|
||||
|
||||
m_logSettings << tr("Disabled") << tr("Periodically") << tr("When updated") << tr("Throttled");
|
||||
}
|
||||
|
||||
void FlightLogManager::setupLogStatuses()
|
||||
{
|
||||
m_logStatuses << tr("Never") << tr("Only when Armed") << tr("Always");
|
||||
}
|
||||
|
||||
void FlightLogManager::connectionStatusChanged()
|
||||
{
|
||||
if (m_telemtryManager->isConnected()) {
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
setBoardConnected(utilMngr->getBoardModel() == 0x0903);
|
||||
} else {
|
||||
setBoardConnected(false);
|
||||
}
|
||||
if (boardConnected()) {
|
||||
resetSettings(false);
|
||||
}
|
||||
}
|
||||
|
||||
bool FlightLogManager::updateLogWrapper(QString name, int level, int period)
|
||||
{
|
||||
UAVOLogSettingsWrapper *wrapper = m_uavoEntriesHash[name];
|
||||
|
||||
if (wrapper) {
|
||||
wrapper->setSetting(level);
|
||||
wrapper->setPeriod(period);
|
||||
qDebug() << "Wrapper" << name << ", level" << level << ", period" << period;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
ExtendedDebugLogEntry::ExtendedDebugLogEntry() : DebugLogEntry(),
|
||||
m_object(0)
|
||||
{}
|
||||
@ -415,3 +661,51 @@ void ExtendedDebugLogEntry::setData(const DebugLogEntry::DataFields &data, UAVOb
|
||||
m_object->unpack(getData().Data);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
UAVOLogSettingsWrapper::UAVOLogSettingsWrapper() : QObject()
|
||||
{}
|
||||
|
||||
UAVOLogSettingsWrapper::UAVOLogSettingsWrapper(UAVDataObject *object) : QObject(),
|
||||
m_object(object), m_setting(DISABLED), m_period(0), m_dirty(0)
|
||||
{
|
||||
reset(false);
|
||||
}
|
||||
|
||||
UAVOLogSettingsWrapper::~UAVOLogSettingsWrapper()
|
||||
{}
|
||||
|
||||
void UAVOLogSettingsWrapper::reset(bool clear)
|
||||
{
|
||||
setSetting(m_object->GetLoggingUpdateMode(m_object->getMetadata()));
|
||||
setPeriod(m_object->getMetadata().loggingUpdatePeriod);
|
||||
if (clear) {
|
||||
int oldSetting = setting();
|
||||
int oldPeriod = period();
|
||||
setSetting(0);
|
||||
setPeriod(0);
|
||||
setDirty(oldSetting != setting() || oldPeriod != period());
|
||||
} else {
|
||||
setDirty(false);
|
||||
}
|
||||
}
|
||||
|
||||
UAVObject::UpdateMode UAVOLogSettingsWrapper::settingAsUpdateMode()
|
||||
{
|
||||
switch (m_setting) {
|
||||
case 0:
|
||||
return UAVObject::UPDATEMODE_MANUAL;
|
||||
|
||||
case 1:
|
||||
return UAVObject::UPDATEMODE_PERIODIC;
|
||||
|
||||
case 2:
|
||||
return UAVObject::UPDATEMODE_ONCHANGE;
|
||||
|
||||
case 3:
|
||||
return UAVObject::UPDATEMODE_THROTTLED;
|
||||
|
||||
default:
|
||||
return UAVObject::UPDATEMODE_MANUAL;
|
||||
}
|
||||
}
|
||||
|
@ -30,15 +30,108 @@
|
||||
|
||||
#include <QObject>
|
||||
#include <QList>
|
||||
#include <QHash>
|
||||
#include <QQmlListProperty>
|
||||
#include <QSemaphore>
|
||||
#include <QXmlStreamWriter>
|
||||
#include <QTextStream>
|
||||
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavobjectutilmanager.h"
|
||||
#include "debuglogentry.h"
|
||||
#include "debuglogstatus.h"
|
||||
#include "debuglogsettings.h"
|
||||
#include "debuglogcontrol.h"
|
||||
#include "objectpersistence.h"
|
||||
#include "uavtalk/telemetrymanager.h"
|
||||
|
||||
class UAVOLogSettingsWrapper : public QObject {
|
||||
Q_OBJECT Q_PROPERTY(UAVDataObject *object READ object NOTIFY objectChanged)
|
||||
Q_PROPERTY(QString name READ name NOTIFY nameChanged)
|
||||
Q_PROPERTY(int setting READ setting WRITE setSetting NOTIFY settingChanged)
|
||||
Q_PROPERTY(int period READ period WRITE setPeriod NOTIFY periodChanged)
|
||||
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
|
||||
|
||||
public:
|
||||
enum UAVLogSetting { DISABLED = 0, ON_CHANGE, THROTTLED, PERIODICALLY };
|
||||
|
||||
explicit UAVOLogSettingsWrapper();
|
||||
explicit UAVOLogSettingsWrapper(UAVDataObject *object);
|
||||
~UAVOLogSettingsWrapper();
|
||||
|
||||
QString name() const
|
||||
{
|
||||
return m_object->getName();
|
||||
}
|
||||
|
||||
int setting() const
|
||||
{
|
||||
return m_setting;
|
||||
}
|
||||
|
||||
UAVObject::UpdateMode settingAsUpdateMode();
|
||||
|
||||
int period() const
|
||||
{
|
||||
return m_period;
|
||||
}
|
||||
|
||||
UAVDataObject *object() const
|
||||
{
|
||||
return m_object;
|
||||
}
|
||||
|
||||
bool dirty() const
|
||||
{
|
||||
return m_dirty;
|
||||
}
|
||||
|
||||
public slots:
|
||||
void setSetting(int setting)
|
||||
{
|
||||
if (m_setting != setting) {
|
||||
m_setting = setting;
|
||||
setDirty(true);
|
||||
if (m_setting != 1 && m_setting != 3) {
|
||||
setPeriod(0);
|
||||
}
|
||||
emit settingChanged(setting);
|
||||
}
|
||||
}
|
||||
|
||||
void setPeriod(int arg)
|
||||
{
|
||||
if (m_period != arg) {
|
||||
m_period = arg;
|
||||
setDirty(true);
|
||||
emit periodChanged(arg);
|
||||
}
|
||||
}
|
||||
|
||||
void setDirty(bool arg)
|
||||
{
|
||||
if (m_dirty != arg) {
|
||||
m_dirty = arg;
|
||||
emit dirtyChanged(arg);
|
||||
}
|
||||
}
|
||||
|
||||
void reset(bool clear);
|
||||
|
||||
signals:
|
||||
void settingChanged(int setting);
|
||||
void nameChanged(QString name);
|
||||
void periodChanged(int period);
|
||||
void objectChanged(UAVDataObject *arg);
|
||||
|
||||
void dirtyChanged(bool arg);
|
||||
|
||||
private:
|
||||
UAVDataObject *m_object;
|
||||
int m_setting;
|
||||
int m_period;
|
||||
bool m_dirty;
|
||||
};
|
||||
|
||||
class ExtendedDebugLogEntry : public DebugLogEntry {
|
||||
Q_OBJECT Q_PROPERTY(QString LogString READ getLogString WRITE setLogString NOTIFY LogStringUpdated)
|
||||
@ -72,19 +165,35 @@ private:
|
||||
|
||||
class FlightLogManager : public QObject {
|
||||
Q_OBJECT Q_PROPERTY(DebugLogStatus *flightLogStatus READ flightLogStatus)
|
||||
Q_PROPERTY(DebugLogControl * flightLogControl READ flightLogControl)
|
||||
Q_PROPERTY(DebugLogSettings * flightLogSettings READ flightLogSettings)
|
||||
Q_PROPERTY(QQmlListProperty<ExtendedDebugLogEntry> logEntries READ logEntries NOTIFY logEntriesChanged)
|
||||
Q_PROPERTY(QStringList flightEntries READ flightEntries NOTIFY flightEntriesChanged)
|
||||
Q_PROPERTY(bool disableControls READ disableControls WRITE setDisableControls NOTIFY disableControlsChanged)
|
||||
Q_PROPERTY(bool disableExport READ disableExport WRITE setDisableExport NOTIFY disableExportChanged)
|
||||
Q_PROPERTY(bool adjustExportedTimestamps READ adjustExportedTimestamps WRITE setAdjustExportedTimestamps NOTIFY adjustExportedTimestampsChanged)
|
||||
Q_PROPERTY(bool boardConnected READ boardConnected WRITE setBoardConnected NOTIFY boardConnectedChanged)
|
||||
|
||||
Q_PROPERTY(QQmlListProperty<UAVOLogSettingsWrapper> uavoEntries READ uavoEntries NOTIFY uavoEntriesChanged)
|
||||
Q_PROPERTY(QStringList logSettings READ logSettings NOTIFY logSettingsChanged)
|
||||
Q_PROPERTY(QStringList logStatuses READ logStatuses NOTIFY logStatusesChanged)
|
||||
Q_PROPERTY(int loggingEnabled READ loggingEnabled WRITE setLoggingEnabled NOTIFY loggingEnabledChanged)
|
||||
|
||||
|
||||
public:
|
||||
explicit FlightLogManager(QObject *parent = 0);
|
||||
~FlightLogManager();
|
||||
|
||||
QQmlListProperty<ExtendedDebugLogEntry> logEntries();
|
||||
QQmlListProperty<UAVOLogSettingsWrapper> uavoEntries();
|
||||
|
||||
QStringList flightEntries();
|
||||
|
||||
QStringList logSettings()
|
||||
{
|
||||
return m_logSettings;
|
||||
}
|
||||
|
||||
DebugLogStatus *flightLogStatus() const
|
||||
{
|
||||
return m_flightLogStatus;
|
||||
@ -107,19 +216,54 @@ public:
|
||||
return m_adjustExportedTimestamps;
|
||||
}
|
||||
|
||||
bool boardConnected() const
|
||||
{
|
||||
return m_boardConnected;
|
||||
}
|
||||
|
||||
QStringList logStatuses() const
|
||||
{
|
||||
return m_logStatuses;
|
||||
}
|
||||
|
||||
DebugLogControl *flightLogControl() const
|
||||
{
|
||||
return m_flightLogControl;
|
||||
}
|
||||
|
||||
DebugLogSettings *flightLogSettings() const
|
||||
{
|
||||
return m_flightLogSettings;
|
||||
}
|
||||
|
||||
int loggingEnabled() const
|
||||
{
|
||||
return m_loggingEnabled;
|
||||
}
|
||||
|
||||
signals:
|
||||
void logEntriesChanged();
|
||||
void flightEntriesChanged();
|
||||
void logSettingsChanged();
|
||||
void uavoEntriesChanged();
|
||||
void disableControlsChanged(bool arg);
|
||||
void disableExportChanged(bool arg);
|
||||
|
||||
void adjustExportedTimestampsChanged(bool arg);
|
||||
void boardConnectedChanged(bool arg);
|
||||
|
||||
void logStatusesChanged(QStringList arg);
|
||||
void loggingEnabledChanged(int arg);
|
||||
|
||||
public slots:
|
||||
void clearAllLogs();
|
||||
void retrieveLogs(int flightToRetrieve = -1);
|
||||
void exportLogs();
|
||||
void cancelExportLogs();
|
||||
void loadSettings();
|
||||
void saveSettings();
|
||||
void resetSettings(bool clear);
|
||||
void saveSettingsToBoard();
|
||||
bool saveUAVObjectToFlash(UAVObject *object);
|
||||
|
||||
void setDisableControls(bool arg)
|
||||
{
|
||||
@ -145,26 +289,60 @@ public slots:
|
||||
}
|
||||
}
|
||||
|
||||
void setBoardConnected(bool arg)
|
||||
{
|
||||
if (m_boardConnected != arg) {
|
||||
m_boardConnected = arg;
|
||||
emit boardConnectedChanged(arg);
|
||||
}
|
||||
}
|
||||
|
||||
void setLoggingEnabled(int arg)
|
||||
{
|
||||
if (m_loggingEnabled != arg) {
|
||||
m_loggingEnabled = arg;
|
||||
emit loggingEnabledChanged(arg);
|
||||
}
|
||||
}
|
||||
|
||||
private slots:
|
||||
void updateFlightEntries(quint16 currentFlight);
|
||||
void setupUAVOWrappers();
|
||||
void setupLogSettings();
|
||||
void setupLogStatuses();
|
||||
void connectionStatusChanged();
|
||||
bool updateLogWrapper(QString name, int level, int period);
|
||||
|
||||
private:
|
||||
UAVObjectManager *m_objectManager;
|
||||
UAVObjectUtilManager *m_objectUtilManager;
|
||||
TelemetryManager *m_telemtryManager;
|
||||
DebugLogControl *m_flightLogControl;
|
||||
DebugLogStatus *m_flightLogStatus;
|
||||
DebugLogEntry *m_flightLogEntry;
|
||||
DebugLogSettings *m_flightLogSettings;
|
||||
ObjectPersistence *m_objectPersistence;
|
||||
|
||||
QList<ExtendedDebugLogEntry *> m_logEntries;
|
||||
QStringList m_flightEntries;
|
||||
QStringList m_logSettings;
|
||||
QStringList m_logStatuses;
|
||||
|
||||
static const int UAVTALK_TIMEOUT = 4000;
|
||||
bool m_disableControls;
|
||||
bool m_disableExport;
|
||||
bool m_cancelDownload;
|
||||
bool m_adjustExportedTimestamps;
|
||||
QList<UAVOLogSettingsWrapper *> m_uavoEntries;
|
||||
QHash<QString, UAVOLogSettingsWrapper *> m_uavoEntriesHash;
|
||||
|
||||
void exportToOPL(QString fileName);
|
||||
void exportToCSV(QString fileName);
|
||||
void exportToXML(QString fileName);
|
||||
|
||||
static const int UAVTALK_TIMEOUT = 4000;
|
||||
static const int LOG_SETTINGS_FILE_VERSION = 1;
|
||||
bool m_disableControls;
|
||||
bool m_disableExport;
|
||||
bool m_cancelDownload;
|
||||
bool m_adjustExportedTimestamps;
|
||||
bool m_boardConnected;
|
||||
int m_loggingEnabled;
|
||||
};
|
||||
|
||||
#endif // FLIGHTLOGMANAGER_H
|
||||
|
@ -75,6 +75,8 @@ void FlightLogPlugin::ShowLogManagementDialog()
|
||||
m_logDialog = new FlightLogDialog(0, new FlightLogManager());
|
||||
connect(m_logDialog, SIGNAL(finished(int)), this, SLOT(LogManagementDialogClosed()));
|
||||
m_logDialog->show();
|
||||
} else {
|
||||
m_logDialog->raise();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1,45 +1,35 @@
|
||||
TEMPLATE = lib
|
||||
TARGET = GCSControl
|
||||
QT += svg
|
||||
QT += opengl
|
||||
QT += network
|
||||
TARGET = GCSControl
|
||||
|
||||
include(../../openpilotgcsplugin.pri)
|
||||
include(../../plugins/coreplugin/coreplugin.pri)
|
||||
QT += svg opengl network
|
||||
|
||||
include(../../openpilotgcsplugin.pri)
|
||||
include(../../plugins/coreplugin/coreplugin.pri)
|
||||
include(../../plugins/uavobjects/uavobjects.pri)
|
||||
include(../../libs/sdlgamepad/sdlgamepad.pri)
|
||||
|
||||
macx {
|
||||
# Ensures that SDL framework and header files are found when compiled with Qt5.1.1
|
||||
INCLUDEPATH += /Library/Frameworks/SDL.framework/Headers
|
||||
SDL = -F/Library/Frameworks
|
||||
# Add SDL to CFLAGS fixes build problems on mac
|
||||
QMAKE_CFLAGS += $$SDL
|
||||
QMAKE_CXXFLAGS += $$SDL
|
||||
# Let the linker know where to find the frameworks
|
||||
LIBS += $$SDL
|
||||
}
|
||||
|
||||
|
||||
HEADERS += gcscontrolgadget.h \
|
||||
HEADERS += \
|
||||
gcscontrolgadget.h \
|
||||
gcscontrolgadgetconfiguration.h \
|
||||
gcscontrolgadgetoptionspage.h
|
||||
HEADERS += joystickcontrol.h
|
||||
HEADERS += gcscontrolgadgetwidget.h
|
||||
HEADERS += gcscontrolgadgetfactory.h
|
||||
HEADERS += gcscontrolplugin.h
|
||||
gcscontrolgadgetoptionspage.h \
|
||||
gcscontrolgadgetwidget.h \
|
||||
gcscontrolgadgetfactory.h \
|
||||
gcscontrolplugin.h \
|
||||
joystickcontrol.h
|
||||
|
||||
SOURCES += gcscontrolgadget.cpp \
|
||||
SOURCES += \
|
||||
gcscontrolgadget.cpp \
|
||||
gcscontrolgadgetconfiguration.cpp \
|
||||
gcscontrolgadgetoptionspage.cpp
|
||||
SOURCES += gcscontrolgadgetwidget.cpp
|
||||
SOURCES += gcscontrolgadgetfactory.cpp
|
||||
SOURCES += gcscontrolplugin.cpp
|
||||
SOURCES += joystickcontrol.cpp
|
||||
gcscontrolgadgetoptionspage.cpp \
|
||||
gcscontrolgadgetwidget.cpp \
|
||||
gcscontrolgadgetfactory.cpp \
|
||||
gcscontrolplugin.cpp \
|
||||
joystickcontrol.cpp
|
||||
|
||||
OTHER_FILES += GCSControl.pluginspec
|
||||
|
||||
FORMS += gcscontrol.ui \
|
||||
FORMS += \
|
||||
gcscontrol.ui \
|
||||
gcscontrolgadgetoptionspage.ui
|
||||
|
||||
RESOURCES += gcscontrol.qrc
|
||||
|
@ -31,7 +31,6 @@
|
||||
#include "coreplugin/dialogs/ioptionspage.h"
|
||||
#include "gcscontrolplugin.h"
|
||||
#include "sdlgamepad/sdlgamepad.h"
|
||||
#include <SDL/SDL.h>
|
||||
|
||||
#include <QDebug>
|
||||
#include <QCheckBox>
|
||||
|
@ -33,8 +33,8 @@
|
||||
|
||||
bool isFirstRun = true;
|
||||
QString debugInfo(DBG_BUFFER_MAX_SIZE, ' ');
|
||||
QString pluginFolder(MAX_PATH, ' ');
|
||||
QString outputFolder(MAX_PATH, ' ');
|
||||
QString pluginFolder(_MAX_PATH, ' ');
|
||||
QString outputFolder(_MAX_PATH, ' ');
|
||||
|
||||
QList<quint16> videoModes;
|
||||
QTime ledTimer;
|
||||
|
@ -230,7 +230,7 @@ void LoggingThread::retrieveSettings()
|
||||
QList< QList<UAVDataObject *> > objs = objMngr->getDataObjects();
|
||||
for (int n = 0; n < objs.length(); ++n) {
|
||||
UAVDataObject *obj = objs[n][0];
|
||||
if (obj->isSettings()) {
|
||||
if (obj->isSettingsObject()) {
|
||||
queue.enqueue(obj);
|
||||
}
|
||||
}
|
||||
|
@ -292,11 +292,9 @@ void modelMapProxy::dataChanged(const QModelIndex &topLeft, const QModelIndex &b
|
||||
void modelMapProxy::rowsInserted(const QModelIndex &parent, int first, int last)
|
||||
{
|
||||
Q_UNUSED(parent);
|
||||
Q_UNUSED(first);
|
||||
Q_UNUSED(last);
|
||||
|
||||
/*
|
||||
for (int x = first; x < last + 1; x++) {
|
||||
|
||||
for (int x = first; x < last + 1; x++) {
|
||||
QModelIndex index;
|
||||
WayPointItem *item;
|
||||
internals::PointLatLng latlng;
|
||||
@ -324,8 +322,8 @@ void modelMapProxy::rowsInserted(const QModelIndex &parent, int first, int last)
|
||||
} else {
|
||||
item = myMap->WPInsert(latlng, altitude, desc, x);
|
||||
}
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
refreshOverlays();
|
||||
}
|
||||
void modelMapProxy::deleteWayPoint(int number)
|
||||
|
@ -517,7 +517,7 @@ bool VehicleConfigurationHelper::saveChangesToController(bool save)
|
||||
m_transactionOK = false;
|
||||
UAVDataObject *obj = objPair->first;
|
||||
QString objDescription = objPair->second;
|
||||
if (UAVObject::GetGcsAccess(obj->getMetadata()) != UAVObject::ACCESS_READONLY && obj->isSettings()) {
|
||||
if (UAVObject::GetGcsAccess(obj->getMetadata()) != UAVObject::ACCESS_READONLY && obj->isSettingsObject()) {
|
||||
emit saveProgress(m_modifiedObjects.count() + 1, ++m_progress, objDescription);
|
||||
|
||||
m_currentTransactionObjectID = obj->getObjID();
|
||||
|
@ -97,6 +97,8 @@ void SystemHealthGadgetWidget::updateAlarms(UAVObject *systemAlarm)
|
||||
delete item; // removeItem does _not_ delete the item.
|
||||
}
|
||||
|
||||
QMatrix backgroundMatrix = (m_renderer->matrixForElement(background->elementId())).inverted();
|
||||
|
||||
QString alarm = systemAlarm->getName();
|
||||
foreach(UAVObjectField * field, systemAlarm->getFields()) {
|
||||
for (uint i = 0; i < field->getNumElements(); ++i) {
|
||||
@ -104,18 +106,21 @@ void SystemHealthGadgetWidget::updateAlarms(UAVObject *systemAlarm)
|
||||
QString value = field->getValue(i).toString();
|
||||
if (!missingElements->contains(element)) {
|
||||
if (m_renderer->elementExists(element)) {
|
||||
QMatrix blockMatrix = m_renderer->matrixForElement(element);
|
||||
qreal startX = blockMatrix.mapRect(m_renderer->boundsOnElement(element)).x();
|
||||
qreal startY = blockMatrix.mapRect(m_renderer->boundsOnElement(element)).y();
|
||||
QString element2 = element + "-" + value;
|
||||
QString element2 = element + "-" + value;
|
||||
if (!missingElements->contains(element2)) {
|
||||
if (m_renderer->elementExists(element2)) {
|
||||
// element2 is in global coordinates
|
||||
// transform its matrix into the coordinates of background
|
||||
QMatrix blockMatrix = backgroundMatrix * m_renderer->matrixForElement(element2);
|
||||
// use this composed projection to get the position in background coordinates
|
||||
QRectF rectProjected = blockMatrix.mapRect(m_renderer->boundsOnElement(element2));
|
||||
|
||||
QGraphicsSvgItem *ind = new QGraphicsSvgItem();
|
||||
ind->setSharedRenderer(m_renderer);
|
||||
ind->setElementId(element2);
|
||||
ind->setParentItem(background);
|
||||
QTransform matrix;
|
||||
matrix.translate(startX, startY);
|
||||
matrix.translate(rectProjected.x(), rectProjected.y());
|
||||
ind->setTransform(matrix, false);
|
||||
} else {
|
||||
if (value.compare("Uninitialised") != 0) {
|
||||
|
@ -99,7 +99,7 @@ void UAVObjectTreeModel::newObject(UAVObject *obj)
|
||||
|
||||
void UAVObjectTreeModel::addDataObject(UAVDataObject *obj)
|
||||
{
|
||||
TopTreeItem *root = obj->isSettings() ? m_settingsTree : m_nonSettingsTree;
|
||||
TopTreeItem *root = obj->isSettingsObject() ? m_settingsTree : m_nonSettingsTree;
|
||||
|
||||
TreeItem *parent = root;
|
||||
|
||||
@ -461,7 +461,7 @@ ObjectTreeItem *UAVObjectTreeModel::findObjectTreeItem(UAVObject *object)
|
||||
|
||||
DataObjectTreeItem *UAVObjectTreeModel::findDataObjectTreeItem(UAVDataObject *obj)
|
||||
{
|
||||
TopTreeItem *root = obj->isSettings() ? m_settingsTree : m_nonSettingsTree;
|
||||
TopTreeItem *root = obj->isSettingsObject() ? m_settingsTree : m_nonSettingsTree;
|
||||
|
||||
return root->findDataObjectTreeItemByObjectId(obj->getObjID());
|
||||
}
|
||||
@ -471,7 +471,7 @@ MetaObjectTreeItem *UAVObjectTreeModel::findMetaObjectTreeItem(UAVMetaObject *ob
|
||||
UAVDataObject *dataObject = qobject_cast<UAVDataObject *>(obj->getParentObject());
|
||||
|
||||
Q_ASSERT(dataObject);
|
||||
TopTreeItem *root = dataObject->isSettings() ? m_settingsTree : m_nonSettingsTree;
|
||||
TopTreeItem *root = dataObject->isSettingsObject() ? m_settingsTree : m_nonSettingsTree;
|
||||
return root->findMetaObjectTreeItemByObjectId(obj->getObjID());
|
||||
}
|
||||
|
||||
|
@ -30,40 +30,40 @@
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
UAVDataObject::UAVDataObject(quint32 objID, bool isSingleInst, bool isSet, const QString & name) :
|
||||
UAVDataObject::UAVDataObject(quint32 objID, bool isSingleInst, bool isSettings, const QString & name) :
|
||||
UAVObject(objID, isSingleInst, name)
|
||||
{
|
||||
mobj = NULL;
|
||||
this->isSet = isSet;
|
||||
m_metaObject = NULL;
|
||||
this->m_isSettings = isSettings;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize instance ID and assign a metaobject
|
||||
*/
|
||||
void UAVDataObject::initialize(quint32 instID, UAVMetaObject *mobj)
|
||||
void UAVDataObject::initialize(quint32 instID, UAVMetaObject *metaObject)
|
||||
{
|
||||
QMutexLocker locker(mutex);
|
||||
|
||||
this->mobj = mobj;
|
||||
this->m_metaObject = metaObject;
|
||||
UAVObject::initialize(instID);
|
||||
}
|
||||
|
||||
/**
|
||||
* Assign a metaobject
|
||||
*/
|
||||
void UAVDataObject::initialize(UAVMetaObject *mobj)
|
||||
void UAVDataObject::initialize(UAVMetaObject *metaObject)
|
||||
{
|
||||
QMutexLocker locker(mutex);
|
||||
|
||||
this->mobj = mobj;
|
||||
this->m_metaObject = metaObject;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if this is a data object holding module settings
|
||||
*/
|
||||
bool UAVDataObject::isSettings()
|
||||
bool UAVDataObject::isSettingsObject()
|
||||
{
|
||||
return isSet;
|
||||
return m_isSettings;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -71,8 +71,8 @@ bool UAVDataObject::isSettings()
|
||||
*/
|
||||
void UAVDataObject::setMetadata(const Metadata & mdata)
|
||||
{
|
||||
if (mobj != NULL) {
|
||||
mobj->setData(mdata);
|
||||
if (m_metaObject != NULL) {
|
||||
m_metaObject->setData(mdata);
|
||||
}
|
||||
}
|
||||
|
||||
@ -81,8 +81,8 @@ void UAVDataObject::setMetadata(const Metadata & mdata)
|
||||
*/
|
||||
UAVObject::Metadata UAVDataObject::getMetadata(void)
|
||||
{
|
||||
if (mobj != NULL) {
|
||||
return mobj->getData();
|
||||
if (m_metaObject != NULL) {
|
||||
return m_metaObject->getData();
|
||||
} else {
|
||||
return getDefaultMetadata();
|
||||
}
|
||||
@ -93,5 +93,10 @@ UAVObject::Metadata UAVDataObject::getMetadata(void)
|
||||
*/
|
||||
UAVMetaObject *UAVDataObject::getMetaObject()
|
||||
{
|
||||
return mobj;
|
||||
return m_metaObject;
|
||||
}
|
||||
|
||||
bool UAVDataObject::isDataObject()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
@ -38,19 +38,21 @@ class UAVOBJECTS_EXPORT UAVDataObject : public UAVObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
UAVDataObject(quint32 objID, bool isSingleInst, bool isSet, const QString & name);
|
||||
void initialize(quint32 instID, UAVMetaObject *mobj);
|
||||
void initialize(UAVMetaObject *mobj);
|
||||
bool isSettings();
|
||||
UAVDataObject(quint32 objID, bool isSingleInst, bool isSettingsObject, const QString & name);
|
||||
void initialize(quint32 instID, UAVMetaObject *metaObject);
|
||||
void initialize(UAVMetaObject *metaObject);
|
||||
void setMetadata(const Metadata & mdata);
|
||||
Metadata getMetadata();
|
||||
UAVMetaObject *getMetaObject();
|
||||
virtual UAVDataObject *clone(quint32 instID = 0) = 0;
|
||||
virtual UAVDataObject *dirtyClone() = 0;
|
||||
|
||||
bool isSettingsObject();
|
||||
bool isDataObject();
|
||||
|
||||
private:
|
||||
UAVMetaObject *mobj;
|
||||
bool isSet;
|
||||
UAVMetaObject *m_metaObject;
|
||||
bool m_isSettings;
|
||||
};
|
||||
|
||||
#endif // UAVDATAOBJECT_H
|
||||
|
@ -107,3 +107,8 @@ UAVObject::Metadata UAVMetaObject::getData()
|
||||
|
||||
return parentMetadata;
|
||||
}
|
||||
|
||||
bool UAVMetaObject::isMetaDataObject()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
@ -43,6 +43,8 @@ public:
|
||||
void setData(const Metadata & mdata);
|
||||
Metadata getData();
|
||||
|
||||
bool isMetaDataObject();
|
||||
|
||||
private:
|
||||
UAVObject *parent;
|
||||
Metadata ownMetadata;
|
||||
|
@ -548,6 +548,21 @@ void UAVObject::emitNewInstance(UAVObject *obj)
|
||||
emit newInstance(obj);
|
||||
}
|
||||
|
||||
bool UAVObject::isSettingsObject()
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
bool UAVObject::isDataObject()
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
bool UAVObject::isMetaDataObject()
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize a UAVObjMetadata object.
|
||||
* \param[in] metadata The metadata object
|
||||
@ -686,3 +701,23 @@ void UAVObject::SetGcsTelemetryUpdateMode(UAVObject::Metadata & metadata, UAVObj
|
||||
{
|
||||
SET_BITS(metadata.flags, UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT, val, UAVOBJ_UPDATE_MODE_MASK);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the UAVObject metadata logging update mode
|
||||
* \param[in] metadata The metadata object
|
||||
* \return the logging update mode
|
||||
*/
|
||||
UAVObject::UpdateMode UAVObject::GetLoggingUpdateMode(const UAVObject::Metadata & metadata)
|
||||
{
|
||||
return UAVObject::UpdateMode((metadata.flags >> UAVOBJ_LOGGING_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the UAVObject metadata logging update mode member
|
||||
* \param[in] metadata The metadata object
|
||||
* \param[in] val The logging update mode
|
||||
*/
|
||||
void UAVObject::SetLoggingUpdateMode(UAVObject::Metadata & metadata, UAVObject::UpdateMode val)
|
||||
{
|
||||
SET_BITS(metadata.flags, UAVOBJ_LOGGING_UPDATE_MODE_SHIFT, val, UAVOBJ_UPDATE_MODE_MASK);
|
||||
}
|
||||
|
@ -55,6 +55,7 @@ class UAVOBJECTS_EXPORT UAVObject : public QObject {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
Q_PROPERTY(QString Name READ getName)
|
||||
|
||||
/**
|
||||
* Object update mode
|
||||
@ -132,6 +133,10 @@ public:
|
||||
void emitTransactionCompleted(bool success);
|
||||
void emitNewInstance(UAVObject *);
|
||||
|
||||
virtual bool isSettingsObject();
|
||||
virtual bool isDataObject();
|
||||
virtual bool isMetaDataObject();
|
||||
|
||||
// Metadata accessors
|
||||
static void MetadataInitialize(Metadata & meta);
|
||||
static AccessMode GetFlightAccess(const Metadata & meta);
|
||||
@ -146,6 +151,8 @@ public:
|
||||
static void SetFlightTelemetryUpdateMode(Metadata & meta, UpdateMode val);
|
||||
static UpdateMode GetGcsTelemetryUpdateMode(const Metadata & meta);
|
||||
static void SetGcsTelemetryUpdateMode(Metadata & meta, UpdateMode val);
|
||||
static UpdateMode GetLoggingUpdateMode(const Metadata & meta);
|
||||
static void SetLoggingUpdateMode(Metadata & meta, UpdateMode val);
|
||||
|
||||
public slots:
|
||||
void requestUpdate();
|
||||
|
@ -59,60 +59,79 @@ $(INSTANTIATIONCODE)
|
||||
|
||||
|
||||
fid = fopen(logfile);
|
||||
buffer=fread(fid,Inf,'uchar=>uchar');
|
||||
buffer=fread(fid,Inf,'uchar=>uint8');
|
||||
fseek(fid, 0, 'bof');
|
||||
|
||||
bufferIdx=1;
|
||||
bufferlen = size(buffer);
|
||||
|
||||
correctMsgByte=hex2dec('20');
|
||||
correctTimestampedByte=hex2dec('A0');
|
||||
correctSyncByte=hex2dec('3C');
|
||||
unknownObjIDList=zeros(1,2);
|
||||
|
||||
% Parse log file, entry by entry
|
||||
% prebuf = buffer(1:12);
|
||||
headerLen = 1 + 1 + 2 + 4 + 2; % sync type len id inst
|
||||
timestampLen = 4;
|
||||
crcLen = 1;
|
||||
oplHeaderLen = 8 + 4;
|
||||
|
||||
last_print = -1e10;
|
||||
|
||||
bufferIdx=1;
|
||||
headerIdx=oplHeaderLen + 1;
|
||||
|
||||
startTime=clock;
|
||||
|
||||
while (1)
|
||||
if (feof(fid)); break; end
|
||||
|
||||
try
|
||||
%% Read message header
|
||||
% get sync field (0x3C, 1 byte)
|
||||
sync = fread(fid, 1, 'uint8');
|
||||
if (bufferlen < headerIdx + 12); break; end
|
||||
sync = buffer(headerIdx);
|
||||
% printf('%x ', sync);
|
||||
headerIdx += 1;
|
||||
if sync ~= correctSyncByte
|
||||
prebuf = [prebuf(2:end); sync];
|
||||
wrongSyncByte = wrongSyncByte + 1;
|
||||
continue
|
||||
end
|
||||
|
||||
% get msg type (quint8 1 byte ) should be 0x20, ignore the rest?
|
||||
msgType = fread(fid, 1, 'uint8');
|
||||
if msgType ~= correctMsgByte && msgType ~= hex2dec('A0')
|
||||
wrongMessageByte = wrongMessageByte + 1;
|
||||
|
||||
% printf('\n %u:',headerIdx - 1);
|
||||
% get the opl timestamp and datablock size
|
||||
oplTimestamp = typecast(uint8(buffer(headerIdx - 1 - 8 - 4:headerIdx - 1 - 8 - 1)), 'uint32');
|
||||
oplSize = typecast(uint8(buffer(headerIdx - 1 - 8:headerIdx - 1 - 1)), 'uint64');
|
||||
|
||||
% get msg type (quint8 1 byte ) should be 0x20/0xA0, ignore the rest
|
||||
msgType = buffer(headerIdx);
|
||||
headerIdx += 1;
|
||||
if msgType ~= correctMsgByte && msgType ~= correctTimestampedByte
|
||||
% fixme: it should read the whole message payload instead of skipping and blindly searching for next sync byte.
|
||||
fprintf('\nSkipping message type: %x \n', msgType);
|
||||
continue
|
||||
end
|
||||
|
||||
% get msg size (quint16 2 bytes) excludes crc, include msg header and data payload
|
||||
msgSize = fread(fid, 1, 'uint16');
|
||||
msgSize = uint32(typecast(buffer(headerIdx:headerIdx + 1), 'uint16'));
|
||||
headerIdx += 2;
|
||||
|
||||
% get obj id (quint32 4 bytes)
|
||||
objID = fread(fid, 1, 'uint32');
|
||||
objID = typecast(uint8(buffer(headerIdx:headerIdx + 3)), 'uint32');
|
||||
headerIdx += 4;
|
||||
|
||||
% get instance id (quint16 2 bytes)
|
||||
instID = typecast(uint8(buffer(headerIdx:headerIdx + 1)), 'uint16');
|
||||
% printf('Id %x type %x size %u Inst %x ', objID, msgType, msgSize, instID);
|
||||
headerIdx += 2;
|
||||
|
||||
% get timestamp if needed (quint32 4 bytes)
|
||||
if msgType == correctMsgByte
|
||||
%% Process header if we are aligned
|
||||
timestamp = typecast(uint8(prebuf(1:4)), 'uint32');
|
||||
datasize = typecast(uint8(prebuf(5:12)), 'uint64');
|
||||
datasize = msgSize - headerLen;
|
||||
elseif msgType == correctTimestampedByte
|
||||
timestamp = fread(fid,1,'uint16');
|
||||
timestamp = typecast(uint8(buffer(headerIdx:headerIdx + 3)), 'uint32');
|
||||
% printf('ts %u');
|
||||
headerIdx += 4;
|
||||
datasize = msgSize - headerLen - timestampLen;
|
||||
end
|
||||
% printf('\n');
|
||||
bufferIdx = headerIdx;
|
||||
headerIdx += datasize + crcLen + oplHeaderLen;
|
||||
|
||||
if (isempty(objID)) %End of file
|
||||
break;
|
||||
end
|
||||
|
||||
%% Read object
|
||||
|
||||
switch objID
|
||||
@ -124,10 +143,8 @@ $(SWITCHCODE)
|
||||
else
|
||||
unknownObjIDList(unknownObjIDListIdx,2)=unknownObjIDList(unknownObjIDListIdx,2)+1;
|
||||
end
|
||||
|
||||
datasize = typecast(buffer(datasizeBufferIdx + 4:datasizeBufferIdx + 12-1), 'uint64');
|
||||
|
||||
msgBytesLeft = datasize - 1 - 1 - 2 - 4;
|
||||
msgBytesLeft = msgSize - 1 - 1 - 2 - 4;
|
||||
if msgBytesLeft > 255
|
||||
msgBytesLeft = 0;
|
||||
end
|
||||
|
@ -14,17 +14,14 @@ HEADERS += \
|
||||
uavdataobject.h \
|
||||
uavobjectfield.h \
|
||||
uavobjectsinit.h \
|
||||
uavobjectsplugin.h \
|
||||
uavobjecthelper.h
|
||||
|
||||
uavobjectsplugin.h
|
||||
SOURCES += \
|
||||
uavobject.cpp \
|
||||
uavmetaobject.cpp \
|
||||
uavobjectmanager.cpp \
|
||||
uavdataobject.cpp \
|
||||
uavobjectfield.cpp \
|
||||
uavobjectsplugin.cpp \
|
||||
uavobjecthelper.cpp
|
||||
uavobjectsplugin.cpp
|
||||
|
||||
OTHER_FILES += UAVObjects.pluginspec
|
||||
|
||||
|
@ -32,6 +32,9 @@ AbstractUAVObjectHelper::AbstractUAVObjectHelper(QObject *parent) :
|
||||
QObject(parent), m_transactionResult(false), m_transactionCompleted(false)
|
||||
{}
|
||||
|
||||
AbstractUAVObjectHelper::~AbstractUAVObjectHelper()
|
||||
{}
|
||||
|
||||
AbstractUAVObjectHelper::Result AbstractUAVObjectHelper::doObjectAndWait(UAVObject *object, int timeout)
|
||||
{
|
||||
// Lock, we can't call this twice from different threads
|
||||
@ -86,6 +89,9 @@ void AbstractUAVObjectHelper::transactionCompleted(UAVObject *object, bool succe
|
||||
UAVObjectUpdaterHelper::UAVObjectUpdaterHelper(QObject *parent) : AbstractUAVObjectHelper(parent)
|
||||
{}
|
||||
|
||||
UAVObjectUpdaterHelper::~UAVObjectUpdaterHelper()
|
||||
{}
|
||||
|
||||
void UAVObjectUpdaterHelper::doObjectAndWaitImpl()
|
||||
{
|
||||
m_object->updated();
|
||||
@ -94,6 +100,9 @@ void UAVObjectUpdaterHelper::doObjectAndWaitImpl()
|
||||
UAVObjectRequestHelper::UAVObjectRequestHelper(QObject *parent) : AbstractUAVObjectHelper(parent)
|
||||
{}
|
||||
|
||||
UAVObjectRequestHelper::~UAVObjectRequestHelper()
|
||||
{}
|
||||
|
||||
void UAVObjectRequestHelper::doObjectAndWaitImpl()
|
||||
{
|
||||
m_object->requestUpdate();
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user