1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-17 02:52:12 +01:00

Merge branch 'andrecillo/OP-1283_SystemHealthGadgetWidget_updateAlarms_coordinate_calculation_correction' into andrecillo/OP-1273_OP-1282_OP-1283_Diverse_Airspeedsensor_improvements

Merged correction on coordinate calculation in SystemHealth gadget for correct display of Airspeed-Alarm
This commit is contained in:
Andres 2014-03-28 17:01:44 +01:00
commit 7067f4f8ff
17 changed files with 185 additions and 224 deletions

View File

@ -450,6 +450,7 @@ else
GCS_SILENT := silent
endif
.NOTPARALLEL:
.PHONY: openpilotgcs
openpilotgcs: uavobjects_gcs openpilotgcs_qmake openpilotgcs_make
@ -960,6 +961,9 @@ help:
@$(ECHO)
@$(ECHO) " [GCS]"
@$(ECHO) " gcs - Build the Ground Control System (GCS) application (debug|release)"
@$(ECHO) " Skip qmake: QMAKE_SKIP=1"
@$(ECHO) " Compile specific directory: MAKE_DIR=<dir>"
@$(ECHO) " Example: make gcs QMAKE_SKIP=1 MAKE_DIR=src/plugins/coreplugin"
@$(ECHO) " gcs_clean - Remove the Ground Control System (GCS) application (debug|release)"
@$(ECHO) " Supported build configurations: GCS_BUILD_CONF=debug|release (default is $(GCS_BUILD_CONF))"
@$(ECHO)

View File

@ -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.

View File

@ -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;

View File

@ -40,6 +40,7 @@
#include <airspeedsensor.h>
#include <gpspositionsensor.h>
#include <gpsvelocitysensor.h>
#include <homelocation.h>
#include <gyrostate.h>
#include <accelstate.h>
@ -55,10 +56,14 @@
#include "CoordinateConversions.h"
// Private constants
#define STACK_SIZE_BYTES 256
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_REGULAR
#define TASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
#define TIMEOUT_MS 10
#define STACK_SIZE_BYTES 256
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_REGULAR
#define TASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
#define TIMEOUT_MS 10
// Private filter init const
#define FILTER_INIT_FORCE -1
#define FILTER_INIT_IF_POSSIBLE -2
// local macros, ONLY to be used in the middle of StateEstimationCb in section RUNSTATE_LOAD after the update of states updated!
#define FETCH_SENSOR_FROM_UAVOBJECT_CHECK_AND_LOAD_TO_STATE_3_DIMENSIONS(sensorname, shortname, a1, a2, a3) \
@ -134,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
@ -228,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)
@ -253,6 +259,8 @@ int32_t StateEstimationInitialize(void)
GPSVelocitySensorInitialize();
GPSPositionSensorInitialize();
HomeLocationInitialize();
GyroStateInitialize();
AccelStateInitialize();
MagStateInitialize();
@ -262,6 +270,8 @@ int32_t StateEstimationInitialize(void)
RevoSettingsConnectCallback(&settingsUpdatedCb);
HomeLocationConnectCallback(&homeLocationUpdatedCb);
GyroSensorConnectCallback(&sensorUpdatedCb);
AccelSensorConnectCallback(&sensorUpdatedCb);
MagSensorConnectCallback(&sensorUpdatedCb);
@ -344,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:
@ -492,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

View File

@ -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,16 +569,11 @@ 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);;
stats.CPUTemp = PIOS_CONVERT_VOLT_TO_CPU_TEMP(temp_voltage);;
#endif
SystemStatsSet(&stats);
}
@ -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.

View File

@ -33,6 +33,7 @@
static xSemaphoreHandle mLock;
static xTaskHandle *mTaskHandles;
static uint32_t mLastMonitorTime;
static uint32_t mLastIdleMonitorTime;
static uint16_t mMaxTasks;
/**
@ -53,9 +54,11 @@ 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();
mLastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE();
mLastIdleMonitorTime = portGET_RUN_TIME_COUNTER_VALUE();
#else
mLastMonitorTime = 0;
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

View File

@ -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

View File

@ -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);

View File

@ -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

View File

@ -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

View File

@ -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:

View File

@ -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). */

View File

@ -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:

View File

@ -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>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;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.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;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.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</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"/>

View File

@ -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;

View File

@ -97,6 +97,8 @@ void SystemHealthGadgetWidget::updateAlarms(UAVObject *systemAlarm)
delete item; // removeItem does _not_ delete the item.
}
QMatrix backgroundMatrix = m_renderer->matrixForElement(background->elementId());
QString alarm = systemAlarm->getName();
foreach(UAVObjectField * field, systemAlarm->getFields()) {
for (uint i = 0; i < field->getNumElements(); ++i) {
@ -104,12 +106,16 @@ void SystemHealthGadgetWidget::updateAlarms(UAVObject *systemAlarm)
QString value = field->getValue(i).toString();
if (!missingElements->contains(element)) {
if (m_renderer->elementExists(element)) {
QMatrix blockMatrix = m_renderer->matrixForElement(element);
qreal startX = blockMatrix.mapRect(m_renderer->boundsOnElement(element)).x();
qreal startY = blockMatrix.mapRect(m_renderer->boundsOnElement(element)).y();
QString element2 = element + "-" + value;
QString element2 = element + "-" + value;
if (!missingElements->contains(element2)) {
if (m_renderer->elementExists(element2)) {
// element2 is in global coordinates
// transform its matrix into the coordinates of background
QMatrix blockMatrix = backgroundMatrix.inverted() * m_renderer->matrixForElement(element2);
// use this composed projection to get the position in background coordinates
qreal startX = blockMatrix.mapRect(m_renderer->boundsOnElement(element2)).x();
qreal startY = blockMatrix.mapRect(m_renderer->boundsOnElement(element2)).y();
QGraphicsSvgItem *ind = new QGraphicsSvgItem();
ind->setSharedRenderer(m_renderer);
ind->setElementId(element2);

View File

@ -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"/>