mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into next
This commit is contained in:
commit
3b7b06aad0
6
Makefile
6
Makefile
@ -450,6 +450,7 @@ else
|
||||
GCS_SILENT := silent
|
||||
endif
|
||||
|
||||
.NOTPARALLEL:
|
||||
.PHONY: openpilotgcs
|
||||
openpilotgcs: uavobjects_gcs openpilotgcs_qmake openpilotgcs_make
|
||||
|
||||
@ -722,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
|
||||
@ -877,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,6 +41,7 @@
|
||||
#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"
|
||||
@ -59,7 +60,7 @@
|
||||
static xTaskHandle taskHandle;
|
||||
static bool airspeedEnabled = false;
|
||||
static AirspeedSettingsData airspeedSettings;
|
||||
|
||||
static AirspeedSettingsAirspeedSensorTypeOptions lastAirspeedSensorType = 0;
|
||||
static int8_t airspeedADCPin = -1;
|
||||
|
||||
|
||||
@ -118,6 +119,8 @@ int32_t AirspeedInitialize()
|
||||
}
|
||||
}
|
||||
|
||||
lastAirspeedSensorType = airspeedSettings.AirspeedSensorType;
|
||||
|
||||
AirspeedSensorInitialize();
|
||||
AirspeedSettingsInitialize();
|
||||
|
||||
@ -152,6 +155,21 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
|
||||
// Update the airspeed object
|
||||
AirspeedSensorGet(&airspeedData);
|
||||
|
||||
// if sensor type changed and the last sensor was
|
||||
// either Eagletree or PixHawk, reset Airspeed alarm
|
||||
if (airspeedSettings.AirspeedSensorType != lastAirspeedSensorType) {
|
||||
switch (lastAirspeedSensorType) {
|
||||
// Eagletree or PixHawk => Reset Airspeed alams
|
||||
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_EAGLETREEAIRSPEEDV3:
|
||||
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_PIXHAWKAIRSPEEDMS4525DO:
|
||||
AlarmsDefault(SYSTEMALARMS_ALARM_AIRSPEED);
|
||||
break;
|
||||
// else do not reset Airspeed alarm
|
||||
default: break;
|
||||
}
|
||||
lastAirspeedSensorType = airspeedSettings.AirspeedSensorType;
|
||||
}
|
||||
|
||||
switch (airspeedSettings.AirspeedSensorType) {
|
||||
#if defined(PIOS_INCLUDE_MPXV)
|
||||
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_DIYDRONESMPXV7002:
|
||||
@ -165,10 +183,17 @@ 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;
|
||||
}
|
||||
|
174
flight/modules/Airspeed/baro_airspeed_ms4525do.c
Normal file
174
flight/modules/Airspeed/baro_airspeed_ms4525do.c
Normal file
@ -0,0 +1,174 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @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 "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)
|
||||
|
||||
#define max(x, y) ((x) >= (y) ? (x) : (y))
|
||||
|
||||
// Private types
|
||||
|
||||
// Private functions definitions
|
||||
static int8_t baro_airspeedReadMS4525DO(AirspeedSensorData *airspeedSensor, AirspeedSettingsData *airspeedSettings);
|
||||
|
||||
|
||||
// Private variables
|
||||
static uint16_t calibrationCount = 0;
|
||||
static uint32_t filter_reg = 0; // Barry Dorr filter register
|
||||
|
||||
void baro_airspeedGetMS4525DO(AirspeedSensorData *airspeedSensor, AirspeedSettingsData *airspeedSettings)
|
||||
{
|
||||
// request measurement first
|
||||
int8_t retVal = PIOS_MS4525DO_Request();
|
||||
|
||||
if (retVal != 0) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_ERROR);
|
||||
return;
|
||||
}
|
||||
|
||||
// Datasheet of MS4525DO: conversion needs 0.5 ms + 20% more when status bit used
|
||||
// delay by one Tick or at least 2 ms
|
||||
const portTickType xDelay = max(2 / portTICK_RATE_MS, 1);
|
||||
vTaskDelay(xDelay);
|
||||
|
||||
// read the sensor
|
||||
retVal = baro_airspeedReadMS4525DO(airspeedSensor, airspeedSettings);
|
||||
|
||||
switch (retVal) {
|
||||
case 0: AlarmsClear(SYSTEMALARMS_ALARM_AIRSPEED);
|
||||
break;
|
||||
case -4:
|
||||
case -5:
|
||||
case -7: AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_WARNING);
|
||||
break;
|
||||
case -1:
|
||||
case -2:
|
||||
case -3:
|
||||
case -6:
|
||||
default: AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_ERROR);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Private functions
|
||||
static int8_t baro_airspeedReadMS4525DO(AirspeedSensorData *airspeedSensor, AirspeedSettingsData *airspeedSettings)
|
||||
{
|
||||
// Check to see if airspeed sensor is returning airspeedSensor
|
||||
uint16_t values[2];
|
||||
int8_t retVal = PIOS_MS4525DO_Read(values);
|
||||
|
||||
if (retVal == 0) {
|
||||
airspeedSensor->SensorValue = values[0];
|
||||
airspeedSensor->SensorValueTemperature = values[1];
|
||||
} else {
|
||||
airspeedSensor->SensorValue = -1;
|
||||
airspeedSensor->SensorValueTemperature = -1;
|
||||
airspeedSensor->SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
|
||||
airspeedSensor->CalibratedAirspeed = 0;
|
||||
return retVal;
|
||||
}
|
||||
|
||||
// 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);
|
||||
return -7;
|
||||
} 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;
|
||||
}
|
||||
return -7;
|
||||
}
|
||||
}
|
||||
|
||||
/* 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;
|
||||
|
||||
return retVal;
|
||||
}
|
||||
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_MS4525DO) */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
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
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -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);
|
||||
}
|
||||
}
|
||||
@ -1078,7 +1078,8 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode)
|
||||
AirspeedStateGet(&airspeed);
|
||||
|
||||
airspeed.CalibratedAirspeed = airspeedData.CalibratedAirspeed;
|
||||
airspeed.TrueAirspeed = airspeed.CalibratedAirspeed * IAS2TAS(homeLocation.Altitude - Nav.Pos[2]);
|
||||
airspeed.TrueAirspeed = (airspeedSensor.TrueAirspeed < 0.f) ? airspeed.CalibratedAirspeed *IAS2TAS(homeLocation.Altitude - positionState.Down) : airspeedSensor.TrueAirspeed;
|
||||
|
||||
AirspeedStateSet(&airspeed);
|
||||
|
||||
if (!gps_vel_updated && !gps_updated) {
|
||||
|
@ -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
|
||||
|
@ -63,8 +63,6 @@
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static uint32_t idleCounter;
|
||||
static uint32_t idleCounterClear;
|
||||
static xTaskHandle systemTaskHandle;
|
||||
static bool stackOverflow;
|
||||
static bool mallocFailed;
|
||||
@ -130,8 +128,6 @@ static void systemTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
|
||||
// Initialize vars
|
||||
idleCounter = 0;
|
||||
idleCounterClear = 0;
|
||||
lastSysTime = xTaskGetTickCount();
|
||||
|
||||
// Main system loop
|
||||
@ -205,15 +201,7 @@ static void systemTask(__attribute__((unused)) void *parameters)
|
||||
* Called by the RTOS when the CPU is idle, used to measure the CPU idle time.
|
||||
*/
|
||||
void vApplicationIdleHook(void)
|
||||
{
|
||||
// Called when the scheduler has no tasks to run
|
||||
if (idleCounterClear == 0) {
|
||||
++idleCounter;
|
||||
} else {
|
||||
idleCounter = 0;
|
||||
idleCounterClear = 0;
|
||||
}
|
||||
}
|
||||
{}
|
||||
|
||||
/**
|
||||
* Called by the RTOS when a stack overflow is detected.
|
||||
|
@ -290,20 +290,20 @@ 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;
|
||||
@ -312,7 +312,6 @@ static void updateRadioComBridgeStats()
|
||||
|
||||
radioComBridgeStats.RadioTxBytes += radioUAVTalkStats.txBytes;
|
||||
radioComBridgeStats.RadioTxFailures += radioUAVTalkStats.txErrors;
|
||||
radioComBridgeStats.RadioTxRetries += data->radioTxRetries;
|
||||
|
||||
radioComBridgeStats.RadioRxBytes += radioUAVTalkStats.rxBytes;
|
||||
radioComBridgeStats.RadioRxFailures += radioUAVTalkStats.rxErrors;
|
||||
@ -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;
|
||||
|
@ -82,14 +82,9 @@
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3) // FLIGHT CONTROL priority
|
||||
#define FAILSAFE_TIMEOUT_MS 30
|
||||
|
||||
// number of flight mode switch positions
|
||||
#define NUM_FMS_POSITIONS 6
|
||||
|
||||
// The PID_RATE_ROLL set is used by Rate mode and the rate portion of Attitude mode
|
||||
// The PID_RATE set is used by the attitude portion of Attitude mode
|
||||
// The PID_RATEA_ROLL set is used by Rattitude mode because it needs to maintain
|
||||
// - two independant rate PIDs because it does rate and attitude simultaneously
|
||||
enum { PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_RATEA_ROLL, PID_RATEA_PITCH, PID_RATEA_YAW, PID_MAX };
|
||||
enum { PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_MAX };
|
||||
enum { RATE_P, RATE_I, RATE_D, RATE_LIMIT, RATE_OFFSET };
|
||||
enum { ATT_P, ATT_I, ATT_LIMIT, ATT_OFFSET };
|
||||
|
||||
@ -109,7 +104,7 @@ struct pid pids[PID_MAX];
|
||||
|
||||
int cur_flight_mode = -1;
|
||||
|
||||
static uint8_t rattitude_anti_windup;
|
||||
static float rattitude_mode_transition_stick_position;
|
||||
static float cruise_control_min_thrust;
|
||||
static float cruise_control_max_thrust;
|
||||
static uint8_t cruise_control_max_angle;
|
||||
@ -117,7 +112,7 @@ static float cruise_control_max_power_factor;
|
||||
static float cruise_control_power_trim;
|
||||
static int8_t cruise_control_inverted_power_switch;
|
||||
static float cruise_control_neutral_thrust;
|
||||
static uint8_t cruise_control_flight_mode_switch_pos_enable[NUM_FMS_POSITIONS];
|
||||
static uint8_t cruise_control_flight_mode_switch_pos_enable[FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM];
|
||||
|
||||
// Private functions
|
||||
static void stabilizationTask(void *parameters);
|
||||
@ -127,9 +122,6 @@ static void SettingsUpdatedCb(UAVObjEvent *ev);
|
||||
static void BankUpdatedCb(UAVObjEvent *ev);
|
||||
static void SettingsBankUpdatedCb(UAVObjEvent *ev);
|
||||
|
||||
static float stab_log2f(float x);
|
||||
static float stab_powf(float x, uint8_t p);
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
@ -167,9 +159,6 @@ int32_t StabilizationStart()
|
||||
*/
|
||||
int32_t StabilizationInitialize()
|
||||
{
|
||||
// stop the compile if the number of switch positions changes, but has not been changed here
|
||||
PIOS_STATIC_ASSERT(NUM_FMS_POSITIONS == sizeof(((FlightModeSettingsData *)0)->FlightModePosition) / sizeof((((FlightModeSettingsData *)0)->FlightModePosition)[0]));
|
||||
|
||||
// Initialize variables
|
||||
ManualControlCommandInitialize();
|
||||
ManualControlSettingsInitialize();
|
||||
@ -388,7 +377,6 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
if (reinit) {
|
||||
pids[PID_ROLL + i].iAccumulator = 0;
|
||||
pids[PID_RATE_ROLL + i].iAccumulator = 0;
|
||||
pids[PID_RATEA_ROLL + i].iAccumulator = 0;
|
||||
}
|
||||
|
||||
// Compute what Rate mode would give for this stick angle's rate
|
||||
@ -411,8 +399,8 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
float rateDesiredAxisAttitude;
|
||||
rateDesiredAxisAttitude = pid_apply(&pids[PID_ROLL + i], attitude_error, dT);
|
||||
rateDesiredAxisAttitude = bound(rateDesiredAxisAttitude,
|
||||
cast_struct_to_array(stabBank.MaximumRate,
|
||||
stabBank.MaximumRate.Roll)[i]);
|
||||
cast_struct_to_array(stabBank.ManualRate,
|
||||
stabBank.ManualRate.Roll)[i]);
|
||||
|
||||
// Compute the weighted average rate desired
|
||||
// Using max() rather than sqrt() for cpu speed;
|
||||
@ -422,81 +410,54 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
// magnitude = sqrt(stabDesired.Roll*stabDesired.Roll + stabDesired.Pitch*stabDesired.Pitch);
|
||||
float magnitude;
|
||||
magnitude = fmaxf(fabsf(stabDesired.Roll), fabsf(stabDesired.Pitch));
|
||||
|
||||
// modify magnitude to move the Att to Rate transition to the place
|
||||
// specified by the user
|
||||
// we are looking for where the stick angle == transition angle
|
||||
// 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]
|
||||
// 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
|
||||
// I tested 14.01 and came up with .61 without even remembering this number
|
||||
// I thought that moving the P,I, and maxangle terms around would change this value
|
||||
// and that I would have to take these into account, but varying
|
||||
// all P's and I's by factors of 1/2 to 2 didn't change it noticeably
|
||||
// and varying maxangle from 4 to 120 didn't either.
|
||||
// so for now I'm not taking these into account
|
||||
// while working with this, it occurred to me that Attitude mode,
|
||||
// set up with maxangle=190 would be similar to Ratt, and it is.
|
||||
#define STICK_VALUE_AT_MODE_TRANSITION 0.618033989f
|
||||
|
||||
// the following assumes the transition would otherwise be at 0.618033989f
|
||||
// and THAT assumes that Att ramps up to max roll rate
|
||||
// when a small number of degrees off of where it should be
|
||||
|
||||
// if below the transition angle (still in attitude mode)
|
||||
// '<=' instead of '<' keeps rattitude_mode_transition_stick_position==1.0 from causing DZ
|
||||
if (magnitude <= rattitude_mode_transition_stick_position) {
|
||||
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 - rattitude_mode_transition_stick_position)
|
||||
+ STICK_VALUE_AT_MODE_TRANSITION;
|
||||
}
|
||||
rateDesiredAxis[i] = (1.0f - magnitude) * rateDesiredAxisAttitude
|
||||
+ magnitude * rateDesiredAxisRate;
|
||||
|
||||
// Compute the inner loop for both Rate mode and Attitude mode
|
||||
// actuatorDesiredAxis[i] is the weighted average of the two PIDs from the two rates
|
||||
actuatorDesiredAxis[i] =
|
||||
(1.0f - magnitude) * pid_apply_setpoint(&pids[PID_RATEA_ROLL + i], speedScaleFactor, rateDesiredAxis[i], gyro_filtered[i], dT)
|
||||
+ magnitude * pid_apply_setpoint(&pids[PID_RATE_ROLL + i], speedScaleFactor, rateDesiredAxis[i], gyro_filtered[i], dT);
|
||||
// Compute the inner loop for the averaged rate
|
||||
// actuatorDesiredAxis[i] is the weighted average
|
||||
actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], speedScaleFactor,
|
||||
rateDesiredAxis[i], gyro_filtered[i], dT);
|
||||
actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i], 1.0f);
|
||||
|
||||
// settings.RattitudeAntiWindup controls the iAccumulator zeroing
|
||||
// - so both iAccs don't wind up too far;
|
||||
// - nor do both iAccs get held too close to zero at mid stick
|
||||
|
||||
// I suspect that there would be windup without it
|
||||
// - since rate and attitude fight each other here
|
||||
// - rate trying to pull it over the top and attitude trying to pull it back down
|
||||
|
||||
// Wind-up increases linearly with cycles for a fixed error.
|
||||
// We must never increase the iAcc or we risk oscillation.
|
||||
|
||||
// Use the powf() function to make two anti-windup curves
|
||||
// - one for zeroing rate close to center stick
|
||||
// - the other for zeroing attitude close to max stick
|
||||
|
||||
// the bigger the dT the more anti windup needed
|
||||
// the bigger the PID[].i the more anti windup needed
|
||||
// more anti windup is achieved with a lower powf() power
|
||||
// a doubling of e.g. PID[].i should cause the runtime anti windup factor
|
||||
// to get twice as far away from 1.0 (towards zero)
|
||||
// e.g. from .90 to .80
|
||||
|
||||
// magic numbers
|
||||
// these generate the inverted parabola like curves that go through [0,1] and [1,0]
|
||||
// the higher the power, the closer the curve is to a straight line
|
||||
// from [0,1] to [1,1] to [1,0] and the less anti windup is applied
|
||||
|
||||
// the UAVO RattitudeAntiWindup varies from 0 to 31
|
||||
// 0 turns off anti windup
|
||||
// 1 gives very little anti-windup because the power given to powf() is 31
|
||||
// 31 gives a lot of anti-windup because the power given to powf() is 1
|
||||
// the 32.1 is what does this
|
||||
// the 7.966 and 17.668 cancel the default PID value and dT given to log2f()
|
||||
// if these are non-default, tweaking is thus done so the user doesn't have to readjust
|
||||
// the default value of 10 for UAVO RattitudeAntiWindup gives a power of 22
|
||||
// these calculations are for magnitude = 0.5, so 22 corresponds to the number of bits
|
||||
// used in the mantissa of the float
|
||||
// i.e. 1.0-(0.5^22) almost underflows
|
||||
|
||||
// This may only be useful for aircraft with large Ki values and limits
|
||||
if (dT > 0.0f && rattitude_anti_windup > 0.0f) {
|
||||
float factor;
|
||||
|
||||
// At magnitudes close to one, the Attitude accumulators gets zeroed
|
||||
if (pids[PID_ROLL + i].i > 0.0f) {
|
||||
factor = 1.0f - stab_powf(magnitude, ((uint8_t)(32.1f - 7.966f - stab_log2f(dT * pids[PID_ROLL + i].i))) - rattitude_anti_windup);
|
||||
pids[PID_ROLL + i].iAccumulator *= factor;
|
||||
}
|
||||
if (pids[PID_RATEA_ROLL + i].i > 0.0f) {
|
||||
factor = 1.0f - stab_powf(magnitude, ((uint8_t)(32.1f - 17.668f - stab_log2f(dT * pids[PID_RATEA_ROLL + i].i))) - rattitude_anti_windup);
|
||||
pids[PID_RATEA_ROLL + i].iAccumulator *= factor;
|
||||
}
|
||||
|
||||
// At magnitudes close to zero, the Rate accumulator gets zeroed
|
||||
if (pids[PID_RATE_ROLL + i].i > 0.0f) {
|
||||
factor = 1.0f - stab_powf(1.0f - magnitude, ((uint8_t)(32.1f - 17.668f - stab_log2f(dT * pids[PID_RATE_ROLL + i].i))) - rattitude_anti_windup);
|
||||
pids[PID_RATE_ROLL + i].iAccumulator *= factor;
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR:
|
||||
|
||||
// Store for debugging output
|
||||
rateDesiredAxis[i] = stabDesiredAxis[i];
|
||||
|
||||
@ -604,7 +565,7 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
// to maintain same altitdue with changing bank angle
|
||||
// but without manually adjusting thrust
|
||||
// do it here and all the various flight modes (e.g. Altitude Hold) can use it
|
||||
if (flight_mode_switch_position < NUM_FMS_POSITIONS
|
||||
if (flight_mode_switch_position < FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM
|
||||
&& cruise_control_flight_mode_switch_pos_enable[flight_mode_switch_position] != (uint8_t)0
|
||||
&& cruise_control_max_power_factor > 0.0001f) {
|
||||
static uint8_t toggle;
|
||||
@ -715,44 +676,9 @@ static float bound(float val, float range)
|
||||
}
|
||||
|
||||
|
||||
// x small (0.0 < x < .01) so interpolation of fractional part is reasonable
|
||||
static float stab_log2f(float x)
|
||||
{
|
||||
union {
|
||||
volatile float f;
|
||||
volatile uint32_t i;
|
||||
volatile unsigned char c[4];
|
||||
} __attribute__((packed)) u1, u2;
|
||||
|
||||
u2.f = u1.f = x;
|
||||
u1.i <<= 1;
|
||||
u2.i &= 0xff800000;
|
||||
|
||||
// get and unbias the exponent, add in a linear interpolation of the fractional part
|
||||
return (float)(u1.c[3] - 127) + (x / u2.f) - 1.0f;
|
||||
}
|
||||
|
||||
|
||||
// 0<=x<=1, 0<=p<=31
|
||||
static float stab_powf(float x, uint8_t p)
|
||||
{
|
||||
float retval = 1.0f;
|
||||
|
||||
while (p) {
|
||||
if (p & 1) {
|
||||
retval *= x;
|
||||
}
|
||||
x *= x;
|
||||
p >>= 1;
|
||||
}
|
||||
|
||||
return retval;
|
||||
}
|
||||
|
||||
|
||||
static void SettingsBankUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
if (cur_flight_mode < 0 || cur_flight_mode >= NUM_FMS_POSITIONS) {
|
||||
if (cur_flight_mode < 0 || cur_flight_mode >= FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM) {
|
||||
return;
|
||||
}
|
||||
if ((ev) && ((settings.FlightModeMap[cur_flight_mode] == 0 && ev->obj != StabilizationSettingsBank1Handle()) ||
|
||||
@ -858,27 +784,6 @@ static void BankUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
bank.YawPI.Ki,
|
||||
0,
|
||||
bank.YawPI.ILimit);
|
||||
|
||||
// Set the Rattitude roll rate PID constants
|
||||
pid_configure(&pids[PID_RATEA_ROLL],
|
||||
bank.RollRatePID.Kp,
|
||||
bank.RollRatePID.Ki,
|
||||
bank.RollRatePID.Kd,
|
||||
bank.RollRatePID.ILimit);
|
||||
|
||||
// Set the Rattitude pitch rate PID constants
|
||||
pid_configure(&pids[PID_RATEA_PITCH],
|
||||
bank.PitchRatePID.Kp,
|
||||
bank.PitchRatePID.Ki,
|
||||
bank.PitchRatePID.Kd,
|
||||
bank.PitchRatePID.ILimit);
|
||||
|
||||
// Set the Rattitude yaw rate PID constants
|
||||
pid_configure(&pids[PID_RATEA_YAW],
|
||||
bank.YawRatePID.Kp,
|
||||
bank.YawRatePID.Ki,
|
||||
bank.YawRatePID.Kd,
|
||||
bank.YawRatePID.ILimit);
|
||||
}
|
||||
|
||||
|
||||
@ -918,8 +823,12 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
// force flight mode update
|
||||
cur_flight_mode = -1;
|
||||
|
||||
// Rattitude flight mode anti-windup factor
|
||||
rattitude_anti_windup = settings.RattitudeAntiWindup;
|
||||
// Rattitude stick angle where the attitude to rate transition happens
|
||||
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;
|
||||
}
|
||||
|
||||
cruise_control_min_thrust = (float)settings.CruiseControlMinThrust / 100.0f;
|
||||
cruise_control_max_thrust = (float)settings.CruiseControlMaxThrust / 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);
|
||||
}
|
||||
|
||||
|
@ -40,6 +40,7 @@
|
||||
#include <airspeedsensor.h>
|
||||
#include <gpspositionsensor.h>
|
||||
#include <gpsvelocitysensor.h>
|
||||
#include <homelocation.h>
|
||||
|
||||
#include <gyrostate.h>
|
||||
#include <accelstate.h>
|
||||
@ -60,6 +61,10 @@
|
||||
#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) \
|
||||
if (IS_SET(states.updated, SENSORUPDATES_##shortname)) { \
|
||||
@ -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,7 +139,7 @@ static DelayedCallbackInfo *stateEstimationCallback;
|
||||
|
||||
static volatile RevoSettingsData revoSettings;
|
||||
static volatile sensorUpdates updatedSensors;
|
||||
static int32_t fusionAlgorithm = -1;
|
||||
static volatile int32_t fusionAlgorithm = -1;
|
||||
static filterPipeline *filterChain = NULL;
|
||||
|
||||
// different filters available to state estimation
|
||||
@ -213,6 +233,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 +259,8 @@ int32_t StateEstimationInitialize(void)
|
||||
GPSVelocitySensorInitialize();
|
||||
GPSPositionSensorInitialize();
|
||||
|
||||
HomeLocationInitialize();
|
||||
|
||||
GyroStateInitialize();
|
||||
AccelStateInitialize();
|
||||
MagStateInitialize();
|
||||
@ -247,6 +270,8 @@ int32_t StateEstimationInitialize(void)
|
||||
|
||||
RevoSettingsConnectCallback(&settingsUpdatedCb);
|
||||
|
||||
HomeLocationConnectCallback(&homeLocationUpdatedCb);
|
||||
|
||||
GyroSensorConnectCallback(&sensorUpdatedCb);
|
||||
AccelSensorConnectCallback(&sensorUpdatedCb);
|
||||
MagSensorConnectCallback(&sensorUpdatedCb);
|
||||
@ -329,7 +354,7 @@ 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:
|
||||
@ -379,8 +404,8 @@ 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
|
||||
@ -477,6 +502,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
|
||||
|
@ -92,8 +92,6 @@
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static uint32_t idleCounter;
|
||||
static uint32_t idleCounterClear;
|
||||
static xTaskHandle systemTaskHandle;
|
||||
static xQueueHandle objectPersistenceQueue;
|
||||
static enum { STACKOVERFLOW_NONE = 0, STACKOVERFLOW_WARNING = 1, STACKOVERFLOW_CRITICAL = 3 } stackOverflow;
|
||||
@ -132,6 +130,7 @@ int32_t SystemModStart(void)
|
||||
// Register task
|
||||
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_SYSTEM, systemTaskHandle);
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -186,15 +185,12 @@ static void systemTask(__attribute__((unused)) void *parameters)
|
||||
*/
|
||||
PIOS_SYS_Reset();
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_IAP)
|
||||
/* Record a successful boot */
|
||||
PIOS_IAP_WriteBootCount(0);
|
||||
#endif
|
||||
|
||||
// Initialize vars
|
||||
idleCounter = 0;
|
||||
idleCounterClear = 0;
|
||||
|
||||
// Listen for SettingPersistance object updates, connect a callback function
|
||||
ObjectPersistenceConnectQueue(objectPersistenceQueue);
|
||||
@ -212,9 +208,10 @@ static void systemTask(__attribute__((unused)) void *parameters)
|
||||
// Main system loop
|
||||
while (1) {
|
||||
// Update the system statistics
|
||||
updateStats();
|
||||
cycleCount = cycleCount > 0 ? cycleCount - 1 : 7;
|
||||
|
||||
cycleCount = cycleCount > 0 ? cycleCount - 1 : 7;
|
||||
// if(cycleCount == 1){
|
||||
updateStats();
|
||||
// Update the system alarms
|
||||
updateSystemAlarms();
|
||||
#ifdef DIAG_I2C_WDG_STATS
|
||||
@ -227,10 +224,12 @@ static void systemTask(__attribute__((unused)) void *parameters)
|
||||
PIOS_TASK_MONITOR_ForEachTask(taskMonitorForEachCallback, &taskInfoData);
|
||||
TaskInfoSet(&taskInfoData);
|
||||
// Update the callback status object
|
||||
// if(FALSE){
|
||||
PIOS_CALLBACKSCHEDULER_ForEachCallback(callbackSchedulerForEachCallback, &callbackInfoData);
|
||||
CallbackInfoSet(&callbackInfoData);
|
||||
// }
|
||||
#endif
|
||||
|
||||
// }
|
||||
// Flash the heartbeat LED
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
uint8_t armingStatus;
|
||||
@ -541,7 +540,6 @@ static uint16_t GetFreeIrqStackSize(void)
|
||||
*/
|
||||
static void updateStats()
|
||||
{
|
||||
static portTickType lastTickCount = 0;
|
||||
SystemStatsData stats;
|
||||
|
||||
// Get stats and update
|
||||
@ -559,10 +557,6 @@ static void updateStats()
|
||||
// Get Irq stack status
|
||||
stats.IRQStackRemaining = GetFreeIrqStackSize();
|
||||
|
||||
// When idleCounterClear was not reset by the idle-task, it means the idle-task did not run
|
||||
if (idleCounterClear) {
|
||||
idleCounter = 0;
|
||||
}
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32)
|
||||
if (pios_uavo_settings_fs_id) {
|
||||
PIOS_FLASHFS_GetStats(pios_uavo_settings_fs_id, &fsStats);
|
||||
@ -575,13 +569,8 @@ static void updateStats()
|
||||
stats.UsrSlotsActive = fsStats.num_active_slots;
|
||||
}
|
||||
#endif
|
||||
portTickType now = xTaskGetTickCount();
|
||||
if (now > lastTickCount) {
|
||||
uint32_t dT = (xTaskGetTickCount() - lastTickCount) * portTICK_RATE_MS; // in ms
|
||||
stats.CPULoad = 100 - (uint8_t)roundf(100.0f * ((float)idleCounter / ((float)dT / 1000.0f)) / (float)IDLE_COUNTS_PER_SEC_AT_NO_LOAD);
|
||||
} // else: TickCount has wrapped, do not calc now
|
||||
lastTickCount = now;
|
||||
idleCounterClear = 1;
|
||||
stats.CPULoad = 100 - PIOS_TASK_MONITOR_GetIdlePercentage();
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC) && defined(PIOS_ADC_USE_TEMP_SENSOR)
|
||||
float temp_voltage = PIOS_ADC_PinGetVolt(PIOS_ADC_TEMPERATURE_PIN);
|
||||
stats.CPUTemp = PIOS_CONVERT_VOLT_TO_CPU_TEMP(temp_voltage);;
|
||||
@ -663,15 +652,7 @@ static void updateSystemAlarms()
|
||||
* Called by the RTOS when the CPU is idle, used to measure the CPU idle time.
|
||||
*/
|
||||
void vApplicationIdleHook(void)
|
||||
{
|
||||
// Called when the scheduler has no tasks to run
|
||||
if (idleCounterClear == 0) {
|
||||
++idleCounter;
|
||||
} else {
|
||||
idleCounter = 0;
|
||||
idleCounterClear = 0;
|
||||
}
|
||||
}
|
||||
{}
|
||||
|
||||
/**
|
||||
* Called by the RTOS when a stack overflow is detected.
|
||||
|
@ -54,6 +54,9 @@
|
||||
|
||||
// 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 +83,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);
|
||||
@ -140,13 +144,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 +382,28 @@ 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 +442,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 +458,23 @@ 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 +579,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 +711,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:
|
||||
|
126
flight/pios/common/pios_ms4525do.c
Normal file
126
flight/pios/common/pios_ms4525do.c
Normal file
@ -0,0 +1,126 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @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);
|
||||
static int8_t PIOS_MS4525DO_WriteI2C(uint8_t *buffer, uint8_t len);
|
||||
|
||||
static bool pios_ms4525do_requested = false;
|
||||
|
||||
|
||||
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));
|
||||
}
|
||||
|
||||
|
||||
static int8_t PIOS_MS4525DO_WriteI2C(uint8_t *buffer, uint8_t len)
|
||||
{
|
||||
const struct pios_i2c_txn txn_list[] = {
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = MS4525DO_I2C_ADDR,
|
||||
.rw = PIOS_I2C_TXN_WRITE,
|
||||
.len = len,
|
||||
.buf = buffer,
|
||||
}
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(PIOS_I2C_MS4525DO_ADAPTER, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
|
||||
int8_t PIOS_MS4525DO_Request(void)
|
||||
{
|
||||
// MS4525DO expects a zero length write.
|
||||
// Sending one byte is a workaround that works for the moment
|
||||
uint8_t data = 0;
|
||||
int8_t retVal = PIOS_MS4525DO_WriteI2C(&data, sizeof(data));
|
||||
|
||||
/* requested only when transfer worked */
|
||||
pios_ms4525do_requested = (retVal == 0);
|
||||
|
||||
return retVal;
|
||||
}
|
||||
|
||||
|
||||
// values has to ba an arrray with two elements
|
||||
// values stay untouched on error
|
||||
int8_t PIOS_MS4525DO_Read(uint16_t *values)
|
||||
{
|
||||
if (!pios_ms4525do_requested) {
|
||||
/* Do not try to read when not requested */
|
||||
/* else probably stale data will be obtained */
|
||||
return -4;
|
||||
}
|
||||
|
||||
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);
|
||||
|
||||
/* not requested anymore, only when transfer worked */
|
||||
pios_ms4525do_requested = !(retVal == 0);
|
||||
|
||||
return retVal;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_MS4525DO */
|
@ -33,6 +33,7 @@
|
||||
static xSemaphoreHandle mLock;
|
||||
static xTaskHandle *mTaskHandles;
|
||||
static uint32_t mLastMonitorTime;
|
||||
static uint32_t mLastIdleMonitorTime;
|
||||
static uint16_t mMaxTasks;
|
||||
|
||||
/**
|
||||
@ -54,8 +55,10 @@ int32_t PIOS_TASK_MONITOR_Initialize(uint16_t max_tasks)
|
||||
mMaxTasks = max_tasks;
|
||||
#if (configGENERATE_RUN_TIME_STATS == 1)
|
||||
mLastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE();
|
||||
mLastIdleMonitorTime = portGET_RUN_TIME_COUNTER_VALUE();
|
||||
#else
|
||||
mLastMonitorTime = 0;
|
||||
mLastIdleMonitorTime = 0;
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
@ -146,4 +149,31 @@ void PIOS_TASK_MONITOR_ForEachTask(TaskMonitorTaskInfoCallback callback, void *c
|
||||
xSemaphoreGiveRecursive(mLock);
|
||||
}
|
||||
|
||||
uint8_t PIOS_TASK_MONITOR_GetIdlePercentage()
|
||||
{
|
||||
#if defined(ARCH_POSIX) || defined(ARCH_WIN32)
|
||||
return 50;
|
||||
|
||||
#elif (configGENERATE_RUN_TIME_STATS == 1)
|
||||
xSemaphoreTakeRecursive(mLock, portMAX_DELAY);
|
||||
|
||||
uint32_t currentTime = portGET_RUN_TIME_COUNTER_VALUE();
|
||||
|
||||
/* avoid divide-by-zero if the interval is too small */
|
||||
uint32_t deltaTime = ((currentTime - mLastIdleMonitorTime) / 100) ? : 1;
|
||||
mLastIdleMonitorTime = currentTime;
|
||||
uint8_t running_time_percentage = 0;
|
||||
|
||||
/* Generate idle time percentage stats */
|
||||
running_time_percentage = uxTaskGetRunTime(xTaskGetIdleTaskHandle()) / deltaTime;
|
||||
xSemaphoreGiveRecursive(mLock);
|
||||
return running_time_percentage;
|
||||
|
||||
#else
|
||||
return 0;
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#endif // PIOS_INCLUDE_TASK_MONITOR
|
||||
|
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 */
|
@ -104,4 +104,9 @@ typedef void (*TaskMonitorTaskInfoCallback)(uint16_t task_id, const struct pios_
|
||||
*/
|
||||
extern void PIOS_TASK_MONITOR_ForEachTask(TaskMonitorTaskInfoCallback callback, void *context);
|
||||
|
||||
/**
|
||||
* Return the idle task running time percentage.
|
||||
*/
|
||||
extern uint8_t PIOS_TASK_MONITOR_GetIdlePercentage();
|
||||
|
||||
#endif // PIOS_TASK_MONITOR_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>
|
||||
|
@ -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);
|
||||
|
||||
// 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) {
|
||||
|
@ -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);
|
||||
|
||||
// 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) {
|
||||
|
@ -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);
|
||||
|
@ -75,11 +75,9 @@
|
||||
#endif
|
||||
|
||||
/* Enable run time stats collection */
|
||||
#ifdef DIAG_TASKS
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
|
||||
#define configGENERATE_RUN_TIME_STATS 1
|
||||
#define INCLUDE_uxTaskGetRunTime 1
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 1
|
||||
#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \
|
||||
do { \
|
||||
(*(unsigned long *)0xe000edfc) |= (1 << 24); /* DEMCR |= DEMCR_TRCENA */ \
|
||||
@ -87,6 +85,9 @@
|
||||
} \
|
||||
while (0)
|
||||
#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004) /* DWT_CYCCNT */
|
||||
|
||||
#ifdef DIAG_TASKS
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
#else
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 1
|
||||
#endif
|
||||
|
@ -75,11 +75,9 @@
|
||||
#endif
|
||||
|
||||
/* Enable run time stats collection */
|
||||
#ifdef DIAG_TASKS
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
|
||||
#define configGENERATE_RUN_TIME_STATS 1
|
||||
#define INCLUDE_uxTaskGetRunTime 1
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 1
|
||||
#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \
|
||||
do { \
|
||||
(*(unsigned long *)0xe000edfc) |= (1 << 24); /* DEMCR |= DEMCR_TRCENA */ \
|
||||
@ -87,6 +85,9 @@
|
||||
} \
|
||||
while (0)
|
||||
#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004) /* DWT_CYCCNT */
|
||||
|
||||
#ifdef DIAG_TASKS
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
#else
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 1
|
||||
#endif
|
||||
|
@ -79,6 +79,7 @@
|
||||
/* Enable run time stats collection */
|
||||
#define configGENERATE_RUN_TIME_STATS 1
|
||||
#define INCLUDE_uxTaskGetRunTime 1
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 1
|
||||
|
||||
/*
|
||||
* Once we move to CMSIS2 we can at least use:
|
||||
|
@ -64,6 +64,7 @@
|
||||
#define INCLUDE_xTaskGetSchedulerState 1
|
||||
#define INCLUDE_xTaskGetCurrentTaskHandle 1
|
||||
#define INCLUDE_uxTaskGetStackHighWaterMark 1
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 1
|
||||
|
||||
/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255
|
||||
(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */
|
||||
|
@ -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 */
|
||||
|
@ -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;
|
||||
@ -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.
|
||||
|
@ -125,6 +125,7 @@ extern uint32_t 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_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)
|
||||
|
@ -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) )
|
||||
|
@ -79,6 +79,7 @@
|
||||
/* Enable run time stats collection */
|
||||
#define configGENERATE_RUN_TIME_STATS 1
|
||||
#define INCLUDE_uxTaskGetRunTime 1
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 1
|
||||
|
||||
/*
|
||||
* Once we move to CMSIS2 we can at least use:
|
||||
|
@ -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,6 +87,8 @@ $(INITFIELDS)
|
||||
UAVObjSetInstanceData(obj, instId, &data);
|
||||
|
||||
// Initialize object metadata to their default values
|
||||
if ( instId == 0 ) {
|
||||
UAVObjMetadata metadata;
|
||||
metadata.flags =
|
||||
$(FLIGHTACCESS) << UAVOBJ_ACCESS_SHIFT |
|
||||
$(GCSACCESS) << UAVOBJ_GCS_ACCESS_SHIFT |
|
||||
@ -101,6 +102,7 @@ $(INITFIELDS)
|
||||
metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD);
|
||||
UAVObjSetMetadata(obj, &metadata);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get object handle
|
||||
|
@ -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 \
|
||||
|
@ -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
|
||||
|
@ -21,8 +21,11 @@
|
||||
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 \
|
||||
!mac:LIBS += -lSDL
|
||||
|
||||
SOURCES += \
|
||||
sdlgamepad.cpp
|
||||
|
||||
HEADERS += \
|
||||
sdlgamepad.h \
|
||||
sdlgamepad_global.h
|
||||
|
||||
macx:LIBS += -framework OpenGL -framework SDL -framework Cocoa
|
||||
!macx:LIBS += -lSDL
|
||||
|
||||
OTHER_FILES += COPYING \
|
||||
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>
|
||||
|
@ -82,6 +82,9 @@ 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
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_telemetry->gpsProtocol);
|
||||
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_telemetry->comUsbBridgeSpeed);
|
||||
connect(m_telemetry->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
enableSaveButtons(false);
|
||||
|
@ -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,99 +674,36 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</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>
|
||||
<item row="14" column="3">
|
||||
<widget class="QLabel" name="lblMainSpeed">
|
||||
<property name="text">
|
||||
<string>Changes on this page only take effect after board reset or power cycle</string>
|
||||
<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>
|
||||
<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 row="18" column="3">
|
||||
<widget class="QComboBox" name="cbMainGPSProtocol"/>
|
||||
</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 row="18" column="1">
|
||||
<widget class="QComboBox" name="cbFlexiGPSProtocol"/>
|
||||
</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>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
|
@ -13377,6 +13377,8 @@ border-radius: 5;</string>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>5</number>
|
||||
|
||||
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.000100000000000</double>
|
||||
@ -15941,6 +15943,7 @@ border-radius: 5;</string>
|
||||
<string>element:Kp</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
|
||||
<string>buttongroup:5,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
@ -17352,6 +17355,7 @@ border-radius: 5;</string>
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
@ -19417,6 +19421,7 @@ border-radius: 5;</string>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
@ -19941,6 +19946,7 @@ border-radius: 5;</string>
|
||||
<red>39</red>
|
||||
<green>39</green>
|
||||
<blue>39</blue>
|
||||
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
@ -21975,6 +21981,7 @@ border-radius: 5;</string>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QDoubleSpinBox" name="AccelKp">
|
||||
@ -24004,7 +24011,7 @@ border-radius: 5;</string>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QDoubleSpinBox" name="RattitudeAntiWindup">
|
||||
<widget class="QDoubleSpinBox" name="RattitudeModeTransition">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -24027,7 +24034,7 @@ border-radius: 5;</string>
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>Higher values will keep larger Ki terms and limits from winding up at partial stick. Consider increasing this if you have high Ki values and limits and a sudden stick motion from one aircraft bank angle to another causes the aircraft to rotate and then slowly change rotation.</p></body></html></string>
|
||||
<string><html><head/><body><p>Percentage of full stick where the transition from Attitude to Rate occurs. This transition always occurs when the aircraft is exactly inverted (bank angle 180 degrees). Small values are dangerous because they cause flips at small stick angles. Values significantly over 100 act like attitude mode and can never flip.</p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
@ -24039,18 +24046,18 @@ border-radius: 5;</string>
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<double>0.000000000000000</double>
|
||||
<double>25.000000000000000</double>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>31.000000000000000</double>
|
||||
<double>255.000000000000000</double>
|
||||
</property>
|
||||
<property name="value">
|
||||
<double>10.000000000000000</double>
|
||||
<double>80.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettings</string>
|
||||
<string>fieldname:RattitudeAntiWindup</string>
|
||||
<string>fieldname:RattitudeModeTransition</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:15</string>
|
||||
@ -24090,7 +24097,7 @@ color: rgb(255, 255, 255);
|
||||
border-radius: 5;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Anti-Windup</string>
|
||||
<string>ModeTransition</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
@ -24303,6 +24310,7 @@ border-radius: 5;</string>
|
||||
<string>buttongroup:16</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
@ -26158,6 +26166,7 @@ border-radius: 5;</string>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
|
@ -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,22 +30,35 @@
|
||||
|
||||
#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_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);
|
||||
|
||||
@ -56,7 +69,21 @@ FlightLogManager::FlightLogManager(QObject *parent) :
|
||||
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
|
||||
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
@ -131,7 +131,8 @@ struct hid_device_ {
|
||||
DWORD last_error_num;
|
||||
BOOL read_pending;
|
||||
char *read_buf;
|
||||
OVERLAPPED ol;
|
||||
OVERLAPPED rx_ol;
|
||||
OVERLAPPED tx_ol;
|
||||
};
|
||||
|
||||
static hid_device *new_hid_device()
|
||||
@ -145,15 +146,18 @@ static hid_device *new_hid_device()
|
||||
dev->last_error_num = 0;
|
||||
dev->read_pending = FALSE;
|
||||
dev->read_buf = NULL;
|
||||
memset(&dev->ol, 0, sizeof(dev->ol));
|
||||
dev->ol.hEvent = CreateEvent(NULL, FALSE, FALSE /*inital state f=nonsignaled*/, NULL);
|
||||
memset(&dev->rx_ol, 0, sizeof(dev->rx_ol));
|
||||
memset(&dev->tx_ol, 0, sizeof(dev->tx_ol));
|
||||
dev->rx_ol.hEvent = CreateEvent(NULL, FALSE, FALSE /*inital state f=nonsignaled*/, NULL);
|
||||
dev->tx_ol.hEvent = CreateEvent(NULL, FALSE, FALSE /*inital state f=nonsignaled*/, NULL);
|
||||
|
||||
return dev;
|
||||
}
|
||||
|
||||
static void free_hid_device(hid_device *dev)
|
||||
{
|
||||
CloseHandle(dev->ol.hEvent);
|
||||
CloseHandle(dev->rx_ol.hEvent);
|
||||
CloseHandle(dev->tx_ol.hEvent);
|
||||
CloseHandle(dev->device_handle);
|
||||
LocalFree(dev->last_error_str);
|
||||
free(dev->read_buf);
|
||||
@ -596,9 +600,7 @@ int HID_API_EXPORT HID_API_CALL hid_write(hid_device *dev, const unsigned char *
|
||||
DWORD bytes_written;
|
||||
BOOL res;
|
||||
|
||||
OVERLAPPED ol;
|
||||
unsigned char *buf;
|
||||
memset(&ol, 0, sizeof(ol));
|
||||
|
||||
/* Make sure the right number of bytes are passed to WriteFile. Windows
|
||||
expects the number of bytes which are in the _longest_ report (plus
|
||||
@ -618,7 +620,8 @@ int HID_API_EXPORT HID_API_CALL hid_write(hid_device *dev, const unsigned char *
|
||||
length = dev->output_report_length;
|
||||
}
|
||||
|
||||
res = WriteFile(dev->device_handle, buf, length, NULL, &ol);
|
||||
ResetEvent(dev->tx_ol.hEvent);
|
||||
res = WriteFile(dev->device_handle, buf, length, NULL, &dev->tx_ol);
|
||||
|
||||
if (!res) {
|
||||
if (GetLastError() != ERROR_IO_PENDING) {
|
||||
@ -631,7 +634,7 @@ int HID_API_EXPORT HID_API_CALL hid_write(hid_device *dev, const unsigned char *
|
||||
|
||||
/* Wait here until the write is done. This makes
|
||||
hid_write() synchronous. */
|
||||
res = GetOverlappedResult(dev->device_handle, &ol, &bytes_written, TRUE/*wait*/);
|
||||
res = GetOverlappedResult(dev->device_handle, &dev->tx_ol, &bytes_written, TRUE/*wait*/);
|
||||
if (!res) {
|
||||
/* The Write operation failed. */
|
||||
register_error(dev, "WriteFile");
|
||||
@ -653,14 +656,14 @@ int HID_API_EXPORT HID_API_CALL hid_read_timeout(hid_device *dev, unsigned char
|
||||
BOOL res;
|
||||
|
||||
/* Copy the handle for convenience. */
|
||||
HANDLE ev = dev->ol.hEvent;
|
||||
HANDLE ev = dev->rx_ol.hEvent;
|
||||
|
||||
if (!dev->read_pending) {
|
||||
/* Start an Overlapped I/O read. */
|
||||
dev->read_pending = TRUE;
|
||||
memset(dev->read_buf, 0, dev->input_report_length);
|
||||
ResetEvent(ev);
|
||||
res = ReadFile(dev->device_handle, dev->read_buf, dev->input_report_length, &bytes_read, &dev->ol);
|
||||
res = ReadFile(dev->device_handle, dev->read_buf, dev->input_report_length, &bytes_read, &dev->rx_ol);
|
||||
|
||||
if (!res) {
|
||||
if (GetLastError() != ERROR_IO_PENDING) {
|
||||
@ -686,7 +689,7 @@ int HID_API_EXPORT HID_API_CALL hid_read_timeout(hid_device *dev, unsigned char
|
||||
/* Either WaitForSingleObject() told us that ReadFile has completed, or
|
||||
we are in non-blocking mode. Get the number of bytes read. The actual
|
||||
data has been copied to the data[] array which was passed to ReadFile(). */
|
||||
res = GetOverlappedResult(dev->device_handle, &dev->ol, &bytes_read, TRUE/*wait*/);
|
||||
res = GetOverlappedResult(dev->device_handle, &dev->rx_ol, &bytes_read, TRUE/*wait*/);
|
||||
|
||||
/* Set pending back to false, even if GetOverlappedResult() returned error. */
|
||||
dev->read_pending = FALSE;
|
||||
|
@ -292,10 +292,8 @@ 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++) {
|
||||
QModelIndex index;
|
||||
WayPointItem *item;
|
||||
@ -325,7 +323,7 @@ void modelMapProxy::rowsInserted(const QModelIndex &parent, int first, int last)
|
||||
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;
|
||||
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,59 +59,78 @@ $(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');
|
||||
end
|
||||
|
||||
if (isempty(objID)) %End of file
|
||||
break;
|
||||
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;
|
||||
|
||||
%% Read object
|
||||
|
||||
@ -125,9 +144,7 @@ $(SWITCHCODE)
|
||||
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();
|
@ -33,12 +33,14 @@
|
||||
#include <QMutex>
|
||||
#include <QMutexLocker>
|
||||
|
||||
#include "uavobjectutil_global.h"
|
||||
#include "uavobject.h"
|
||||
|
||||
class UAVOBJECTS_EXPORT AbstractUAVObjectHelper : public QObject {
|
||||
class UAVOBJECTUTIL_EXPORT AbstractUAVObjectHelper : public QObject {
|
||||
Q_OBJECT
|
||||
public:
|
||||
explicit AbstractUAVObjectHelper(QObject *parent = 0);
|
||||
virtual ~AbstractUAVObjectHelper();
|
||||
|
||||
enum Result { SUCCESS, FAIL, TIMEOUT };
|
||||
Result doObjectAndWait(UAVObject *object, int timeout);
|
||||
@ -57,19 +59,21 @@ private:
|
||||
bool m_transactionCompleted;
|
||||
};
|
||||
|
||||
class UAVOBJECTS_EXPORT UAVObjectUpdaterHelper : public AbstractUAVObjectHelper {
|
||||
class UAVOBJECTUTIL_EXPORT UAVObjectUpdaterHelper : public AbstractUAVObjectHelper {
|
||||
Q_OBJECT
|
||||
public:
|
||||
explicit UAVObjectUpdaterHelper(QObject *parent = 0);
|
||||
virtual ~UAVObjectUpdaterHelper();
|
||||
|
||||
protected:
|
||||
virtual void doObjectAndWaitImpl();
|
||||
};
|
||||
|
||||
class UAVOBJECTS_EXPORT UAVObjectRequestHelper : public AbstractUAVObjectHelper {
|
||||
class UAVOBJECTUTIL_EXPORT UAVObjectRequestHelper : public AbstractUAVObjectHelper {
|
||||
Q_OBJECT
|
||||
public:
|
||||
explicit UAVObjectRequestHelper(QObject *parent = 0);
|
||||
virtual ~UAVObjectRequestHelper();
|
||||
|
||||
protected:
|
||||
virtual void doObjectAndWaitImpl();
|
@ -7,9 +7,11 @@ include(uavobjectutil_dependencies.pri)
|
||||
HEADERS += uavobjectutil_global.h \
|
||||
uavobjectutilmanager.h \
|
||||
uavobjectutilplugin.h \
|
||||
devicedescriptorstruct.h
|
||||
devicedescriptorstruct.h \
|
||||
uavobjecthelper.h
|
||||
|
||||
SOURCES += uavobjectutilmanager.cpp \
|
||||
uavobjectutilplugin.cpp
|
||||
uavobjectutilplugin.cpp \
|
||||
uavobjecthelper.cpp
|
||||
|
||||
OTHER_FILES += UAVObjectUtil.pluginspec
|
||||
|
@ -114,7 +114,7 @@ void SmartSaveButton::processOperation(QPushButton *button, bool save)
|
||||
|
||||
sv_result = false;
|
||||
current_objectID = obj->getObjID();
|
||||
if (save && (obj->isSettings())) {
|
||||
if (save && (obj->isSettingsObject())) {
|
||||
for (int i = 0; i < 3; ++i) {
|
||||
qDebug() << "Saving" << obj->getName() << "to board.";
|
||||
connect(utilMngr, SIGNAL(saveCompleted(int, bool)), this, SLOT(saving_finished(int, bool)));
|
||||
|
@ -276,8 +276,8 @@ QString UAVSettingsImportExportFactory::createXMLDocument(const enum storedData
|
||||
QList< QList<UAVDataObject *> > objList = objManager->getDataObjects();
|
||||
foreach(QList<UAVDataObject *> list, objList) {
|
||||
foreach(UAVDataObject * obj, list) {
|
||||
if (((what == Settings) && obj->isSettings()) ||
|
||||
((what == Data) && !obj->isSettings()) ||
|
||||
if (((what == Settings) && obj->isSettingsObject()) ||
|
||||
((what == Data) && !obj->isSettingsObject()) ||
|
||||
(what == Both)) {
|
||||
// add each object to the XML
|
||||
QDomElement o = doc.createElement("object");
|
||||
@ -319,7 +319,7 @@ QString UAVSettingsImportExportFactory::createXMLDocument(const enum storedData
|
||||
}
|
||||
|
||||
// append to the settings or data element
|
||||
if (obj->isSettings()) {
|
||||
if (obj->isSettingsObject()) {
|
||||
settings.appendChild(o);
|
||||
} else {
|
||||
data.appendChild(o);
|
||||
|
@ -78,7 +78,7 @@ void TelemetryMonitor::startRetrievingObjects()
|
||||
if (mobj != NULL) {
|
||||
queue.enqueue(obj);
|
||||
} else if (dobj != NULL) {
|
||||
if (dobj->isSettings()) {
|
||||
if (dobj->isSettingsObject()) {
|
||||
queue.enqueue(obj);
|
||||
} else {
|
||||
if (UAVObject::GetFlightTelemetryUpdateMode(mdata) == UAVObject::UPDATEMODE_ONCHANGE) {
|
||||
|
@ -105,8 +105,6 @@ private:
|
||||
|
||||
static const int TX_BUFFER_SIZE = 2 * 1024;
|
||||
|
||||
static const quint8 crc_table[256];
|
||||
|
||||
// Types
|
||||
typedef enum {
|
||||
STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS, STATE_COMPLETE, STATE_ERROR
|
||||
|
@ -122,9 +122,6 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo *info, int numBytes)
|
||||
matlabSwitchCode.append("\t\t\t" + tableIdxName + " = " + tableIdxName + " + 1;\n");
|
||||
matlabSwitchCode.append("\t\t\t" + objectTableName + "FidIdx(" + tableIdxName + ") = bufferIdx; %#ok<*AGROW>\n");
|
||||
matlabSwitchCode.append("\t\t\tbufferIdx=bufferIdx + " + objectTableName.toUpper() + "_NUMBYTES+1; %+1 is for CRC\n");
|
||||
if (!info->isSingleInst) {
|
||||
matlabSwitchCode.append("\t\t\tbufferIdx = bufferIdx + 2; %An extra two bytes for the instance ID\n");
|
||||
}
|
||||
matlabSwitchCode.append("\t\t\tif " + tableIdxName + " >= length(" + objectTableName + "FidIdx) %Check to see if pre-allocated memory is exhausted\n");
|
||||
matlabSwitchCode.append("\t\t\t\t" + objectTableName + "FidIdx(" + tableIdxName + "*2) = 0;\n");
|
||||
matlabSwitchCode.append("\t\t\tend\n");
|
||||
@ -145,16 +142,15 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo *info, int numBytes)
|
||||
// Add timestamp
|
||||
allocationFields.append("\t" + objectName + ".timestamp = " +
|
||||
"double(typecast(buffer(mcolon(" + objectName + "FidIdx "
|
||||
"- 20, " + objectName + "FidIdx + 4-1 -20)), 'uint32'))';\n");
|
||||
"- headerLen - oplHeaderLen, " + objectName + "FidIdx + 3 - headerLen - oplHeaderLen)), 'uint32'))';\n");
|
||||
|
||||
int currentIdx = 0;
|
||||
|
||||
// Add Instance ID, if necessary
|
||||
if (!info->isSingleInst) {
|
||||
allocationFields.append("\t" + objectName + ".instanceID = " +
|
||||
"double(typecast(buffer(mcolon(" + objectName + "FidIdx "
|
||||
", " + objectName + "FidIdx + 2-1)), 'uint16'))';\n");
|
||||
currentIdx += 2;
|
||||
"double(typecast(buffer(mcolon(" + objectName + "FidIdx - 2"
|
||||
", " + objectName + "FidIdx - 2 + 1)), 'uint16'))';\n");
|
||||
}
|
||||
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
|
@ -69,6 +69,7 @@ SRC += $(PIOSCOMMON)/pios_i2c_esc.c
|
||||
SRC += $(PIOSCOMMON)/pios_l3gd20.c
|
||||
SRC += $(PIOSCOMMON)/pios_mpu6000.c
|
||||
SRC += $(PIOSCOMMON)/pios_mpxv.c
|
||||
SRC += $(PIOSCOMMON)/pios_ms4525do.c
|
||||
SRC += $(PIOSCOMMON)/pios_ms5611.c
|
||||
SRC += $(PIOSCOMMON)/pios_oplinkrcvr.c
|
||||
SRC += $(PIOSCOMMON)/pios_video.c
|
||||
|
@ -27,14 +27,19 @@ SCRIPT_NAME="`basename \"$SCRIPT_PATH\"`"
|
||||
SCRIPT_DIR="`dirname \"$SCRIPT_PATH\"`"
|
||||
ROOT_DIR="`pushd \"$SCRIPT_DIR/../..\" >/dev/null && pwd && popd >/dev/null`"
|
||||
TOOLS_DIR="$ROOT_DIR/tools"
|
||||
if [ -x "$1" ]; then
|
||||
TOOLS_DIR="$1"
|
||||
fi
|
||||
|
||||
# Tools URLs to fetch
|
||||
WGET_URL="http://wiki.openpilot.org/download/attachments/18612236/wget.exe"
|
||||
MAKE_URL="http://wiki.openpilot.org/download/attachments/18612236/make.exe"
|
||||
SEVENZIP_URL="http://wiki.openpilot.org/download/attachments/18612236/7za.exe"
|
||||
|
||||
# Expected tools paths
|
||||
WGET="$TOOLS_DIR/bin/`basename \"$WGET_URL\"`"
|
||||
MAKE="$TOOLS_DIR/bin/`basename \"$MAKE_URL\"`"
|
||||
SEVENZIP="$TOOLS_DIR/bin/`basename \"$SEVENZIP_URL\"`"
|
||||
|
||||
# wget is necessary to fetch other files
|
||||
WGET_NAME="`basename \"$WGET\"`"
|
||||
@ -78,7 +83,6 @@ EOF
|
||||
fi
|
||||
|
||||
# make is necessary to fetch all SDKs
|
||||
MAKE_NAME="`basename \"$MAKE\"`"
|
||||
if [ ! -x "$MAKE" ]; then
|
||||
echo "$SCRIPT_NAME: $MAKE_NAME not found, fetching from $MAKE_URL"
|
||||
MAKE_DIR="`dirname \"$MAKE\"`"
|
||||
@ -86,10 +90,24 @@ if [ ! -x "$MAKE" ]; then
|
||||
$WGET -N --content-disposition -P "$MAKE_DIR" "$MAKE_URL"
|
||||
if [ $? -ne 0 ]; then
|
||||
echo "$SCRIPT_NAME: $MAKE_NAME fetch error, hope it's in the path..."
|
||||
MAKE_NAME="`basename \"$MAKE\"`"
|
||||
MAKE="$MAKE_NAME"
|
||||
fi
|
||||
fi
|
||||
|
||||
# 7-Zip is necessary to install some SDKs
|
||||
if [ ! -x "$SEVENZIP" ]; then
|
||||
echo "$SCRIPT_NAME: $SEVENZIP_NAME not found, fetching from $SEVENZIP_URL"
|
||||
SEVENZIP_DIR="`dirname \"$SEVENZIP\"`"
|
||||
mkdir -p "$SEVENZIP_DIR"
|
||||
$WGET -N --content-disposition -P "$SEVENZIP_DIR" "$SEVENZIP_URL"
|
||||
if [ $? -ne 0 ]; then
|
||||
echo "$SCRIPT_NAME: $SEVENZIP_NAME fetch error, hope it's in the path..."
|
||||
SEVENZIP_NAME="`basename \"$SEVENZIP\"`"
|
||||
SEVENZIP="$SEVENZIP_NAME"
|
||||
fi
|
||||
fi
|
||||
|
||||
# Finally we can fetch all SDKs using top level Makefile
|
||||
cd "$ROOT_DIR"
|
||||
echo "Run 'tools/bin/make all_sdk_install' to install the other tools"
|
||||
|
185
make/tools.mk
185
make/tools.mk
@ -12,6 +12,7 @@
|
||||
# mingw_install (Windows only - NOT USED for Qt-5.1.x)
|
||||
# python_install (Windows only - NOT USED for Qt-5.1.x)
|
||||
# nsis_install (Windows only)
|
||||
# sdl_install (Windows only)
|
||||
# openssl_install (Windows only)
|
||||
# uncrustify_install
|
||||
# doxygen_install
|
||||
@ -58,13 +59,13 @@ endif
|
||||
ifeq ($(UNAME), Linux)
|
||||
ifeq ($(ARCH), x86_64)
|
||||
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux-amd64.tar.bz2
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.1/5.1.1/qt-linux-opensource-5.1.1-x86_64-offline.run
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-linux-opensource-5.1.1-x86_64-offline.run.md5
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.2/5.2.1/qt-opensource-linux-x64-5.2.1.run
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-opensource-linux-x64-5.2.1.run.md5
|
||||
QT_SDK_ARCH := gcc_64
|
||||
else
|
||||
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux-i686.tar.bz2
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.1/5.1.1/qt-linux-opensource-5.1.1-x86-offline.run
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-linux-opensource-5.1.1-x86-offline.run.md5
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.2/5.2.1/qt-opensource-linux-x86-5.2.1.run
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-opensource-linux-x86-5.2.1.run.md5
|
||||
QT_SDK_ARCH := gcc
|
||||
endif
|
||||
UNCRUSTIFY_URL := http://wiki.openpilot.org/download/attachments/18612236/uncrustify-0.60.tar.gz
|
||||
@ -76,8 +77,11 @@ else ifeq ($(UNAME), Darwin)
|
||||
DOXYGEN_URL := http://wiki.openpilot.org/download/attachments/18612236/doxygen-1.8.3.1.src.tar.gz
|
||||
else ifeq ($(UNAME), Windows)
|
||||
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-windows.tar.bz2
|
||||
QT_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-5.1.1-windows.tar.bz2
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.2/5.2.1/qt-opensource-windows-x86-mingw48_opengl-5.2.1.exe
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-opensource-windows-x86-mingw48_opengl-5.2.1.exe.md5
|
||||
QT_SDK_ARCH := mingw48_32
|
||||
NSIS_URL := http://wiki.openpilot.org/download/attachments/18612236/nsis-2.46-unicode.tar.bz2
|
||||
SDL_URL := http://wiki.openpilot.org/download/attachments/18612236/SDL-devel-1.2.15-mingw32.tar.gz
|
||||
OPENSSL_URL := http://wiki.openpilot.org/download/attachments/18612236/openssl-1.0.1e-win32.tar.bz2
|
||||
UNCRUSTIFY_URL := http://wiki.openpilot.org/download/attachments/18612236/uncrustify-0.60-windows.tar.bz2
|
||||
DOXYGEN_URL := http://wiki.openpilot.org/download/attachments/18612236/doxygen-1.8.3.1-windows.tar.bz2
|
||||
@ -87,10 +91,11 @@ GTEST_URL := http://wiki.openpilot.org/download/attachments/18612236/gtest-1.6.0
|
||||
|
||||
# Changing PYTHON_DIR, also update it in ground/openpilotgcs/src/python.pri
|
||||
ARM_SDK_DIR := $(TOOLS_DIR)/gcc-arm-none-eabi-4_7-2013q1
|
||||
QT_SDK_DIR := $(TOOLS_DIR)/qt-5.1.1
|
||||
QT_SDK_DIR := $(TOOLS_DIR)/qt-5.2.1
|
||||
MINGW_DIR := $(QT_SDK_DIR)/Tools/mingw48_32
|
||||
PYTHON_DIR := $(QT_SDK_DIR)/Tools/mingw48_32/opt/bin
|
||||
NSIS_DIR := $(TOOLS_DIR)/nsis-2.46-unicode
|
||||
SDL_DIR := $(TOOLS_DIR)/SDL-1.2.15
|
||||
OPENSSL_DIR := $(TOOLS_DIR)/openssl-1.0.1e-win32
|
||||
UNCRUSTIFY_DIR := $(TOOLS_DIR)/uncrustify-0.60
|
||||
DOXYGEN_DIR := $(TOOLS_DIR)/doxygen-1.8.3.1
|
||||
@ -106,7 +111,7 @@ QT_SDK_PREFIX := $(QT_SDK_DIR)
|
||||
|
||||
BUILD_SDK_TARGETS := arm_sdk qt_sdk
|
||||
ifeq ($(UNAME), Windows)
|
||||
BUILD_SDK_TARGETS += mingw python nsis openssl
|
||||
BUILD_SDK_TARGETS += mingw sdl python nsis openssl
|
||||
endif
|
||||
ALL_SDK_TARGETS := $(BUILD_SDK_TARGETS) gtest uncrustify doxygen
|
||||
|
||||
@ -145,9 +150,18 @@ OPENSSL := openssl
|
||||
ANT := ant
|
||||
JAVAC := javac
|
||||
JAR := jar
|
||||
SEVENZIP := 7z
|
||||
CD := cd
|
||||
GREP := grep
|
||||
ifneq ($(UNAME), Windows)
|
||||
SEVENZIP := 7za
|
||||
else
|
||||
SEVENZIP := 7za.exe
|
||||
ifneq ($(shell $(SEVENZIP) --version >/dev/null 2>&1 && $(ECHO) "found"), found)
|
||||
# no $(SEVENZIP) found in path. hope is in bin...
|
||||
SEVENZIP = $(TOOLS_DIR)/bin/7za.exe
|
||||
endif
|
||||
endif
|
||||
|
||||
# Echo in recipes is a bit tricky in a Windows Git Bash window in some cases.
|
||||
# It does not work if make started under msysGit installed into a path with spaces.
|
||||
ifneq ($(UNAME), Windows)
|
||||
@ -255,7 +269,6 @@ define DOWNLOAD_TEMPLATE
|
||||
)
|
||||
endef
|
||||
|
||||
|
||||
##############################
|
||||
#
|
||||
# Common tool install template
|
||||
@ -298,6 +311,73 @@ $(1)_distclean:
|
||||
|
||||
endef
|
||||
|
||||
##############################
|
||||
#
|
||||
# Windows QT install template
|
||||
# $(1) = tool temp extract/build directory
|
||||
# $(2) = tool install directory
|
||||
# $(3) = tool distribution URL
|
||||
# $(4) = tool distribution .md5 URL
|
||||
# $(5) = tool distribution file
|
||||
# $(6) = QT architecture
|
||||
# $(7) = optional extra build recipes template
|
||||
# $(8) = optional extra clean recipes template
|
||||
#
|
||||
##############################
|
||||
|
||||
define WIN_QT_INSTALL_TEMPLATE
|
||||
|
||||
.PHONY: $(addprefix qt_sdk_, install clean distclean)
|
||||
|
||||
qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR)
|
||||
$(V1) if ! $(SEVENZIP) >/dev/null 2>&1; then \
|
||||
$(ECHO) $(MSG_NOTICE) "Missing 7zip. Run ./make/scripts/win_sdk_install.sh [<OpenPilot tools dir>] to get it." && \
|
||||
exit 1; \
|
||||
fi
|
||||
$(call DOWNLOAD_TEMPLATE,$(3),$(5),"$(4)")
|
||||
# Explode .run file into install packages
|
||||
@$(ECHO) $(MSG_EXTRACTING) $$(call toprel, $(1))
|
||||
$(V1) $(MKDIR) -p $$(call toprel, $(dir $(1)))
|
||||
$(V1) chmod +x $(DL_DIR)/$(5)
|
||||
$(V1) $(DL_DIR)/$(5) --dump-binary-data -o $(1)
|
||||
# Extract packages under tool directory
|
||||
$(V1) $(MKDIR) -p $$(call toprel, $(dir $(2)))
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0qt-project-url.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/1.0.0ThirdPartySoftware_Listing.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0readme.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.win32_mingw48.essentials/5.2.1mingw48_essentials.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.win32_mingw48.essentials/5.2.1x32-4.8.0-release-posix-dwarf-rev2-runtime.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.win32_mingw48.essentials/5.2.1icu_51_1_mingw_builds_4_8_0_posix_dwarf_32.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.win32_mingw48.addons/5.2.1mingw48_addons.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.tools.win32_mingw48/4.8.0-1-1x32-4.8.0-release-posix-dwarf-rev2.7z" | grep -v Extracting
|
||||
# Run patcher
|
||||
@$(ECHO)
|
||||
@$(ECHO) "Executing QtPatch in" $$(call toprel, $(QT_SDK_PREFIX))
|
||||
$(V1) $(CD) $(QT_SDK_PREFIX)
|
||||
$(V1) $(DL_DIR)/$(5) --runoperation QtPatch windows $(QT_SDK_PREFIX) qt5
|
||||
|
||||
# Execute post build templates
|
||||
$(7)
|
||||
|
||||
# Clean up temporary files
|
||||
@$(ECHO) $(MSG_CLEANING) $$(call toprel, $(1))
|
||||
$(V1) [ ! -d "$(1)" ] || $(RM) -rf "$(1)"
|
||||
|
||||
qt_sdk_clean:
|
||||
@$(ECHO) $(MSG_CLEANING) $$(call toprel, $(1))
|
||||
$(V1) [ ! -d "$(1)" ] || $(RM) -rf "$(1)"
|
||||
@$(ECHO) $(MSG_CLEANING) $$(call toprel, "$(2)")
|
||||
$(V1) [ ! -d "$(2)" ] || $(RM) -rf "$(2)"
|
||||
|
||||
$(8)
|
||||
|
||||
qt_sdk_distclean:
|
||||
@$(ECHO) $(MSG_DISTCLEANING) $$(call toprel, $(DL_DIR)/$(5))
|
||||
$(V1) [ ! -f "$(DL_DIR)/$(5)" ] || $(RM) "$(DL_DIR)/$(5)"
|
||||
$(V1) [ ! -f "$(DL_DIR)/$(5).md5" ] || $(RM) "$(DL_DIR)/$(5).md5"
|
||||
|
||||
endef
|
||||
|
||||
##############################
|
||||
#
|
||||
# Linux QT install template
|
||||
@ -317,7 +397,10 @@ define LINUX_QT_INSTALL_TEMPLATE
|
||||
.PHONY: $(addprefix qt_sdk_, install clean distclean)
|
||||
|
||||
qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR)
|
||||
|
||||
$(V1) if ! $(SEVENZIP) >/dev/null 2>&1; then \
|
||||
$(ECHO) $(MSG_NOTICE) "Please install the p7zip for your distribution. i.e.: sudo apt-get install p7zip." && \
|
||||
exit 1; \
|
||||
fi
|
||||
$(call DOWNLOAD_TEMPLATE,$(3),$(5),"$(4)")
|
||||
# Explode .run file into install packages
|
||||
@$(ECHO) $(MSG_EXTRACTING) $$(call toprel, $(1))
|
||||
@ -329,16 +412,16 @@ qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR)
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0qt-project-url.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/1.0.0ThirdPartySoftware_Listing.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0readme.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.511.$(6).essentials/5.1.1$(6)_qt5_essentials.7z" | grep -v Extracting
|
||||
$(V1) if [ -f "$(1)/qt.511.$(6).essentials/5.1.1icu_51_1_ubuntu_11_10_64.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.511.$(6).essentials/5.1.1icu_51_1_ubuntu_11_10_64.7z" | grep -v Extracting; fi
|
||||
$(V1) if [ -f "$(1)/qt.511.$(6).essentials/5.1.1icu_51_1_ubuntu_11_10_32.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.511.$(6).essentials/5.1.1icu_51_1_ubuntu_11_10_32.7z" | grep -v Extracting; fi
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.511.$(6).essentials/5.1.1icu_path_patcher.sh.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.511.$(6).addons/5.1.1$(6)_qt5_addons.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.$(6).essentials/5.2.1$(6)_qt5_essentials.7z" | grep -v Extracting
|
||||
$(V1) if [ -f "$(1)/qt.521.$(6).essentials/5.2.1icu_51_1_ubuntu_11_10_64.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.$(6).essentials/5.2.1icu_51_1_ubuntu_11_10_64.7z" | grep -v Extracting; fi
|
||||
$(V1) if [ -f "$(1)/qt.521.$(6).essentials/5.2.1icu_51_1_ubuntu_11_10_32.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.$(6).essentials/5.2.1icu_51_1_ubuntu_11_10_32.7z" | grep -v Extracting; fi
|
||||
# $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.$(6).essentials/5.2.1icu_path_patcher.sh.7z" | grep -v Extracting
|
||||
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.521.$(6).addons/5.2.1$(6)_qt5_addons.7z" | grep -v Extracting
|
||||
# go to OpenPilot/tools/5.1.1/gcc_64 and call patcher.sh
|
||||
@$(ECHO)
|
||||
@$(ECHO) "Running patcher in" $$(call toprel, $(QT_SDK_PREFIX))
|
||||
$(V1) $(CD) $(QT_SDK_PREFIX)
|
||||
$(V1) "$(QT_SDK_PREFIX)/patcher.sh" $(QT_SDK_PREFIX)
|
||||
# $(V1) "$(QT_SDK_PREFIX)/patcher.sh" $(QT_SDK_PREFIX)
|
||||
# call qmake patcher
|
||||
@$(ECHO) "Executing QtPatch in" $$(call toprel, $(QT_SDK_PREFIX))
|
||||
$(V1) $(DL_DIR)/$(5) --runoperation QtPatch linux $(QT_SDK_PREFIX) qt5
|
||||
@ -398,26 +481,28 @@ endef
|
||||
#
|
||||
# Qt SDK
|
||||
#
|
||||
# Windows: native binary package has been provided
|
||||
# Linux: user should install native Qt SDK package
|
||||
# Mac OS X: user should install native Qt SDK package
|
||||
#
|
||||
##############################
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
QT_SDK_PREFIX := $(QT_SDK_DIR)/5.1.1/mingw48_32
|
||||
QT_SDK_PREFIX := $(QT_SDK_DIR)/5.2.1/$(QT_SDK_ARCH)
|
||||
|
||||
# This additional configuration step should not be necessary
|
||||
# but it is needed as a workaround to https://bugreports.qt-project.org/browse/QTBUG-33254
|
||||
define QT_SDK_CONFIGURE_TEMPLATE
|
||||
@$(ECHO) $(MSG_CONFIGURING) $(call toprel, $(QT_SDK_DIR))
|
||||
$(V1) $(ECHO) $(QUOTE)[Paths]$(QUOTE) > $(QT_SDK_PREFIX)/bin/qt.conf
|
||||
$(V1) $(ECHO) $(QUOTE)Prefix = $(QT_SDK_PREFIX)$(QUOTE) >> $(QT_SDK_PREFIX)/bin/qt.conf
|
||||
endef
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,qt_sdk,$(QT_SDK_DIR),$(QT_SDK_URL),$(notdir $(QT_SDK_URL)),$(QT_SDK_CONFIGURE_TEMPLATE)))
|
||||
QT_BUILD_DIR := $(BUILD_DIR)/QT_BUILD
|
||||
$(eval $(call WIN_QT_INSTALL_TEMPLATE,$(QT_BUILD_DIR),$(QT_SDK_DIR),$(QT_SDK_URL),$(QT_SDK_MD5_URL),$(notdir $(QT_SDK_URL)),$(QT_SDK_ARCH),$(QT_SDK_CONFIGURE_TEMPLATE)))
|
||||
|
||||
else ifeq ($(UNAME), Linux)
|
||||
QT_SDK_PREFIX := "$(QT_SDK_DIR)/5.1.1/$(QT_SDK_ARCH)"
|
||||
|
||||
QT_SDK_PREFIX := "$(QT_SDK_DIR)/5.2.1/$(QT_SDK_ARCH)"
|
||||
QT_BUILD_DIR := $(BUILD_DIR)/QT_BUILD
|
||||
$(eval $(call LINUX_QT_INSTALL_TEMPLATE,$(QT_BUILD_DIR),$(QT_SDK_DIR),$(QT_SDK_URL),$(QT_SDK_MD5_URL),$(notdir $(QT_SDK_URL)),$(QT_SDK_ARCH)))
|
||||
|
||||
@ -428,7 +513,7 @@ QT_SDK_PREFIX := $(QT_SDK_DIR)
|
||||
.PHONY: qt_sdk_install
|
||||
qt_sdk_install:
|
||||
@$(ECHO) $(MSG_NOTICE) --------------------------------------------------------
|
||||
@$(ECHO) $(MSG_NOTICE) Please install native Qt 5.1.x SDK using package manager
|
||||
@$(ECHO) $(MSG_NOTICE) Please install native Qt 5.2.x SDK using package manager
|
||||
@$(ECHO) $(MSG_NOTICE) --------------------------------------------------------
|
||||
|
||||
.PHONY: qt_sdk_clean
|
||||
@ -466,62 +551,40 @@ qt_sdk_version:
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
#$(eval $(call TOOL_INSTALL_TEMPLATE,mingw,$(MINGW_DIR),$(MINGW_URL),$(notdir $(MINGW_URL))))
|
||||
mingw_install:
|
||||
mingw_clean:
|
||||
mingw_distclean:
|
||||
|
||||
ifeq ($(shell [ -d "$(MINGW_DIR)" ] && $(ECHO) "exists"), exists)
|
||||
# set MinGW binary and library paths (QTMINGW is used by qmake, do not rename)
|
||||
export QTMINGW := $(MINGW_DIR)/bin
|
||||
export PATH := $(QTMINGW):$(PATH)
|
||||
else
|
||||
# not installed, use host gcc compiler
|
||||
# $(info $(EMPTY) WARNING $(call toprel, $(MINGW_DIR)) not found (make mingw_install), using system PATH)
|
||||
# $(info $(EMPTY) WARNING $(call toprel, $(MINGW_DIR)) not found, using system PATH)
|
||||
endif
|
||||
|
||||
.PHONY: mingw_version
|
||||
mingw_version:
|
||||
-$(V1) gcc --version | head -n1
|
||||
|
||||
.PHONY: gcc_version
|
||||
gcc_version: mingw_version
|
||||
mingw_version: gcc_version
|
||||
|
||||
else # Linux or Mac
|
||||
|
||||
all_sdk_version: gcc_version
|
||||
|
||||
endif
|
||||
|
||||
.PHONY: gcc_version
|
||||
gcc_version:
|
||||
-$(V1) gcc --version | head -n1
|
||||
|
||||
endif
|
||||
|
||||
##############################
|
||||
#
|
||||
# Python
|
||||
#
|
||||
##############################
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
#$(eval $(call TOOL_INSTALL_TEMPLATE,python,$(PYTHON_DIR),$(PYTHON_URL),$(notdir $(PYTHON_URL))))
|
||||
python_install:
|
||||
python_clean:
|
||||
python_distclean:
|
||||
|
||||
else # Linux or Mac
|
||||
|
||||
all_sdk_version: python_version
|
||||
|
||||
endif
|
||||
|
||||
ifeq ($(shell [ -d "$(PYTHON_DIR)" ] && $(ECHO) "exists"), exists)
|
||||
export PYTHON := $(PYTHON_DIR)/python
|
||||
export PATH := $(PYTHON_DIR):$(PATH)
|
||||
else
|
||||
# not installed, hope it's in the path...
|
||||
# $(info $(EMPTY) WARNING $(call toprel, $(PYTHON_DIR)) not found (make python_install), using system PATH)
|
||||
# $(info $(EMPTY) WARNING $(call toprel, $(PYTHON_DIR)) not found, using system PATH)
|
||||
export PYTHON := python
|
||||
endif
|
||||
|
||||
@ -553,6 +616,29 @@ nsis_version:
|
||||
|
||||
endif
|
||||
|
||||
##############################
|
||||
#
|
||||
# SDL (Windows only)
|
||||
#
|
||||
##############################
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,sdl,$(SDL_DIR),$(SDL_URL),$(notdir $(SDL_URL))))
|
||||
|
||||
ifeq ($(shell [ -d "$(SDL_DIR)" ] && $(ECHO) "exists"), exists)
|
||||
export SDL_DIR := $(SDL_DIR)
|
||||
else
|
||||
# not installed, hope it's in the path...
|
||||
$(info $(EMPTY) WARNING $(call toprel, $(SDL_DIR)) not found (make sdl_install), using system PATH)
|
||||
endif
|
||||
|
||||
.PHONY: sdl_version
|
||||
sdl_version:
|
||||
-$(V1) $(ECHO) "SDL 1.2.15"
|
||||
|
||||
endif
|
||||
|
||||
##############################
|
||||
#
|
||||
# OpenSSL (Windows only)
|
||||
@ -574,6 +660,7 @@ endif
|
||||
.PHONY: openssl_version
|
||||
openssl_version:
|
||||
-$(V1) $(ECHO) "OpenSSL `$(OPENSSL) version`"
|
||||
|
||||
endif
|
||||
|
||||
##############################
|
||||
|
@ -36,7 +36,6 @@ install:
|
||||
cp -arp build/openpilotgcs_release/bin debian/openpilot/usr/local/OpenPilot
|
||||
cp -arp build/openpilotgcs_release/lib debian/openpilot/usr/local/OpenPilot
|
||||
cp -arp build/openpilotgcs_release/share debian/openpilot/usr/local/OpenPilot
|
||||
cp -arp build/openpilotgcs_release/.obj debian/openpilot/usr/local/OpenPilot
|
||||
cp -arp package/linux/qt.conf debian/openpilot/usr/local/OpenPilot/bin
|
||||
cp -arp package/linux/openpilot.desktop debian/openpilot/usr/share/applications
|
||||
cp -arp package/linux/openpilot.png debian/openpilot/usr/share/pixmaps
|
||||
|
@ -3,7 +3,11 @@
|
||||
<description>The raw data from the dynamic pressure sensor with pressure, temperature and airspeed.</description>
|
||||
<field name="SensorConnected" units="" type="enum" elements="1" options="False,True"/>
|
||||
<field name="SensorValue" units="raw" type="uint16" elements="1"/>
|
||||
<field name="SensorValueTemperature" units="raw" type="uint16" elements="1"/>
|
||||
<field name="DifferentialPressure" units="Pa" type="float" elements="1"/>
|
||||
<field name="Temperature" units="K" type="float" elements="1"/>
|
||||
<field name="CalibratedAirspeed" units="m/s" type="float" elements="1"/>
|
||||
<field name="TrueAirspeed" units="m/s" type="float" elements="1" defaultvalue="-1"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="false" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="false" updatemode="periodic" period="1000"/>
|
||||
|
@ -4,7 +4,7 @@
|
||||
<field name="SamplePeriod" units="ms" type="uint8" elements="1" defaultvalue="100"/>
|
||||
<field name="ZeroPoint" units="raw" type="uint16" elements="1" defaultvalue="0"/>
|
||||
<field name="Scale" units="raw" type="float" elements="1" defaultvalue="1.0"/>
|
||||
<field name="AirspeedSensorType" units="" type="enum" elements="1" options="EagleTreeAirspeedV3,DIYDronesMPXV5004,DIYDronesMPXV7002,GroundSpeedBasedWindEstimation" defaultvalue="DIYDronesMPXV7002"/>
|
||||
<field name="AirspeedSensorType" units="" type="enum" elements="1" options="PixHawkAirspeedMS4525DO,EagleTreeAirspeedV3,DIYDronesMPXV5004,DIYDronesMPXV7002,GroundSpeedBasedWindEstimation,None" defaultvalue="GroundSpeedBasedWindEstimation"/>
|
||||
<field name="GroundSpeedBasedEstimationLowPassAlpha" units="" type="float" elements="1" defaultvalue="0.08" />
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -28,7 +28,7 @@
|
||||
<field name="WeakLevelingKp" units="(deg/s)/deg" type="float" elements="1" defaultvalue="0.1"/>
|
||||
<field name="MaxWeakLevelingRate" units="deg/s" type="uint8" elements="1" defaultvalue="5"/>
|
||||
|
||||
<field name="RattitudeAntiWindup" units="" type="uint8" elements="1" defaultvalue="10"/>
|
||||
<field name="RattitudeModeTransition" units="%" type="uint8" elements="1" defaultvalue="80"/>
|
||||
|
||||
<field name="CruiseControlMinThrust" units="%" type="uint8" elements="1" defaultvalue="5"/>
|
||||
<field name="CruiseControlMaxThrust" units="%" type="uint8" elements="1" defaultvalue="90"/>
|
||||
|
@ -15,6 +15,7 @@
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>Guidance</elementname>
|
||||
<elementname>PathPlan</elementname>
|
||||
@ -43,7 +44,7 @@
|
||||
</elementnames>
|
||||
</field>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetrygcs acked="true" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
|
Loading…
Reference in New Issue
Block a user