Merge branch 'bugfix-flight' of ssh://git.openpilot.org/OpenPilot into bugfix-flight
@ -127,6 +127,12 @@ C: Werner Backes
|
||||
D: July 2011
|
||||
V: http://vimeo.com/25983655
|
||||
|
||||
M: CopterControl Y4 flight
|
||||
C: Mat Wellington
|
||||
D: July 2011
|
||||
V: http://www.youtube.com/watch?v=TxZ4MDGIj1o
|
||||
|
||||
|
||||
M: First Altitude Hold using Sonar
|
||||
C:
|
||||
D:
|
||||
|
BIN
artwork/3D Model/multi/joes_cnc/CC.PNG
Normal file
After Width: | Height: | Size: 96 KiB |
BIN
artwork/3D Model/multi/joes_cnc/J14-QT_+.3DS
Normal file
BIN
artwork/3D Model/multi/joes_cnc/J14-QT_+.jpg
Normal file
After Width: | Height: | Size: 125 KiB |
BIN
artwork/3D Model/multi/joes_cnc/J14-QT_X.3DS
Normal file
BIN
artwork/3D Model/multi/joes_cnc/J14-QT_X.jpg
Normal file
After Width: | Height: | Size: 132 KiB |
BIN
artwork/3D Model/multi/joes_cnc/J14-Q_+.3DS
Normal file
BIN
artwork/3D Model/multi/joes_cnc/J14-Q_+.jpg
Normal file
After Width: | Height: | Size: 84 KiB |
BIN
artwork/3D Model/multi/joes_cnc/J14-Q_X.3DS
Normal file
BIN
artwork/3D Model/multi/joes_cnc/J14-Q_X.jpg
Normal file
After Width: | Height: | Size: 84 KiB |
BIN
artwork/3D Model/multi/joes_cnc/TEXTURE.PNG
Normal file
After Width: | Height: | Size: 1.1 KiB |
35
artwork/GCS Icons/dialog-warning.svg
Normal file
@ -0,0 +1,35 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
<svg id="svg3247" xmlns="http://www.w3.org/2000/svg" height="48" width="48" version="1.0" xmlns:xlink="http://www.w3.org/1999/xlink">
|
||||
<defs id="defs3249">
|
||||
<linearGradient id="linearGradient2411" y2="5.4676" gradientUnits="userSpaceOnUse" x2="63.397" gradientTransform="matrix(2.1154 0 0 2.1153 -107.58 32.427)" y1="-12.489" x1="63.397">
|
||||
<stop id="stop4875" style="stop-color:#fff" offset="0"/>
|
||||
<stop id="stop4877" style="stop-color:#fff;stop-opacity:0" offset="1"/>
|
||||
</linearGradient>
|
||||
<linearGradient id="linearGradient2416" y2="3.0816" gradientUnits="userSpaceOnUse" x2="18.379" gradientTransform="matrix(.95844 0 0 .95844 .99752 1.9975)" y1="44.98" x1="18.379">
|
||||
<stop id="stop2492" style="stop-color:#791235" offset="0"/>
|
||||
<stop id="stop2494" style="stop-color:#dd3b27" offset="1"/>
|
||||
</linearGradient>
|
||||
<radialGradient id="radialGradient2414" gradientUnits="userSpaceOnUse" cy="3.99" cx="23.896" gradientTransform="matrix(0 2.2875 -3.0194 0 36.047 -50.63)" r="20.397">
|
||||
<stop id="stop3244" style="stop-color:#f8b17e" offset="0"/>
|
||||
<stop id="stop3246" style="stop-color:#e35d4f" offset=".26238"/>
|
||||
<stop id="stop3248" style="stop-color:#c6262e" offset=".66094"/>
|
||||
<stop id="stop3250" style="stop-color:#690b54" offset="1"/>
|
||||
</radialGradient>
|
||||
<radialGradient id="radialGradient2419" gradientUnits="userSpaceOnUse" cy="4.625" cx="62.625" gradientTransform="matrix(2.1647 0 0 .75294 -111.56 36.518)" r="10.625">
|
||||
<stop id="stop8840" offset="0"/>
|
||||
<stop id="stop8842" style="stop-opacity:0" offset="1"/>
|
||||
</radialGradient>
|
||||
</defs>
|
||||
<g id="layer1">
|
||||
<g id="g3275">
|
||||
<path id="path8836" style="opacity:.3;fill-rule:evenodd;fill:url(#radialGradient2419)" d="m47 40c0 4.418-10.297 8-23 8s-23-3.582-23-8 10.297-8 23-8 23 3.582 23 8z"/>
|
||||
<path id="path2555" style="stroke-linejoin:round;stroke:url(#linearGradient2416);stroke-linecap:round;stroke-width:1.0037;fill:url(#radialGradient2414)" d="m24 5.5018c-10.758 0-19.498 8.7402-19.498 19.498-0.0002 10.758 8.74 19.498 19.498 19.498s19.498-8.74 19.498-19.498-8.74-19.498-19.498-19.498z"/>
|
||||
<path id="path8655" style="opacity:.4;stroke:url(#linearGradient2411);fill:none" d="m42.5 24.999c0 10.218-8.283 18.501-18.5 18.501s-18.5-8.283-18.5-18.501c0-10.217 8.283-18.499 18.5-18.499s18.5 8.282 18.5 18.499z"/>
|
||||
</g>
|
||||
<g id="g3243" transform="translate(51.075 .56862)">
|
||||
<path id="path3295" style="opacity:.2" d="m-29.451 12.554c0.563 5.5 1.208 10.961 1.687 16.482h1.53c0.397-5.302 1.038-10.571 1.501-15.867 0.236-1.254-0.408-2.742-1.732-3.047-1.308-0.3824-2.77 0.565-2.944 1.918-0.029 0.17-0.042 0.342-0.042 0.514zm-0.167 22.359c-0.059 1.637 1.742 2.92 3.28 2.401 1.489-0.38 2.274-2.252 1.51-3.583-0.683-1.375-2.687-1.829-3.84-0.776-0.582 0.479-0.968 1.194-0.95 1.958z"/>
|
||||
<path id="text2315" style="fill:#fff" d="m-29.451 13.555c0.563 5.499 1.208 10.96 1.687 16.481h1.53c0.397-5.301 1.038-10.571 1.501-15.866 0.236-1.254-0.408-2.743-1.732-3.048-1.308-0.382-2.77 0.565-2.944 1.918-0.029 0.17-0.042 0.342-0.042 0.515zm-0.167 22.358c-0.059 1.637 1.742 2.921 3.28 2.402 1.489-0.381 2.274-2.253 1.51-3.584-0.683-1.375-2.687-1.828-3.84-0.776-0.582 0.479-0.968 1.194-0.95 1.958z"/>
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
After Width: | Height: | Size: 3.2 KiB |
@ -113,12 +113,9 @@ OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
# use file-extension c for "c-only"-files
|
||||
|
||||
MODNAMES = $(notdir ${MODULES})
|
||||
|
||||
ifndef TESTAPP
|
||||
## MODULES
|
||||
SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
SRC += ${OUTDIR}/InitMods.c
|
||||
## OPENPILOT CORE:
|
||||
SRC += ${OPMODULEDIR}/System/systemmod.c
|
||||
SRC += $(OPSYSTEM)/coptercontrol.c
|
||||
@ -490,7 +487,7 @@ LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE)))
|
||||
DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE)))
|
||||
|
||||
# Default target.
|
||||
all: gencode build
|
||||
all: build
|
||||
|
||||
ifeq ($(LOADFORMAT),ihex)
|
||||
build: elf hex lss sym
|
||||
@ -506,18 +503,6 @@ endif
|
||||
endif
|
||||
endif
|
||||
|
||||
# Generate intermediate code for objects
|
||||
gencode: ${OUTDIR}/InitMods.c
|
||||
|
||||
# Generate code for module initialization
|
||||
${OUTDIR}/InitMods.c: Makefile
|
||||
@echo $(MSG_MODINIT) $(call toprel, $@)
|
||||
@echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c
|
||||
|
||||
# Generate code for PyMite
|
||||
#$(OUTDIR)/pmlib_img.c $(OUTDIR)/pmlib_nat.c $(OUTDIR)/pmlibusr_img.c $(OUTDIR)/pmlibusr_nat.c $(OUTDIR)/pmfeatures.h: $(wildcard $(PYMITELIB)/*.py) $(wildcard $(PYMITEPLAT)/*.py) $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(FLIGHTPLANS)/*.py)
|
||||
# @echo $(MSG_PYMITEINIT) $(call toprel, $@)
|
||||
@ -624,4 +609,4 @@ else
|
||||
endif
|
||||
|
||||
# Listing of phony targets.
|
||||
.PHONY : all build clean clean_list gencode install
|
||||
.PHONY : all build clean clean_list install
|
||||
|
@ -42,18 +42,16 @@
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Prototype of generated InitModules() function */
|
||||
extern void InitModules(void);
|
||||
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void Stack_Change(void);
|
||||
|
||||
/**
|
||||
* OpenPilot Main function:
|
||||
*
|
||||
* Initialize PiOS<BR>
|
||||
* Create the "System" task (SystemModInitializein Modules/System/systemmod.c) <BR>
|
||||
* Start FreeRTOS Scheduler (vTaskStartScheduler)<BR>
|
||||
* Start FreeRTOS Scheduler (vTaskStartScheduler) (Now handled by caller)
|
||||
* If something goes wrong, blink LED1 and LED2 every 100ms
|
||||
*
|
||||
*/
|
||||
@ -65,40 +63,32 @@ int main()
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
|
||||
/* Initialize the system thread */
|
||||
SystemModInitialize();
|
||||
|
||||
/* Start the FreeRTOS scheduler */
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
/* If we do get here, it will most likely be because we ran out of heap space. */
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize the hardware, libraries and modules (called by the System thread in systemmod.c)
|
||||
*/
|
||||
void OpenPilotInit()
|
||||
{
|
||||
|
||||
/* Architecture dependant Hardware and
|
||||
* core subsystem initialisation
|
||||
* (see pios_board.c for your arch)
|
||||
* */
|
||||
|
||||
PIOS_Board_Init();
|
||||
|
||||
#ifdef ERASE_FLASH
|
||||
PIOS_Flash_W25X_EraseChip();
|
||||
while(TRUE){};
|
||||
#endif
|
||||
|
||||
/* Initialize modules */
|
||||
InitModules();
|
||||
}
|
||||
MODULE_INITIALISE_ALL
|
||||
|
||||
/* swap the stack to use the IRQ stack */
|
||||
Stack_Change();
|
||||
|
||||
/* Start the FreeRTOS scheduler which should never returns.*/
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
PIOS_LED_Off(LED1); \
|
||||
for(;;) { \
|
||||
PIOS_LED_Toggle(LED1); \
|
||||
PIOS_DELAY_WaitmS(100); \
|
||||
};
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -30,7 +30,7 @@
|
||||
#define configTICK_RATE_HZ ( ( portTickType ) 1000 )
|
||||
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )
|
||||
#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 48 )
|
||||
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 14 * 1024 ) )
|
||||
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 55 * 256) )
|
||||
#define configMAX_TASK_NAME_LEN ( 16 )
|
||||
#define configUSE_TRACE_FACILITY 0
|
||||
#define configUSE_16_BIT_TICKS 0
|
||||
@ -71,6 +71,10 @@ configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest
|
||||
NVIC value of 255. */
|
||||
#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32)
|
||||
#define CHECK_IRQ_STACK
|
||||
#endif
|
||||
|
||||
/* Enable run time stats collection */
|
||||
//#if defined(DEBUG)
|
||||
#define configGENERATE_RUN_TIME_STATS 1
|
||||
@ -83,6 +87,7 @@ do {\
|
||||
#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004)/* DWT_CYCCNT */
|
||||
//#endif
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
@ -88,13 +88,15 @@
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 220
|
||||
#define HEAP_LIMIT_CRITICAL 40
|
||||
#define IRQSTACK_LIMIT_WARNING 100
|
||||
#define IRQSTACK_LIMIT_CRITICAL 60
|
||||
#define CPULOAD_LIMIT_WARNING 85
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
/* Task stack sizes */
|
||||
#define PIOS_ACTUATOR_STACK_SIZE 1020
|
||||
#define PIOS_MANUAL_STACK_SIZE 724
|
||||
#define PIOS_SYSTEM_STACK_SIZE 560
|
||||
#define PIOS_SYSTEM_STACK_SIZE 460
|
||||
#define PIOS_STABILIZATION_STACK_SIZE 524
|
||||
#define PIOS_TELEM_STACK_SIZE 500
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 96
|
||||
|
@ -434,7 +434,7 @@ static const struct pios_usart_cfg pios_usart_spektrum_flexi_cfg = {
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
@ -442,7 +442,7 @@ static const struct pios_usart_cfg pios_usart_spektrum_flexi_cfg = {
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
|
@ -69,7 +69,7 @@ static void ahrscommsTask(void *parameters);
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AHRSCommsInitialize(void)
|
||||
int32_t AHRSCommsStart(void)
|
||||
{
|
||||
// Start main task
|
||||
xTaskCreate(ahrscommsTask, (signed char *)"AHRSComms", STACK_SIZE, NULL, TASK_PRIORITY, &taskHandle);
|
||||
@ -79,6 +79,17 @@ int32_t AHRSCommsInitialize(void)
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AHRSCommsInitialize(void)
|
||||
{
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(AHRSCommsInitialize, 0, AHRSCommsStart, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
|
||||
/**
|
||||
* Module thread, should not return.
|
||||
*/
|
||||
|
@ -85,6 +85,19 @@ typedef struct {
|
||||
int8_t matrix[5];
|
||||
} __attribute__((packed)) Mixer_t;
|
||||
|
||||
/**
|
||||
* @brief Module initialization
|
||||
* @return 0
|
||||
*/
|
||||
int32_t ActuatorStart()
|
||||
{
|
||||
// Start main task
|
||||
xTaskCreate(actuatorTask, (signed char*)"Actuator", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ACTUATOR, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_ACTUATOR);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Module initialization
|
||||
@ -100,14 +113,10 @@ int32_t ActuatorInitialize()
|
||||
|
||||
// If settings change, update the output rate
|
||||
ActuatorSettingsConnectCallback(actuator_update_rate);
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(actuatorTask, (signed char*)"Actuator", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ACTUATOR, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_ACTUATOR);
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(ActuatorInitialize, 0, ActuatorStart, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
|
||||
/**
|
||||
* @brief Main Actuator module task
|
||||
|
@ -37,6 +37,7 @@
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "altitude.h"
|
||||
#include "baroaltitude.h" // object that will be updated by the module
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
#include "sonaraltitude.h" // object that will be updated by the module
|
||||
@ -66,12 +67,22 @@ static void altitudeTask(void *parameters);
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AltitudeInitialize()
|
||||
int32_t AltitudeStart()
|
||||
{
|
||||
// Start main task
|
||||
xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AltitudeInitialize()
|
||||
{
|
||||
|
||||
// init down-sampling data
|
||||
alt_ds_temp = 0;
|
||||
alt_ds_pres = 0;
|
||||
@ -79,7 +90,7 @@ int32_t AltitudeInitialize()
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(AltitudeInitialize, 0, AltitudeStart, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
/**
|
||||
* Module thread, should not return.
|
||||
*/
|
||||
|
@ -3,7 +3,7 @@
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup Attitude Copter Control Attitude Estimation
|
||||
* @brief Acquires sensor data and computes attitude estimate
|
||||
* @brief Acquires sensor data and computes attitude estimate
|
||||
* Specifically updates the the @ref AttitudeActual "AttitudeActual" and @ref AttitudeRaw "AttitudeRaw" settings objects
|
||||
* @{
|
||||
*
|
||||
@ -89,6 +89,22 @@ static float q[4] = {1,0,0,0};
|
||||
static float R[3][3];
|
||||
static int8_t rotate = 0;
|
||||
static bool zero_during_arming = false;
|
||||
static bool bias_correct_gyro = true;
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AttitudeStart(void)
|
||||
{
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(AttitudeTask, (signed char *)"Attitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ATTITUDE, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
@ -104,91 +120,107 @@ int32_t AttitudeInitialize(void)
|
||||
attitude.q3 = 0;
|
||||
attitude.q4 = 0;
|
||||
AttitudeActualSet(&attitude);
|
||||
|
||||
|
||||
// Cannot trust the values to init right above if BL runs
|
||||
gyro_correct_int[0] = 0;
|
||||
gyro_correct_int[1] = 0;
|
||||
gyro_correct_int[2] = 0;
|
||||
|
||||
q[0] = 1;
|
||||
q[1] = 0;
|
||||
q[2] = 0;
|
||||
q[3] = 0;
|
||||
for(uint8_t i = 0; i < 3; i++)
|
||||
for(uint8_t j = 0; j < 3; j++)
|
||||
R[i][j] = 0;
|
||||
|
||||
// Create queue for passing gyro data, allow 2 back samples in case
|
||||
gyro_queue = xQueueCreate(1, sizeof(float) * 4);
|
||||
if(gyro_queue == NULL)
|
||||
if(gyro_queue == NULL)
|
||||
return -1;
|
||||
|
||||
|
||||
PIOS_ADC_SetQueue(gyro_queue);
|
||||
|
||||
|
||||
AttitudeSettingsConnectCallback(&settingsUpdatedCb);
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(AttitudeTask, (signed char *)"Attitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ATTITUDE, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(AttitudeInitialize, 0, AttitudeStart, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
|
||||
/**
|
||||
* Module thread, should not return.
|
||||
*/
|
||||
static void AttitudeTask(void *parameters)
|
||||
{
|
||||
|
||||
uint8_t init = 0;
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE);
|
||||
|
||||
PIOS_ADC_Config((PIOS_ADC_RATE / 1000.0f) * UPDATE_RATE);
|
||||
|
||||
// Keep flash CS pin high while talking accel
|
||||
PIOS_FLASH_DISABLE;
|
||||
PIOS_FLASH_DISABLE;
|
||||
PIOS_ADXL345_Init();
|
||||
|
||||
zero_during_arming = false;
|
||||
|
||||
|
||||
// Force settings update to make sure rotation loaded
|
||||
settingsUpdatedCb(AttitudeSettingsHandle());
|
||||
|
||||
// Main task loop
|
||||
while (1) {
|
||||
|
||||
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
|
||||
if(xTaskGetTickCount() < 7000) {
|
||||
// Force settings update to make sure rotation loaded
|
||||
settingsUpdatedCb(AttitudeSettingsHandle());
|
||||
if((xTaskGetTickCount() < 7000) && (xTaskGetTickCount() > 1000)) {
|
||||
// For first 7 seconds use accels to get gyro bias
|
||||
accelKp = 1;
|
||||
accelKi = 0.9;
|
||||
yawBiasRate = 0.23;
|
||||
init = 0;
|
||||
}
|
||||
}
|
||||
else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) {
|
||||
accelKp = 1;
|
||||
accelKi = 0.9;
|
||||
yawBiasRate = 0.23;
|
||||
init = 0;
|
||||
init = 0;
|
||||
} else if (init == 0) {
|
||||
settingsUpdatedCb(AttitudeSettingsHandle());
|
||||
// Reload settings (all the rates)
|
||||
AttitudeSettingsAccelKiGet(&accelKi);
|
||||
AttitudeSettingsAccelKpGet(&accelKp);
|
||||
AttitudeSettingsYawBiasRateGet(&yawBiasRate);
|
||||
init = 1;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE);
|
||||
|
||||
|
||||
AttitudeRawData attitudeRaw;
|
||||
AttitudeRawGet(&attitudeRaw);
|
||||
updateSensors(&attitudeRaw);
|
||||
AttitudeRawGet(&attitudeRaw);
|
||||
updateSensors(&attitudeRaw);
|
||||
updateAttitude(&attitudeRaw);
|
||||
AttitudeRawSet(&attitudeRaw);
|
||||
AttitudeRawSet(&attitudeRaw);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
{
|
||||
static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
{
|
||||
struct pios_adxl345_data accel_data;
|
||||
float gyro[4];
|
||||
|
||||
|
||||
// Only wait the time for two nominal updates before setting an alarm
|
||||
if(xQueueReceive(gyro_queue, (void * const) gyro, UPDATE_RATE * 2) == errQUEUE_EMPTY) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
// First sample is temperature
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_X] = -(gyro[1] - GYRO_NEUTRAL) * gyroGain;
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Y] = (gyro[2] - GYRO_NEUTRAL) * gyroGain;
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] = -(gyro[3] - GYRO_NEUTRAL) * gyroGain;
|
||||
|
||||
|
||||
int32_t x = 0;
|
||||
int32_t y = 0;
|
||||
int32_t z = 0;
|
||||
@ -203,9 +235,9 @@ static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
} while ( (i < 32) && (samples_remaining > 0) );
|
||||
attitudeRaw->gyrotemp[0] = samples_remaining;
|
||||
attitudeRaw->gyrotemp[1] = i;
|
||||
|
||||
|
||||
float accel[3] = {(float) x / i, (float) y / i, (float) z / i};
|
||||
|
||||
|
||||
if(rotate) {
|
||||
// TODO: rotate sensors too so stabilization is well behaved
|
||||
float vec_out[3];
|
||||
@ -221,68 +253,68 @@ static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
attitudeRaw->accels[0] = accel[0];
|
||||
attitudeRaw->accels[1] = accel[1];
|
||||
attitudeRaw->accels[2] = accel[2];
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Scale accels and correct bias
|
||||
attitudeRaw->accels[ATTITUDERAW_ACCELS_X] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_X] - accelbias[0]) * 0.004f * 9.81f;
|
||||
attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] - accelbias[1]) * 0.004f * 9.81f;
|
||||
attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] - accelbias[2]) * 0.004f * 9.81f;
|
||||
|
||||
// Applying integral component here so it can be seen on the gyros and correct bias
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_X] += gyro_correct_int[0];
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Y] += gyro_correct_int[1];
|
||||
|
||||
// Because most crafts wont get enough information from gravity to zero yaw gyro
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] += gyro_correct_int[2];
|
||||
gyro_correct_int[2] += - attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] * yawBiasRate;
|
||||
|
||||
if(bias_correct_gyro) {
|
||||
// Applying integral component here so it can be seen on the gyros and correct bias
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_X] += gyro_correct_int[0];
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Y] += gyro_correct_int[1];
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] += gyro_correct_int[2];
|
||||
}
|
||||
|
||||
// Because most crafts wont get enough information from gravity to zero yaw gyro, we try
|
||||
// and make it average zero (weakly)
|
||||
gyro_correct_int[2] += - attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] * yawBiasRate;
|
||||
}
|
||||
|
||||
static void updateAttitude(AttitudeRawData * attitudeRaw)
|
||||
{
|
||||
float dT;
|
||||
portTickType thisSysTime = xTaskGetTickCount();
|
||||
static portTickType lastSysTime = 0;
|
||||
static portTickType thisSysTime;
|
||||
|
||||
static float dT = 0;
|
||||
|
||||
thisSysTime = xTaskGetTickCount();
|
||||
if(thisSysTime > lastSysTime) // reuse dt in case of wraparound
|
||||
dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f;
|
||||
|
||||
dT = (thisSysTime == lastSysTime) ? 0.001 : (portMAX_DELAY & (thisSysTime - lastSysTime)) / portTICK_RATE_MS / 1000.0f;
|
||||
lastSysTime = thisSysTime;
|
||||
|
||||
|
||||
// Bad practice to assume structure order, but saves memory
|
||||
float gyro[3];
|
||||
gyro[0] = attitudeRaw->gyros[0];
|
||||
gyro[1] = attitudeRaw->gyros[1];
|
||||
gyro[2] = attitudeRaw->gyros[2];
|
||||
|
||||
|
||||
{
|
||||
float * accels = attitudeRaw->accels;
|
||||
float grot[3];
|
||||
float accel_err[3];
|
||||
|
||||
|
||||
// Rotate gravity to body frame and cross with accels
|
||||
grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2]));
|
||||
grot[1] = -(2 * (q[2] * q[3] + q[0] * q[1]));
|
||||
grot[2] = -(q[0] * q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]);
|
||||
CrossProduct((const float *) accels, (const float *) grot, accel_err);
|
||||
|
||||
// Account for accel magnitude
|
||||
|
||||
// Account for accel magnitude
|
||||
float accel_mag = sqrt(accels[0]*accels[0] + accels[1]*accels[1] + accels[2]*accels[2]);
|
||||
accel_err[0] /= accel_mag;
|
||||
accel_err[1] /= accel_mag;
|
||||
accel_err[2] /= accel_mag;
|
||||
|
||||
// Accumulate integral of error. Scale here so that units are (rad/s) but Ki has units of s
|
||||
|
||||
// Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s
|
||||
gyro_correct_int[0] += accel_err[0] * accelKi;
|
||||
gyro_correct_int[1] += accel_err[1] * accelKi;
|
||||
//gyro_correct_int[2] += accel_err[2] * settings.AccelKI * dT;
|
||||
|
||||
|
||||
// Correct rates based on error, integral component dealt with in updateSensors
|
||||
gyro[0] += accel_err[0] * accelKp / dT;
|
||||
gyro[1] += accel_err[1] * accelKp / dT;
|
||||
gyro[2] += accel_err[2] * accelKp / dT;
|
||||
}
|
||||
|
||||
|
||||
{ // scoping variables to save memory
|
||||
// Work out time derivative from INSAlgo writeup
|
||||
// Also accounts for the fact that gyros are in deg/s
|
||||
@ -291,28 +323,37 @@ static void updateAttitude(AttitudeRawData * attitudeRaw)
|
||||
qdot[1] = (q[0] * gyro[0] - q[3] * gyro[1] + q[2] * gyro[2]) * dT * M_PI / 180 / 2;
|
||||
qdot[2] = (q[3] * gyro[0] + q[0] * gyro[1] - q[1] * gyro[2]) * dT * M_PI / 180 / 2;
|
||||
qdot[3] = (-q[2] * gyro[0] + q[1] * gyro[1] + q[0] * gyro[2]) * dT * M_PI / 180 / 2;
|
||||
|
||||
|
||||
// Take a time step
|
||||
q[0] = q[0] + qdot[0];
|
||||
q[1] = q[1] + qdot[1];
|
||||
q[2] = q[2] + qdot[2];
|
||||
q[3] = q[3] + qdot[3];
|
||||
}
|
||||
|
||||
|
||||
// Renomalize
|
||||
float qmag = sqrt(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]);
|
||||
q[0] = q[0] / qmag;
|
||||
q[1] = q[1] / qmag;
|
||||
q[2] = q[2] / qmag;
|
||||
q[3] = q[3] / qmag;
|
||||
|
||||
|
||||
// If quaternion has become inappropriately short or is nan reinit.
|
||||
// THIS SHOULD NEVER ACTUALLY HAPPEN
|
||||
if((fabs(qmag) < 1e-3) || (qmag != qmag)) {
|
||||
q[0] = 1;
|
||||
q[1] = 0;
|
||||
q[2] = 0;
|
||||
q[3] = 0;
|
||||
}
|
||||
|
||||
AttitudeActualData attitudeActual;
|
||||
AttitudeActualGet(&attitudeActual);
|
||||
|
||||
|
||||
quat_copy(q, &attitudeActual.q1);
|
||||
|
||||
|
||||
// Convert into eueler degrees (makes assumptions about RPY order)
|
||||
Quaternion2RPY(&attitudeActual.q1,&attitudeActual.Roll);
|
||||
Quaternion2RPY(&attitudeActual.q1,&attitudeActual.Roll);
|
||||
|
||||
AttitudeActualSet(&attitudeActual);
|
||||
}
|
||||
@ -320,36 +361,41 @@ static void updateAttitude(AttitudeRawData * attitudeRaw)
|
||||
static void settingsUpdatedCb(UAVObjEvent * objEv) {
|
||||
AttitudeSettingsData attitudeSettings;
|
||||
AttitudeSettingsGet(&attitudeSettings);
|
||||
|
||||
|
||||
|
||||
|
||||
accelKp = attitudeSettings.AccelKp;
|
||||
accelKi = attitudeSettings.AccelKi;
|
||||
accelKi = attitudeSettings.AccelKi;
|
||||
yawBiasRate = attitudeSettings.YawBiasRate;
|
||||
gyroGain = attitudeSettings.GyroGain;
|
||||
|
||||
|
||||
zero_during_arming = attitudeSettings.ZeroDuringArming == ATTITUDESETTINGS_ZERODURINGARMING_TRUE;
|
||||
|
||||
bias_correct_gyro = attitudeSettings.BiasCorrectGyro == ATTITUDESETTINGS_BIASCORRECTGYRO_TRUE;
|
||||
|
||||
accelbias[0] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_X];
|
||||
accelbias[1] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Y];
|
||||
accelbias[2] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Z];
|
||||
|
||||
|
||||
gyro_correct_int[0] = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_X] / 100.0f;
|
||||
gyro_correct_int[1] = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_Y] / 100.0f;
|
||||
gyro_correct_int[2] = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_Z] / 100.0f;
|
||||
|
||||
// Indicates not to expend cycles on rotation
|
||||
if(attitudeSettings.BoardRotation[0] == 0 && attitudeSettings.BoardRotation[1] == 0 &&
|
||||
attitudeSettings.BoardRotation[2] == 0) {
|
||||
rotate = 0;
|
||||
|
||||
|
||||
// Shouldn't be used but to be safe
|
||||
float rotationQuat[4] = {1,0,0,0};
|
||||
Quaternion2R(rotationQuat, R);
|
||||
} else {
|
||||
float rotationQuat[4];
|
||||
const float rpy[3] = {attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_ROLL],
|
||||
attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_PITCH],
|
||||
const float rpy[3] = {attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_ROLL],
|
||||
attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_PITCH],
|
||||
attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_YAW]};
|
||||
RPY2Quaternion(rpy, rotationQuat);
|
||||
Quaternion2R(rotationQuat, R);
|
||||
rotate = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
/**
|
||||
* @}
|
||||
|
@ -75,6 +75,7 @@ static void onTimer(UAVObjEvent* ev);
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
MODULE_INITCALL(BatteryInitialize, 0, 0, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
int32_t BatteryInitialize(void)
|
||||
{
|
||||
static UAVObjEvent ev;
|
||||
|
@ -49,9 +49,14 @@
|
||||
#include "examplemodperiodic.h"
|
||||
#include "examplemodthread.h"
|
||||
|
||||
void ExampleInitialize(void)
|
||||
void ExampleStart(void)
|
||||
{
|
||||
ExampleModEventInitialize();
|
||||
ExampleModPeriodicInitialize();
|
||||
ExampleModThreadInitialize();
|
||||
}
|
||||
|
||||
void ExampleInitialize(void)
|
||||
{
|
||||
ExampleModEventInitialize();
|
||||
}
|
||||
MODULE_INITCALL(ExampleInitialize, 0, ExampleStart, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
|
@ -88,7 +88,7 @@ static void resetTask(UAVObjEvent *);
|
||||
* \note
|
||||
*
|
||||
*/
|
||||
|
||||
MODULE_INITCALL(FirmwareIAPInitialize, 0, 0, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
int32_t FirmwareIAPInitialize()
|
||||
{
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
@ -100,7 +100,7 @@ int32_t FirmwareIAPInitialize()
|
||||
data.ArmReset=0;
|
||||
data.crc = 0;
|
||||
FirmwareIAPObjSet( &data );
|
||||
FirmwareIAPObjConnectCallback( &FirmwareIAPCallback );
|
||||
if(bdinfo->magic==PIOS_BOARD_INFO_BLOB_MAGIC) FirmwareIAPObjConnectCallback( &FirmwareIAPCallback );
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -31,6 +31,7 @@
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "pm.h"
|
||||
#include "flightplan.h"
|
||||
#include "flightplanstatus.h"
|
||||
#include "flightplancontrol.h"
|
||||
#include "flightplansettings.h"
|
||||
@ -53,6 +54,20 @@ static void objectUpdatedCb(UAVObjEvent * ev);
|
||||
// External variables (temporary, TODO: this will be loaded from the SD card)
|
||||
extern unsigned char usrlib_img[];
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
int32_t FlightPlanStart()
|
||||
{
|
||||
taskHandle = NULL;
|
||||
|
||||
// Start VM thread
|
||||
xTaskCreate(flightPlanTask, (signed char *)"FlightPlan", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_FLIGHTPLAN, taskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
@ -69,13 +84,9 @@ int32_t FlightPlanInitialize()
|
||||
// Listen for FlightPlanControl updates
|
||||
FlightPlanControlConnectQueue(queue);
|
||||
|
||||
// Start VM thread
|
||||
xTaskCreate(flightPlanTask, (signed char *)"FlightPlan", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_FLIGHTPLAN, taskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(FlightPlanInitialize, 0, FlightPlanStart, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
/**
|
||||
* Module task
|
||||
*/
|
||||
|
@ -109,19 +109,27 @@ static uint32_t numParsingErrors;
|
||||
* \return 0 on success
|
||||
*/
|
||||
|
||||
int32_t GPSInitialize(void)
|
||||
int32_t GPSStart(void)
|
||||
{
|
||||
signed portBASE_TYPE xReturn;
|
||||
|
||||
// TODO: Get gps settings object
|
||||
gpsPort = PIOS_COM_GPS;
|
||||
|
||||
// Start gps task
|
||||
xReturn = xTaskCreate(gpsTask, (signed char *)"GPS", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &gpsTaskHandle);
|
||||
xTaskCreate(gpsTask, (signed char *)"GPS", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &gpsTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_GPS, gpsTaskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
/**
|
||||
* Initialise the gps module
|
||||
* \return -1 if initialisation failed
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t GPSInitialize(void)
|
||||
{
|
||||
// TODO: Get gps settings object
|
||||
gpsPort = PIOS_COM_GPS;
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(GPSInitialize, 0, GPSStart, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
|
||||
// ****************
|
||||
/**
|
||||
|
@ -78,6 +78,19 @@ static void updateVtolDesiredVelocity();
|
||||
static void manualSetDesiredVelocity();
|
||||
static void updateVtolDesiredAttitude();
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t GuidanceStart()
|
||||
{
|
||||
// Start main task
|
||||
xTaskCreate(guidanceTask, (signed char *)"Guidance", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &guidanceTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_GUIDANCE, guidanceTaskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
@ -90,12 +103,9 @@ int32_t GuidanceInitialize()
|
||||
// Listen for updates.
|
||||
AttitudeRawConnectQueue(queue);
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(guidanceTask, (signed char *)"Guidance", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &guidanceTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_GUIDANCE, guidanceTaskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(GuidanceInitialize, 0, GuidanceStart, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
|
||||
static float northVelIntegral = 0;
|
||||
static float eastVelIntegral = 0;
|
||||
|
@ -27,5 +27,5 @@
|
||||
#define EXAMPLEMODPERIODIC_H
|
||||
|
||||
int32_t ExampleModPeriodicInitialize();
|
||||
|
||||
int32_t GuidanceInitialize(void);
|
||||
#endif // EXAMPLEMODPERIODIC_H
|
||||
|
@ -1,7 +1,7 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @{
|
||||
* @addtogroup ManualControlModule Manual Control Module
|
||||
* @{
|
||||
*
|
||||
@ -45,4 +45,64 @@ typedef enum {FLIGHTMODE_UNDEFINED = 0, FLIGHTMODE_MANUAL = 1, FLIGHTMODE_STABIL
|
||||
|
||||
int32_t ManualControlInitialize();
|
||||
|
||||
|
||||
/*
|
||||
* These are assumptions we make in the flight code about the order of settings and their consistency between
|
||||
* objects. Please keep this synchronized to the UAVObjects
|
||||
*/
|
||||
#define assumptions1 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
#define assumptions3 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
#define assumptions5 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
#define ARMING_CHANNEL_ROLL 0
|
||||
#define ARMING_CHANNEL_PITCH 1
|
||||
#define ARMING_CHANNEL_YAW 2
|
||||
|
||||
#define assumptions7 ( \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_ROLL) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_ROLL) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHFORWARD -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_PITCH) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHAFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_PITCH) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_YAW) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_YAW) \
|
||||
)
|
||||
|
||||
#define assumptions8 ( \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHFORWARD -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHAFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) \
|
||||
)
|
||||
|
||||
#define assumptions_flightmode ( \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL == (int) FLIGHTSTATUS_FLIGHTMODE_MANUAL) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED1) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED2) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL == (int) FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD == (int) FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) \
|
||||
)
|
||||
|
||||
#endif // MANUALCONTROL_H
|
||||
|
@ -87,76 +87,32 @@ static uint32_t timeDifferenceMs(portTickType start_time, portTickType end_time)
|
||||
static bool okToArm(void);
|
||||
static bool validInputRange(int16_t min, int16_t max, uint16_t value);
|
||||
|
||||
#define assumptions1 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
#define assumptions3 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
#define assumptions5 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
|
||||
|
||||
#define ARMING_CHANNEL_ROLL 0
|
||||
#define ARMING_CHANNEL_PITCH 1
|
||||
#define ARMING_CHANNEL_YAW 2
|
||||
|
||||
#define assumptions7 ( \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_ROLL) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_ROLL) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHFORWARD -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_PITCH) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHAFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_PITCH) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_YAW) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_YAW) \
|
||||
)
|
||||
|
||||
#define assumptions8 ( \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHFORWARD -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHAFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) \
|
||||
)
|
||||
|
||||
|
||||
#define assumptions_flightmode ( \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL == (int) FLIGHTSTATUS_FLIGHTMODE_MANUAL) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED1) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED2) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL == (int) FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD == (int) FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) \
|
||||
)
|
||||
|
||||
#define assumptions (assumptions1 && assumptions3 && assumptions5 && assumptions7 && assumptions8 && assumptions_flightmode)
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
int32_t ManualControlStart()
|
||||
{
|
||||
/* Check the assumptions about uavobject enum's are correct */
|
||||
if(!assumptions)
|
||||
return -1;
|
||||
// Start main task
|
||||
xTaskCreate(manualControlTask, (signed char *)"ManualControl", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_MANUALCONTROL, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
int32_t ManualControlInitialize()
|
||||
{
|
||||
/* Check the assumptions about uavobject enum's are correct */
|
||||
if(!assumptions)
|
||||
return -1;
|
||||
// Start main task
|
||||
xTaskCreate(manualControlTask, (signed char *)"ManualControl", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_MANUALCONTROL, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL);
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(ManualControlInitialize, 0, ManualControlStart, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
|
||||
/**
|
||||
* Module task
|
||||
@ -295,14 +251,14 @@ static void manualControlTask(void *parameters)
|
||||
ManualControlCommandSet(&cmd);
|
||||
|
||||
}
|
||||
|
||||
|
||||
} else {
|
||||
ManualControlCommandGet(&cmd); /* Under GCS control */
|
||||
}
|
||||
|
||||
|
||||
FlightStatusGet(&flightStatus);
|
||||
|
||||
|
||||
// Depending on the mode update the Stabilization or Actuator objects
|
||||
switch(PARSE_FLIGHT_MODE(flightStatus.FlightMode)) {
|
||||
case FLIGHTMODE_UNDEFINED:
|
||||
@ -318,11 +274,11 @@ static void manualControlTask(void *parameters)
|
||||
case FLIGHTMODE_GUIDANCE:
|
||||
// TODO: Implement
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void updateActuatorDesired(ManualControlCommandData * cmd)
|
||||
static void updateActuatorDesired(ManualControlCommandData * cmd)
|
||||
{
|
||||
ActuatorDesiredData actuator;
|
||||
ActuatorDesiredGet(&actuator);
|
||||
@ -330,17 +286,17 @@ static void updateActuatorDesired(ManualControlCommandData * cmd)
|
||||
actuator.Pitch = cmd->Pitch;
|
||||
actuator.Yaw = cmd->Yaw;
|
||||
actuator.Throttle = (cmd->Throttle < 0) ? -1 : cmd->Throttle;
|
||||
ActuatorDesiredSet(&actuator);
|
||||
ActuatorDesiredSet(&actuator);
|
||||
}
|
||||
|
||||
static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualControlSettingsData * settings)
|
||||
{
|
||||
StabilizationDesiredData stabilization;
|
||||
StabilizationDesiredGet(&stabilization);
|
||||
|
||||
|
||||
StabilizationSettingsData stabSettings;
|
||||
StabilizationSettingsGet(&stabSettings);
|
||||
|
||||
|
||||
uint8_t * stab_settings;
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
@ -357,30 +313,36 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon
|
||||
default:
|
||||
// Major error, this should not occur because only enter this block when one of these is true
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
return;
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
// TOOD: Add assumption about order of stabilization desired and manual control stabilization mode fields having same order
|
||||
stabilization.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = stab_settings[0];
|
||||
stabilization.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = stab_settings[1];
|
||||
stabilization.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = stab_settings[2];
|
||||
|
||||
|
||||
stabilization.Roll = (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Roll :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Roll * stabSettings.RollMax :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
|
||||
0; // this is an invalid mode
|
||||
;
|
||||
stabilization.Pitch = (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Pitch :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Pitch * stabSettings.PitchMax :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
|
||||
0; // this is an invalid mode
|
||||
|
||||
stabilization.Yaw = (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Yaw :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? fmod(cmd->Yaw * 180.0, 360) :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Yaw * stabSettings.YawMax :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
|
||||
0; // this is an invalid mode
|
||||
|
||||
stabilization.Throttle = (cmd->Throttle < 0) ? -1 : cmd->Throttle;
|
||||
|
||||
stabilization.Throttle = (cmd->Throttle < 0) ? -1 : cmd->Throttle;
|
||||
StabilizationDesiredSet(&stabilization);
|
||||
}
|
||||
|
||||
@ -466,11 +428,11 @@ static void setArmedIfChanged(uint8_t val) {
|
||||
* @param[out] cmd The structure to set the armed in
|
||||
* @param[in] settings Settings indicating the necessary position
|
||||
*/
|
||||
static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData * settings)
|
||||
{
|
||||
static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData * settings)
|
||||
{
|
||||
|
||||
bool lowThrottle = cmd->Throttle <= 0;
|
||||
|
||||
|
||||
if (settings->Arming == MANUALCONTROLSETTINGS_ARMING_ALWAYSDISARMED) {
|
||||
// In this configuration we always disarm
|
||||
setArmedIfChanged(FLIGHTSTATUS_ARMED_DISARMED);
|
||||
@ -478,7 +440,7 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData
|
||||
// Not really needed since this function not called when disconnected
|
||||
if (cmd->Connected == MANUALCONTROLCOMMAND_CONNECTED_FALSE)
|
||||
return;
|
||||
|
||||
|
||||
// The throttle is not low, in case we where arming or disarming, abort
|
||||
if (!lowThrottle) {
|
||||
switch(armState) {
|
||||
@ -495,20 +457,20 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
// The rest of these cases throttle is low
|
||||
if (settings->Arming == MANUALCONTROLSETTINGS_ARMING_ALWAYSARMED) {
|
||||
// In this configuration, we go into armed state as soon as the throttle is low, never disarm
|
||||
setArmedIfChanged(FLIGHTSTATUS_ARMED_ARMED);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
// When the configuration is not "Always armed" and no "Always disarmed",
|
||||
// the state will not be changed when the throttle is not low
|
||||
static portTickType armedDisarmStart;
|
||||
float armingInputLevel = 0;
|
||||
|
||||
|
||||
// Calc channel see assumptions7
|
||||
int8_t sign = ((settings->Arming-MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2) ? -1 : 1;
|
||||
switch ( (settings->Arming-MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 ) {
|
||||
@ -516,26 +478,26 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData
|
||||
case ARMING_CHANNEL_PITCH: armingInputLevel = sign * cmd->Pitch; break;
|
||||
case ARMING_CHANNEL_YAW: armingInputLevel = sign * cmd->Yaw; break;
|
||||
}
|
||||
|
||||
|
||||
bool manualArm = false;
|
||||
bool manualDisarm = false;
|
||||
|
||||
|
||||
if (armingInputLevel <= -ARMED_THRESHOLD)
|
||||
manualArm = true;
|
||||
else if (armingInputLevel >= +ARMED_THRESHOLD)
|
||||
manualDisarm = true;
|
||||
|
||||
|
||||
switch(armState) {
|
||||
case ARM_STATE_DISARMED:
|
||||
setArmedIfChanged(FLIGHTSTATUS_ARMED_DISARMED);
|
||||
|
||||
|
||||
// only allow arming if it's OK too
|
||||
if (manualArm && okToArm()) {
|
||||
armedDisarmStart = lastSysTime;
|
||||
armState = ARM_STATE_ARMING_MANUAL;
|
||||
}
|
||||
break;
|
||||
|
||||
|
||||
case ARM_STATE_ARMING_MANUAL:
|
||||
setArmedIfChanged(FLIGHTSTATUS_ARMED_ARMING);
|
||||
|
||||
@ -544,7 +506,7 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData
|
||||
else if (!manualArm)
|
||||
armState = ARM_STATE_DISARMED;
|
||||
break;
|
||||
|
||||
|
||||
case ARM_STATE_ARMED:
|
||||
// When we get here, the throttle is low,
|
||||
// we go immediately to disarming due to timeout, also when the disarming mechanism is not enabled
|
||||
@ -552,19 +514,19 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData
|
||||
armState = ARM_STATE_DISARMING_TIMEOUT;
|
||||
setArmedIfChanged(FLIGHTSTATUS_ARMED_ARMED);
|
||||
break;
|
||||
|
||||
|
||||
case ARM_STATE_DISARMING_TIMEOUT:
|
||||
// We get here when armed while throttle low, even when the arming timeout is not enabled
|
||||
if ((settings->ArmedTimeout != 0) && (timeDifferenceMs(armedDisarmStart, lastSysTime) > settings->ArmedTimeout))
|
||||
armState = ARM_STATE_DISARMED;
|
||||
|
||||
|
||||
// Switch to disarming due to manual control when needed
|
||||
if (manualDisarm) {
|
||||
armedDisarmStart = lastSysTime;
|
||||
armState = ARM_STATE_DISARMING_MANUAL;
|
||||
}
|
||||
break;
|
||||
|
||||
|
||||
case ARM_STATE_DISARMING_MANUAL:
|
||||
if (manualDisarm &&(timeDifferenceMs(armedDisarmStart, lastSysTime) > ARMED_TIME_MS))
|
||||
armState = ARM_STATE_DISARMED;
|
||||
@ -581,25 +543,25 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData
|
||||
* @param[in] settings The settings which indicate which position is which mode
|
||||
* @param[in] flightMode the value of the switch position
|
||||
*/
|
||||
static void processFlightMode(ManualControlSettingsData * settings, float flightMode)
|
||||
static void processFlightMode(ManualControlSettingsData * settings, float flightMode)
|
||||
{
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
|
||||
|
||||
uint8_t newMode;
|
||||
// Note here the code is ass
|
||||
if (flightMode < -FLIGHT_MODE_LIMIT)
|
||||
if (flightMode < -FLIGHT_MODE_LIMIT)
|
||||
newMode = settings->FlightModePosition[0];
|
||||
else if (flightMode > FLIGHT_MODE_LIMIT)
|
||||
else if (flightMode > FLIGHT_MODE_LIMIT)
|
||||
newMode = settings->FlightModePosition[2];
|
||||
else
|
||||
newMode = settings->FlightModePosition[1];
|
||||
|
||||
else
|
||||
newMode = settings->FlightModePosition[1];
|
||||
|
||||
if(flightStatus.FlightMode != newMode) {
|
||||
flightStatus.FlightMode = newMode;
|
||||
FlightStatusSet(&flightStatus);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
@ -621,3 +583,4 @@ bool validInputRange(int16_t min, int16_t max, uint16_t value)
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
@ -77,6 +77,14 @@ static xTaskHandle taskHandle;
|
||||
static StabilizationSettingsData settings;
|
||||
static xQueueHandle queue;
|
||||
float dT = 1;
|
||||
float gyro_alpha = 0;
|
||||
float gyro_filtered[3] = {0,0,0};
|
||||
float axis_lock_accum[3] = {0,0,0};
|
||||
uint8_t max_axis_lock = 0;
|
||||
uint8_t max_axislock_rate = 0;
|
||||
float weak_leveling_kp = 0;
|
||||
uint8_t weak_leveling_max = 0;
|
||||
|
||||
pid_type pids[PID_MAX];
|
||||
|
||||
// Private functions
|
||||
@ -89,27 +97,40 @@ static void SettingsUpdatedCb(UAVObjEvent * ev);
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
int32_t StabilizationInitialize()
|
||||
int32_t StabilizationStart()
|
||||
{
|
||||
// Initialize variables
|
||||
|
||||
// Create object queue
|
||||
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
|
||||
// Listen for updates.
|
||||
// AttitudeActualConnectQueue(queue);
|
||||
AttitudeRawConnectQueue(queue);
|
||||
|
||||
StabilizationSettingsConnectCallback(SettingsUpdatedCb);
|
||||
SettingsUpdatedCb(StabilizationSettingsHandle());
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(stabilizationTask, (signed char*)"Stabilization", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_STABILIZATION, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_STABILIZATION);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
int32_t StabilizationInitialize()
|
||||
{
|
||||
// Initialize variables
|
||||
|
||||
// Create object queue
|
||||
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
|
||||
// Listen for updates.
|
||||
// AttitudeActualConnectQueue(queue);
|
||||
AttitudeRawConnectQueue(queue);
|
||||
|
||||
StabilizationSettingsConnectCallback(SettingsUpdatedCb);
|
||||
SettingsUpdatedCb(StabilizationSettingsHandle());
|
||||
// Start main task
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(StabilizationInitialize, 0, StabilizationStart, 0, MODULE_EXEC_NOORDER_FLAG)
|
||||
|
||||
/**
|
||||
* Module task
|
||||
*/
|
||||
@ -118,8 +139,8 @@ static void stabilizationTask(void* parameters)
|
||||
portTickType lastSysTime;
|
||||
portTickType thisSysTime;
|
||||
UAVObjEvent ev;
|
||||
|
||||
|
||||
|
||||
|
||||
ActuatorDesiredData actuatorDesired;
|
||||
StabilizationDesiredData stabDesired;
|
||||
RateDesiredData rateDesired;
|
||||
@ -127,28 +148,28 @@ static void stabilizationTask(void* parameters)
|
||||
AttitudeRawData attitudeRaw;
|
||||
SystemSettingsData systemSettings;
|
||||
FlightStatusData flightStatus;
|
||||
|
||||
|
||||
SettingsUpdatedCb((UAVObjEvent *) NULL);
|
||||
|
||||
|
||||
// Main task loop
|
||||
lastSysTime = xTaskGetTickCount();
|
||||
ZeroPids();
|
||||
while(1) {
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION);
|
||||
|
||||
|
||||
// Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe
|
||||
if ( xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE )
|
||||
{
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_STABILIZATION,SYSTEMALARMS_ALARM_WARNING);
|
||||
continue;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Check how long since last update
|
||||
thisSysTime = xTaskGetTickCount();
|
||||
if(thisSysTime > lastSysTime) // reuse dt in case of wraparound
|
||||
dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f;
|
||||
lastSysTime = thisSysTime;
|
||||
|
||||
|
||||
FlightStatusGet(&flightStatus);
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
AttitudeActualGet(&attitudeActual);
|
||||
@ -162,11 +183,11 @@ static void stabilizationTask(void* parameters)
|
||||
float q_desired[4];
|
||||
float q_error[4];
|
||||
float local_error[3];
|
||||
|
||||
|
||||
// Essentially zero errors for anything in rate or none
|
||||
if(stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE)
|
||||
rpy_desired[0] = stabDesired.Roll;
|
||||
else
|
||||
rpy_desired[0] = stabDesired.Roll;
|
||||
else
|
||||
rpy_desired[0] = attitudeActual.Roll;
|
||||
|
||||
if(stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE)
|
||||
@ -178,13 +199,13 @@ static void stabilizationTask(void* parameters)
|
||||
rpy_desired[2] = stabDesired.Yaw;
|
||||
else
|
||||
rpy_desired[2] = attitudeActual.Yaw;
|
||||
|
||||
|
||||
RPY2Quaternion(rpy_desired, q_desired);
|
||||
quat_inverse(q_desired);
|
||||
quat_mult(q_desired, &attitudeActual.q1, q_error);
|
||||
quat_inverse(q_error);
|
||||
Quaternion2RPY(q_error, local_error);
|
||||
|
||||
|
||||
#else
|
||||
// Simpler algorithm for CC, less memory
|
||||
float local_error[3] = {stabDesired.Roll - attitudeActual.Roll,
|
||||
@ -192,49 +213,83 @@ static void stabilizationTask(void* parameters)
|
||||
stabDesired.Yaw - attitudeActual.Yaw};
|
||||
local_error[2] = fmod(local_error[2] + 180, 360) - 180;
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
for(uint8_t i = 0; i < MAX_AXES; i++) {
|
||||
gyro_filtered[i] = gyro_filtered[i] * gyro_alpha + attitudeRaw.gyros[i] * (1 - gyro_alpha);
|
||||
}
|
||||
|
||||
float *attitudeDesiredAxis = &stabDesired.Roll;
|
||||
float *actuatorDesiredAxis = &actuatorDesired.Roll;
|
||||
float *rateDesiredAxis = &rateDesired.Roll;
|
||||
|
||||
|
||||
//Calculate desired rate
|
||||
for(int8_t ct=0; ct< MAX_AXES; ct++)
|
||||
for(uint8_t i=0; i< MAX_AXES; i++)
|
||||
{
|
||||
switch(stabDesired.StabilizationMode[ct])
|
||||
switch(stabDesired.StabilizationMode[i])
|
||||
{
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE:
|
||||
rateDesiredAxis[ct] = attitudeDesiredAxis[ct];
|
||||
rateDesiredAxis[i] = attitudeDesiredAxis[i];
|
||||
axis_lock_accum[i] = 0;
|
||||
break;
|
||||
|
||||
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING:
|
||||
{
|
||||
float weak_leveling = local_error[i] * weak_leveling_kp;
|
||||
|
||||
if(weak_leveling > weak_leveling_max)
|
||||
weak_leveling = weak_leveling_max;
|
||||
if(weak_leveling < -weak_leveling_max)
|
||||
weak_leveling = -weak_leveling_max;
|
||||
|
||||
rateDesiredAxis[i] = attitudeDesiredAxis[i] + weak_leveling;
|
||||
|
||||
axis_lock_accum[i] = 0;
|
||||
break;
|
||||
}
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
|
||||
rateDesiredAxis[ct] = ApplyPid(&pids[PID_ROLL + ct], local_error[ct]);
|
||||
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i]);
|
||||
axis_lock_accum[i] = 0;
|
||||
break;
|
||||
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK:
|
||||
if(fabs(attitudeDesiredAxis[i]) > max_axislock_rate) {
|
||||
// While getting strong commands act like rate mode
|
||||
rateDesiredAxis[i] = attitudeDesiredAxis[i];
|
||||
axis_lock_accum[i] = 0;
|
||||
} else {
|
||||
// For weaker commands or no command simply attitude lock (almost) on no gyro change
|
||||
axis_lock_accum[i] += (attitudeDesiredAxis[i] - gyro_filtered[i]) * dT;
|
||||
if(axis_lock_accum[i] > max_axis_lock)
|
||||
axis_lock_accum[i] = max_axis_lock;
|
||||
else if(axis_lock_accum[i] < -max_axis_lock)
|
||||
axis_lock_accum[i] = -max_axis_lock;
|
||||
|
||||
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i]);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
uint8_t shouldUpdate = 1;
|
||||
RateDesiredSet(&rateDesired);
|
||||
ActuatorDesiredGet(&actuatorDesired);
|
||||
//Calculate desired command
|
||||
for(int8_t ct=0; ct< MAX_AXES; ct++)
|
||||
{
|
||||
if(fabs(rateDesiredAxis[ct]) > settings.MaximumRate[ct])
|
||||
{
|
||||
if(rateDesiredAxis[ct] > 0)
|
||||
{
|
||||
rateDesiredAxis[ct] = settings.MaximumRate[ct];
|
||||
}else
|
||||
{
|
||||
rateDesiredAxis[ct] = -settings.MaximumRate[ct];
|
||||
}
|
||||
|
||||
}
|
||||
if(rateDesiredAxis[ct] > settings.MaximumRate[ct])
|
||||
rateDesiredAxis[ct] = settings.MaximumRate[ct];
|
||||
else if(rateDesiredAxis[ct] < -settings.MaximumRate[ct])
|
||||
rateDesiredAxis[ct] = -settings.MaximumRate[ct];
|
||||
|
||||
switch(stabDesired.StabilizationMode[ct])
|
||||
{
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE:
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK:
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING:
|
||||
{
|
||||
float command = ApplyPid(&pids[PID_RATE_ROLL + ct], rateDesiredAxis[ct]-attitudeRaw.gyros[ct]);
|
||||
float command = ApplyPid(&pids[PID_RATE_ROLL + ct], rateDesiredAxis[ct] - gyro_filtered[ct]);
|
||||
actuatorDesiredAxis[ct] = bound(command);
|
||||
break;
|
||||
}
|
||||
@ -255,16 +310,16 @@ static void stabilizationTask(void* parameters)
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Save dT
|
||||
actuatorDesired.UpdateTime = dT * 1000;
|
||||
|
||||
|
||||
if(PARSE_FLIGHT_MODE(flightStatus.FlightMode) == FLIGHTMODE_MANUAL)
|
||||
shouldUpdate = 0;
|
||||
|
||||
|
||||
if(shouldUpdate)
|
||||
{
|
||||
actuatorDesired.Throttle = stabDesired.Throttle;
|
||||
@ -272,16 +327,16 @@ static void stabilizationTask(void* parameters)
|
||||
actuatorDesired.NumLongUpdates++;
|
||||
ActuatorDesiredSet(&actuatorDesired);
|
||||
}
|
||||
|
||||
|
||||
if(flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED ||
|
||||
!shouldUpdate || (stabDesired.Throttle < 0))
|
||||
!shouldUpdate)
|
||||
{
|
||||
ZeroPids();
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
// Clear alarms
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_STABILIZATION);
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_STABILIZATION);
|
||||
}
|
||||
}
|
||||
|
||||
@ -289,15 +344,15 @@ float ApplyPid(pid_type * pid, const float err)
|
||||
{
|
||||
float diff = (err - pid->lastErr);
|
||||
pid->lastErr = err;
|
||||
pid->iAccumulator += err * pid->i * dT;
|
||||
if(fabs(pid->iAccumulator) > pid->iLim) {
|
||||
if(pid->iAccumulator >0) {
|
||||
pid->iAccumulator = pid->iLim;
|
||||
} else {
|
||||
pid->iAccumulator = -pid->iLim;
|
||||
}
|
||||
|
||||
// Scale up accumulator by 1000 while computing to avoid losing precision
|
||||
pid->iAccumulator += err * (pid->i * dT * 1000);
|
||||
if(pid->iAccumulator > (pid->iLim * 1000)) {
|
||||
pid->iAccumulator = pid->iLim * 1000;
|
||||
} else if (pid->iAccumulator < -(pid->iLim * 1000)) {
|
||||
pid->iAccumulator = -pid->iLim * 1000;
|
||||
}
|
||||
return ((err * pid->p) + pid->iAccumulator + (diff * pid->d / dT));
|
||||
return ((err * pid->p) + pid->iAccumulator / 1000 + (diff * pid->d / dT));
|
||||
}
|
||||
|
||||
|
||||
@ -307,6 +362,8 @@ static void ZeroPids(void)
|
||||
pids[ct].iAccumulator = 0;
|
||||
pids[ct].lastErr = 0;
|
||||
}
|
||||
for(uint8_t i = 0; i < 3; i++)
|
||||
axis_lock_accum[i] = 0;
|
||||
}
|
||||
|
||||
|
||||
@ -328,14 +385,58 @@ static void SettingsUpdatedCb(UAVObjEvent * ev)
|
||||
{
|
||||
memset(pids,0,sizeof (pid_type) * PID_MAX);
|
||||
StabilizationSettingsGet(&settings);
|
||||
|
||||
float * data = settings.RollRatePI;
|
||||
for(int8_t pid=0; pid < PID_MAX; pid++)
|
||||
{
|
||||
pids[pid].p = *data++;
|
||||
pids[pid].i = *data++;
|
||||
pids[pid].iLim = *data++;
|
||||
}
|
||||
|
||||
// Set the roll rate PID constants
|
||||
pids[0].p = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP];
|
||||
pids[0].i = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI];
|
||||
pids[0].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD];
|
||||
pids[0].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT];
|
||||
|
||||
// Set the pitch rate PID constants
|
||||
pids[1].p = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP];
|
||||
pids[1].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI];
|
||||
pids[1].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD];
|
||||
pids[1].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT];
|
||||
|
||||
// Set the yaw rate PID constants
|
||||
pids[2].p = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP];
|
||||
pids[2].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI];
|
||||
pids[2].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD];
|
||||
pids[2].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT];
|
||||
|
||||
// Set the roll attitude PI constants
|
||||
pids[3].p = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP];
|
||||
pids[3].i = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI];
|
||||
pids[3].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT];
|
||||
|
||||
// Set the pitch attitude PI constants
|
||||
pids[4].p = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP];
|
||||
pids[4].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI];
|
||||
pids[4].iLim = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT];
|
||||
|
||||
// Set the yaw attitude PI constants
|
||||
pids[5].p = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP];
|
||||
pids[5].i = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI];
|
||||
pids[5].iLim = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT];
|
||||
|
||||
// Maximum deviation to accumulate for axis lock
|
||||
max_axis_lock = settings.MaxAxisLock;
|
||||
max_axislock_rate = settings.MaxAxisLockRate;
|
||||
|
||||
// Settings for weak leveling
|
||||
weak_leveling_kp = settings.WeakLevelingKp;
|
||||
weak_leveling_max = settings.MaxWeakLevelingRate;
|
||||
|
||||
// The dT has some jitter iteration to iteration that we don't want to
|
||||
// make thie result unpredictable. Still, it's nicer to specify the constant
|
||||
// based on a time (in ms) rather than a fixed multiplier. The error between
|
||||
// update rates on OP (~300 Hz) and CC (~475 Hz) is negligible for this
|
||||
// calculation
|
||||
const float fakeDt = 0.0025;
|
||||
if(settings.GyroTau < 0.0001)
|
||||
gyro_alpha = 0; // not trusting this to resolve to 0
|
||||
else
|
||||
gyro_alpha = exp(-fakeDt / settings.GyroTau);
|
||||
}
|
||||
|
||||
|
||||
|
@ -84,18 +84,34 @@ static void updateSystemAlarms();
|
||||
static void systemTask(void *parameters);
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup.
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
* Create the module task.
|
||||
* \returns 0 on success or -1 if initialization failed
|
||||
*/
|
||||
int32_t SystemModInitialize(void)
|
||||
int32_t SystemModStart(void)
|
||||
{
|
||||
// Initialize vars
|
||||
stackOverflow = 0;
|
||||
// Create system task
|
||||
xTaskCreate(systemTask, (signed char *)"System", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &systemTaskHandle);
|
||||
// Register task
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_SYSTEM, systemTaskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize the module, called on startup.
|
||||
* \returns 0 on success or -1 if initialization failed
|
||||
*/
|
||||
int32_t SystemModInitialize(void)
|
||||
{
|
||||
|
||||
SystemModStart();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(SystemModInitialize, 0, 0, 0, MODULE_EXEC_FIRST_FLAG)
|
||||
/**
|
||||
* System task, periodically executes every SYSTEM_UPDATE_PERIOD_MS
|
||||
*/
|
||||
@ -103,11 +119,8 @@ static void systemTask(void *parameters)
|
||||
{
|
||||
portTickType lastSysTime;
|
||||
|
||||
// System initialization
|
||||
OpenPilotInit();
|
||||
|
||||
// Register task
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_SYSTEM, systemTaskHandle);
|
||||
/* create all modules thread */
|
||||
MODULE_TASKCREATE_ALL
|
||||
|
||||
// Initialize vars
|
||||
idleCounter = 0;
|
||||
@ -118,7 +131,7 @@ static void systemTask(void *parameters)
|
||||
ObjectPersistenceConnectCallback(&objectUpdatedCb);
|
||||
|
||||
// Main system loop
|
||||
while (1) {
|
||||
while (1) {
|
||||
// Update the system statistics
|
||||
updateStats();
|
||||
|
||||
@ -260,6 +273,48 @@ static void updateWDGstats()
|
||||
WatchdogStatusSet(&watchdogStatus);
|
||||
}
|
||||
|
||||
/**
|
||||
* Called periodically to update the system stats
|
||||
*/
|
||||
static uint16_t GetFreeIrqStackSize(void)
|
||||
{
|
||||
uint32_t i = 0x200;
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) && defined(CHECK_IRQ_STACK)
|
||||
extern uint32_t _irq_stack_top;
|
||||
extern uint32_t _irq_stack_end;
|
||||
uint32_t pattern = 0x0000A5A5;
|
||||
uint32_t *ptr = &_irq_stack_end;
|
||||
|
||||
#if 1 /* the ugly way accurate but takes more time, useful for debugging */
|
||||
uint32_t stack_size = (((uint32_t)&_irq_stack_top - (uint32_t)&_irq_stack_end) & ~3 ) / 4;
|
||||
|
||||
for (i=0; i< stack_size; i++)
|
||||
{
|
||||
if (ptr[i] != pattern)
|
||||
{
|
||||
i=i*4;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#else /* faster way but not accurate */
|
||||
if (*(volatile uint32_t *)((uint32_t)ptr + IRQSTACK_LIMIT_CRITICAL) != pattern)
|
||||
{
|
||||
i = IRQSTACK_LIMIT_CRITICAL - 1;
|
||||
}
|
||||
else if (*(volatile uint32_t *)((uint32_t)ptr + IRQSTACK_LIMIT_WARNING) != pattern)
|
||||
{
|
||||
i = IRQSTACK_LIMIT_WARNING - 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
i = IRQSTACK_LIMIT_WARNING;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
return i;
|
||||
}
|
||||
|
||||
/**
|
||||
* Called periodically to update the system stats
|
||||
*/
|
||||
@ -278,6 +333,9 @@ static void updateStats()
|
||||
stats.HeapRemaining = xPortGetFreeHeapSize();
|
||||
#endif
|
||||
|
||||
// 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;
|
||||
@ -320,6 +378,17 @@ static void updateSystemAlarms()
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY);
|
||||
}
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) && defined(CHECK_IRQ_STACK)
|
||||
// Check IRQ stack
|
||||
if (stats.IRQStackRemaining < IRQSTACK_LIMIT_CRITICAL) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else if (stats.IRQStackRemaining < IRQSTACK_LIMIT_WARNING) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_WARNING);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Check CPU load
|
||||
if (stats.CPULoad > CPULOAD_LIMIT_CRITICAL) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_CPUOVERLOAD, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
|
@ -31,6 +31,7 @@
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "telemetry.h"
|
||||
#include "flighttelemetrystats.h"
|
||||
#include "gcstelemetrystats.h"
|
||||
#include "telemetrysettings.h"
|
||||
@ -80,6 +81,28 @@ static void updateTelemetryStats();
|
||||
static void gcsTelemetryStatsUpdated();
|
||||
static void updateSettings();
|
||||
|
||||
/**
|
||||
* Initialise the telemetry module
|
||||
* \return -1 if initialisation failed
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t TelemetryStart(void)
|
||||
{
|
||||
|
||||
// Start telemetry tasks
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
|
||||
xTaskCreate(telemetryRxTask, (signed char *)"TelRx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYTX, telemetryTxTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYRX, telemetryRxTaskHandle);
|
||||
|
||||
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
|
||||
xTaskCreate(telemetryTxPriTask, (signed char *)"TelPriTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TXPRI, &telemetryTxPriTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYTXPRI, telemetryTxPriTaskHandle);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the telemetry module
|
||||
* \return -1 if initialisation failed
|
||||
@ -117,20 +140,11 @@ int32_t TelemetryInitialize(void)
|
||||
GCSTelemetryStatsConnectQueue(priorityQueue);
|
||||
TelemetrySettingsConnectQueue(priorityQueue);
|
||||
|
||||
// Start telemetry tasks
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
|
||||
xTaskCreate(telemetryRxTask, (signed char *)"TelRx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYTX, telemetryTxTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYRX, telemetryRxTaskHandle);
|
||||
|
||||
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
|
||||
xTaskCreate(telemetryTxPriTask, (signed char *)"TelPriTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TXPRI, &telemetryTxPriTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYTXPRI, telemetryTxPriTaskHandle);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(TelemetryInitialize, 0, TelemetryStart, 0, MODULE_EXEC_LAST_FLAG)
|
||||
|
||||
/**
|
||||
* Register a new object, adds object to local list and connects the queue depending on the object's
|
||||
* telemetry settings.
|
||||
|
@ -112,8 +112,6 @@ UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
# use file-extension c for "c-only"-files
|
||||
|
||||
MODNAMES = $(notdir ${MODULES} ${PYMODULES})
|
||||
|
||||
ifndef TESTAPP
|
||||
|
||||
## PyMite files and modules
|
||||
@ -128,7 +126,6 @@ SRC += $(PYSRC)
|
||||
|
||||
## MODULES
|
||||
SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
SRC += ${OUTDIR}/InitMods.c
|
||||
## OPENPILOT CORE:
|
||||
SRC += ${OPMODULEDIR}/System/systemmod.c
|
||||
SRC += $(OPSYSTEM)/openpilot.c
|
||||
@ -472,19 +469,10 @@ endif
|
||||
endif
|
||||
|
||||
# Generate intermediate code
|
||||
gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h
|
||||
gencode: ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h
|
||||
|
||||
$(PYSRC): gencode
|
||||
|
||||
# Generate code for module initialization
|
||||
${OUTDIR}/InitMods.c: Makefile
|
||||
@echo $(MSG_MODINIT) $(call toprel, $@)
|
||||
@echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c
|
||||
|
||||
# Generate code for PyMite
|
||||
${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py)
|
||||
@echo $(MSG_PYMITEINIT) $(call toprel, $@)
|
||||
|
@ -441,9 +441,13 @@ ${OUTDIR}/InitMods.c: Makefile.posix
|
||||
@echo ${MSG_MODINIT}
|
||||
@echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Start(void);}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c
|
||||
|
||||
# Generate code for PyMite
|
||||
${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py)
|
||||
|
@ -83,6 +83,9 @@ do {\
|
||||
#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004)/* DWT_CYCCNT */
|
||||
#endif
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32)
|
||||
#define CHECK_IRQ_STACK
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -84,6 +84,8 @@
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 4000
|
||||
#define HEAP_LIMIT_CRITICAL 1000
|
||||
#define IRQSTACK_LIMIT_WARNING 150
|
||||
#define IRQSTACK_LIMIT_CRITICAL 80
|
||||
#define CPULOAD_LIMIT_WARNING 80
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
|
@ -62,11 +62,10 @@ static void TaskSDCard(void *pvParameters);
|
||||
int32_t CONSOLE_Parse(uint8_t port, char c);
|
||||
void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value);
|
||||
|
||||
/* Prototype of generated InitModules() function */
|
||||
extern void InitModules(void);
|
||||
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void Stack_Change(void);
|
||||
static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change")));
|
||||
|
||||
/**
|
||||
* OpenPilot Main function:
|
||||
@ -85,48 +84,42 @@ int main()
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
|
||||
/* Initialize the system thread */
|
||||
SystemModInitialize();
|
||||
|
||||
/* Start the FreeRTOS scheduler */
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
/* If we do get here, it will most likely be because we ran out of heap space. */
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(LED2);
|
||||
for(;;) {
|
||||
PIOS_LED_Toggle(LED1);
|
||||
PIOS_LED_Toggle(LED2);
|
||||
PIOS_DELAY_WaitmS(100);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize the hardware, libraries and modules (called by the System thread in systemmod.c)
|
||||
*/
|
||||
void OpenPilotInit()
|
||||
{
|
||||
|
||||
/* Architecture dependant Hardware and
|
||||
* core subsystem initialisation
|
||||
* (see pios_board.c for your arch)
|
||||
* */
|
||||
|
||||
PIOS_Board_Init();
|
||||
|
||||
/* Initialize modules */
|
||||
InitModules();
|
||||
MODULE_INITIALISE_ALL
|
||||
|
||||
#if INCLUDE_TEST_TASKS
|
||||
/* Create test tasks */
|
||||
//xTaskCreate(TaskTesting, (signed portCHAR *)"Testing", configMINIMAL_STACK_SIZE , NULL, 4, NULL);
|
||||
//xTaskCreate(TaskHIDTest, (signed portCHAR *)"HIDTest", configMINIMAL_STACK_SIZE , NULL, 3, NULL);
|
||||
//xTaskCreate(TaskServos, (signed portCHAR *)"Servos", configMINIMAL_STACK_SIZE , NULL, 3, NULL);
|
||||
//xTaskCreate(TaskSDCard, (signed portCHAR *)"SDCard", configMINIMAL_STACK_SIZE, NULL, (tskIDLE_PRIORITY + 2), NULL);
|
||||
xTaskCreate(TaskTesting, (signed portCHAR *)"Testing", configMINIMAL_STACK_SIZE , NULL, 4, NULL);
|
||||
xTaskCreate(TaskHIDTest, (signed portCHAR *)"HIDTest", configMINIMAL_STACK_SIZE , NULL, 3, NULL);
|
||||
xTaskCreate(TaskServos, (signed portCHAR *)"Servos", configMINIMAL_STACK_SIZE , NULL, 3, NULL);
|
||||
xTaskCreate(TaskSDCard, (signed portCHAR *)"SDCard", configMINIMAL_STACK_SIZE, NULL, (tskIDLE_PRIORITY + 2), NULL);
|
||||
#endif
|
||||
|
||||
/* swap the stack to use the IRQ stack (does nothing in sim mode) */
|
||||
Stack_Change_Weak();
|
||||
|
||||
/* Start the FreeRTOS scheduler which should never returns.*/
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
PIOS_LED_Off(LED1); \
|
||||
for(;;) { \
|
||||
PIOS_LED_Toggle(LED1); \
|
||||
PIOS_DELAY_WaitmS(100); \
|
||||
};
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
#if INCLUDE_TEST_TASKS
|
||||
static void TaskTesting(void *pvParameters)
|
||||
{
|
||||
@ -342,5 +335,5 @@ static void TaskSDCard(void *pvParameters)
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
*/
|
||||
|
||||
|
@ -38,7 +38,22 @@
|
||||
* and we cannot define a linker script for each of them atm
|
||||
*/
|
||||
|
||||
#define uavobj_initcall(fn)
|
||||
extern void InitModules();
|
||||
extern void StartModules();
|
||||
|
||||
#define UAVOBJ_INITCALL(fn)
|
||||
#define MODULE_INITCALL(ifn, iparam, sfn, sparam, flags)
|
||||
|
||||
#define MODULE_TASKCREATE_ALL { \
|
||||
/* Start all module threads */ \
|
||||
StartModules(); \
|
||||
}
|
||||
|
||||
#define MODULE_INITIALISE_ALL { \
|
||||
/* Initialize modules */ \
|
||||
InitModules(); \
|
||||
/* Initialize the system thread */ \
|
||||
SystemModInitialize();}
|
||||
|
||||
#endif /* PIOS_INITCALL_H */
|
||||
|
||||
|
@ -38,7 +38,18 @@
|
||||
* and we cannot define a linker script for each of them atm
|
||||
*/
|
||||
|
||||
#define uavobj_initcall(fn)
|
||||
#define UAVOBJ_INITCALL(fn)
|
||||
#define MODULE_INITCALL(ifn, iparam, sfn, sparam, flags)
|
||||
|
||||
#define MODULE_TASKCREATE_ALL
|
||||
|
||||
#define MODULE_INITIALISE_ALL { \
|
||||
/* Initialize modules */ \
|
||||
InitModules(); \
|
||||
/* Start the FreeRTOS scheduler which never returns.*/ \
|
||||
/* Initialize the system thread */ \
|
||||
SystemModInitialize();}
|
||||
|
||||
|
||||
#endif /* PIOS_INITCALL_H */
|
||||
|
||||
|
@ -1,6 +1,6 @@
|
||||
/*
|
||||
FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd.
|
||||
|
||||
|
||||
|
||||
***************************************************************************
|
||||
* *
|
||||
@ -79,16 +79,18 @@ static union xRTOS_HEAP
|
||||
volatile portDOUBLE dDummy;
|
||||
#else
|
||||
volatile unsigned long ulDummy;
|
||||
#endif
|
||||
#endif
|
||||
unsigned char ucHeap[ configTOTAL_HEAP_SIZE ];
|
||||
} xHeap;
|
||||
} xHeap __attribute__ ((section (".heap")));
|
||||
|
||||
static size_t xNextFreeByte = ( size_t ) 0;
|
||||
static size_t currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE;
|
||||
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
void *pvPortMalloc( size_t xWantedSize )
|
||||
{
|
||||
void *pvReturn = NULL;
|
||||
void *pvReturn = NULL;
|
||||
|
||||
/* Ensure that blocks are always aligned to the required number of bytes. */
|
||||
#if portBYTE_ALIGNMENT != 1
|
||||
@ -102,17 +104,17 @@ void *pvReturn = NULL;
|
||||
vTaskSuspendAll();
|
||||
{
|
||||
/* Check there is enough room left for the allocation. */
|
||||
if( ( ( xNextFreeByte + xWantedSize ) < configTOTAL_HEAP_SIZE ) &&
|
||||
if( ( ( xNextFreeByte + xWantedSize ) < currentTOTAL_HEAP_SIZE ) &&
|
||||
( ( xNextFreeByte + xWantedSize ) > xNextFreeByte ) )/* Check for overflow. */
|
||||
{
|
||||
/* Return the next free byte then increment the index past this
|
||||
block. */
|
||||
pvReturn = &( xHeap.ucHeap[ xNextFreeByte ] );
|
||||
xNextFreeByte += xWantedSize;
|
||||
}
|
||||
xNextFreeByte += xWantedSize;
|
||||
}
|
||||
}
|
||||
xTaskResumeAll();
|
||||
|
||||
|
||||
#if( configUSE_MALLOC_FAILED_HOOK == 1 )
|
||||
{
|
||||
if( pvReturn == NULL )
|
||||
@ -121,7 +123,7 @@ void *pvReturn = NULL;
|
||||
vApplicationMallocFailedHook();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
return pvReturn;
|
||||
}
|
||||
@ -129,8 +131,8 @@ void *pvReturn = NULL;
|
||||
|
||||
void vPortFree( void *pv )
|
||||
{
|
||||
/* Memory cannot be freed using this scheme. See heap_2.c and heap_3.c
|
||||
for alternative implementations, and the memory management pages of
|
||||
/* Memory cannot be freed using this scheme. See heap_2.c and heap_3.c
|
||||
for alternative implementations, and the memory management pages of
|
||||
http://www.FreeRTOS.org for more information. */
|
||||
( void ) pv;
|
||||
}
|
||||
@ -145,8 +147,14 @@ void vPortInitialiseBlocks( void )
|
||||
|
||||
size_t xPortGetFreeHeapSize( void )
|
||||
{
|
||||
return ( configTOTAL_HEAP_SIZE - xNextFreeByte );
|
||||
return ( currentTOTAL_HEAP_SIZE - xNextFreeByte );
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
|
||||
|
||||
void xPortIncreaseHeapSize( size_t bytes )
|
||||
{
|
||||
vTaskSuspendAll();
|
||||
currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE + bytes;
|
||||
xTaskResumeAll();
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
@ -1,6 +1,6 @@
|
||||
/*
|
||||
FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd.
|
||||
|
||||
|
||||
|
||||
***************************************************************************
|
||||
* *
|
||||
@ -81,7 +81,7 @@ static union xRTOS_HEAP
|
||||
volatile unsigned long ulDummy;
|
||||
#endif
|
||||
unsigned char ucHeap[ configTOTAL_HEAP_SIZE ];
|
||||
} xHeap;
|
||||
} xHeap __attribute__ ((section (".heap")));
|
||||
|
||||
/* Define the linked list structure. This is used to link free blocks in order
|
||||
of their size. */
|
||||
@ -101,6 +101,7 @@ static xBlockLink xStart, xEnd;
|
||||
/* Keeps track of the number of free bytes remaining, but says nothing about
|
||||
fragmentation. */
|
||||
static size_t xFreeBytesRemaining = configTOTAL_HEAP_SIZE;
|
||||
static size_t currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE;
|
||||
|
||||
/* STATIC FUNCTIONS ARE DEFINED AS MACROS TO MINIMIZE THE FUNCTION CALL DEPTH. */
|
||||
|
||||
@ -140,13 +141,13 @@ xBlockLink *pxFirstFreeBlock; \
|
||||
xStart.xBlockSize = ( size_t ) 0; \
|
||||
\
|
||||
/* xEnd is used to mark the end of the list of free blocks. */ \
|
||||
xEnd.xBlockSize = configTOTAL_HEAP_SIZE; \
|
||||
xEnd.xBlockSize = currentTOTAL_HEAP_SIZE; \
|
||||
xEnd.pxNextFreeBlock = NULL; \
|
||||
\
|
||||
/* To start with there is a single free block that is sized to take up the \
|
||||
entire heap space. */ \
|
||||
pxFirstFreeBlock = ( void * ) xHeap.ucHeap; \
|
||||
pxFirstFreeBlock->xBlockSize = configTOTAL_HEAP_SIZE; \
|
||||
pxFirstFreeBlock->xBlockSize = currentTOTAL_HEAP_SIZE; \
|
||||
pxFirstFreeBlock->pxNextFreeBlock = &xEnd; \
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
@ -181,7 +182,7 @@ void *pvReturn = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
if( ( xWantedSize > 0 ) && ( xWantedSize < configTOTAL_HEAP_SIZE ) )
|
||||
if( ( xWantedSize > 0 ) && ( xWantedSize < currentTOTAL_HEAP_SIZE ) )
|
||||
{
|
||||
/* Blocks are stored in byte order - traverse the list from the start
|
||||
(smallest) block until one of adequate size is found. */
|
||||
@ -220,7 +221,7 @@ void *pvReturn = NULL;
|
||||
/* Insert the new block into the list of free blocks. */
|
||||
prvInsertBlockIntoFreeList( ( pxNewBlockLink ) );
|
||||
}
|
||||
|
||||
|
||||
xFreeBytesRemaining -= pxBlock->xBlockSize;
|
||||
}
|
||||
}
|
||||
@ -276,3 +277,18 @@ void vPortInitialiseBlocks( void )
|
||||
{
|
||||
/* This just exists to keep the linker quiet. */
|
||||
}
|
||||
|
||||
void xPortIncreaseHeapSize( size_t bytes )
|
||||
{
|
||||
xBlockLink *pxNewBlockLink;
|
||||
vTaskSuspendAll();
|
||||
currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE + bytes;
|
||||
xEnd.xBlockSize = currentTOTAL_HEAP_SIZE;
|
||||
xFreeBytesRemaining += bytes;
|
||||
/* Insert the new block into the list of free blocks. */
|
||||
pxNewBlockLink = ( void * ) &xHeap.ucHeap[ configTOTAL_HEAP_SIZE ];
|
||||
pxNewBlockLink->xBlockSize = bytes;
|
||||
prvInsertBlockIntoFreeList( ( pxNewBlockLink ) );
|
||||
xTaskResumeAll();
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
@ -3,7 +3,8 @@ PROVIDE ( vPortSVCHandler = 0 ) ;
|
||||
PROVIDE ( xPortPendSVHandler = 0 ) ;
|
||||
PROVIDE ( xPortSysTickHandler = 0 ) ;
|
||||
|
||||
_estack = 0x20004FF0;
|
||||
/* This is the size of the stack for early init and for all FreeRTOS IRQs */
|
||||
_irq_stack_size = 0x400;
|
||||
|
||||
/* Section Definitions */
|
||||
SECTIONS
|
||||
@ -59,6 +60,24 @@ SECTIONS
|
||||
_ebss = . ;
|
||||
} > SRAM
|
||||
|
||||
/*
|
||||
* This stack is used both as the initial sp during early init as well as ultimately
|
||||
* being used as the STM32's MSP (Main Stack Pointer) which is the same stack that
|
||||
* is used for _all_ interrupt handlers. The end of this stack should be placed
|
||||
* against the lowest address in RAM so that a stack overrun results in a hard fault
|
||||
* at the first access beyond the end of the stack.
|
||||
*/
|
||||
.irq_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_irq_stack_end = . ;
|
||||
. = . + _irq_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_irq_stack_top = . - 4 ;
|
||||
_init_stack_top = _irq_stack_top;
|
||||
. = ALIGN(4);
|
||||
} > SRAM
|
||||
|
||||
. = ALIGN(4);
|
||||
_end = . ;
|
||||
|
||||
|
@ -1,3 +1,10 @@
|
||||
/* This is the size of the stack for all FreeRTOS IRQs */
|
||||
_irq_stack_size = 0x180;
|
||||
/* This is the size of the stack for early init: life span is until scheduler starts */
|
||||
_init_stack_size = 0x80;
|
||||
/* there is probably a way to get that from the MEMORY section */
|
||||
_eram = ORIGIN(SRAM) + LENGTH(SRAM);
|
||||
|
||||
/* Stub out these functions since we don't use them anyway */
|
||||
PROVIDE ( vPortSVCHandler = 0 ) ;
|
||||
PROVIDE ( xPortPendSVHandler = 0 ) ;
|
||||
@ -5,8 +12,6 @@ PROVIDE ( xPortSysTickHandler = 0 ) ;
|
||||
|
||||
PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO));
|
||||
|
||||
_estack = 0x20004FF0;
|
||||
|
||||
/* Section Definitions */
|
||||
SECTIONS
|
||||
{
|
||||
@ -29,6 +34,16 @@ SECTIONS
|
||||
__uavobj_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
/* module sections */
|
||||
.initcallmodule.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__module_initcall_start = .;
|
||||
KEEP(*(.initcallmodule.init))
|
||||
. = ALIGN(4);
|
||||
__module_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
@ -43,6 +58,23 @@ SECTIONS
|
||||
_etext = .;
|
||||
_sidata = .;
|
||||
|
||||
/*
|
||||
* This stack is used both as the initial sp during early init as well as ultimately
|
||||
* being used as the STM32's MSP (Main Stack Pointer) which is the same stack that
|
||||
* is used for _all_ interrupt handlers. The end of this stack should be placed
|
||||
* against the lowest address in RAM so that a stack overrun results in a hard fault
|
||||
* at the first access beyond the end of the stack.
|
||||
*/
|
||||
.irq_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_irq_stack_end = . ;
|
||||
. = . + _irq_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_irq_stack_top = . - 4 ;
|
||||
. = ALIGN(4);
|
||||
} > SRAM
|
||||
|
||||
.data : AT (_etext)
|
||||
{
|
||||
_sdata = .;
|
||||
@ -51,6 +83,8 @@ SECTIONS
|
||||
_edata = . ;
|
||||
} > SRAM
|
||||
|
||||
|
||||
|
||||
/* .bss section which is used for uninitialized data */
|
||||
.bss (NOLOAD) :
|
||||
{
|
||||
@ -60,6 +94,27 @@ SECTIONS
|
||||
. = ALIGN(4);
|
||||
_ebss = . ;
|
||||
} > SRAM
|
||||
|
||||
.heap (NOLOAD) :
|
||||
{
|
||||
_sheap = . ;
|
||||
_sheap_pre_rtos = . ;
|
||||
*(.heap)
|
||||
. = ALIGN(4);
|
||||
_eheap = . ;
|
||||
_eheap_pre_rtos = . ;
|
||||
_init_stack_end = . ;
|
||||
_sheap_post_rtos = . ;
|
||||
. = . + _init_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_eheap_post_rtos = . ;
|
||||
_init_stack_top = . - 4 ;
|
||||
} > SRAM
|
||||
|
||||
|
||||
/* keep the heap section at the end of the SRAM */
|
||||
/* this will allow to claim the remaining bytes not used
|
||||
/* at run time! (done by the reset vector).
|
||||
|
||||
. = ALIGN(4);
|
||||
_end = . ;
|
||||
|
@ -250,6 +250,7 @@ SECTIONS
|
||||
. = . + _irq_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_irq_stack_top = . - 4 ;
|
||||
_init_stack_top = _irq_stack_top;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
|
@ -223,6 +223,7 @@ SECTIONS
|
||||
. = . + _irq_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_irq_stack_top = . - 4 ;
|
||||
_init_stack_top = _irq_stack_top;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
@ -364,5 +365,3 @@ SECTIONS
|
||||
.debug_typenames 0 : { *(.debug_typenames) }
|
||||
.debug_varnames 0 : { *(.debug_varnames) }
|
||||
}
|
||||
|
||||
|
||||
|
@ -1,5 +1,9 @@
|
||||
/* This is the size of the stack for early init and for all FreeRTOS IRQs */
|
||||
_irq_stack_size = 0x400;
|
||||
/* This is the size of the stack for early init: life span is until scheduler starts */
|
||||
_init_stack_size = 0x400;
|
||||
/* there is probably a way to get that from the MEMORY section */
|
||||
_eram = ORIGIN(RAM) + LENGTH(RAM);
|
||||
|
||||
/* Check valid alignment for VTOR */
|
||||
ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region flash not aligned for startup vector table");
|
||||
@ -191,6 +195,16 @@ SECTIONS
|
||||
__uavobj_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
/* module sections */
|
||||
.initcallmodule.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__module_initcall_start = .;
|
||||
KEEP(*(.initcallmodule.init))
|
||||
. = ALIGN(4);
|
||||
__module_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
/* the program code is stored in the .text section, which goes to Flash */
|
||||
.text :
|
||||
{
|
||||
@ -261,6 +275,26 @@ SECTIONS
|
||||
_ebss = . ;
|
||||
} >RAM
|
||||
|
||||
.heap (NOLOAD) :
|
||||
{
|
||||
_sheap = . ;
|
||||
_sheap_pre_rtos = . ;
|
||||
*(.heap)
|
||||
. = ALIGN(4);
|
||||
_eheap = . ;
|
||||
_eheap_pre_rtos = . ;
|
||||
_init_stack_end = . ;
|
||||
_sheap_post_rtos = . ;
|
||||
. = . + _init_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_eheap_post_rtos = . ;
|
||||
_init_stack_top = . - 4 ;
|
||||
} > RAM
|
||||
|
||||
/* keep the heap section at the end of the SRAM */
|
||||
/* this will allow to claim the remaining bytes not used
|
||||
/* at run time! (done by the reset vector).
|
||||
|
||||
PROVIDE ( end = _ebss );
|
||||
PROVIDE ( _end = _ebss );
|
||||
|
||||
|
@ -98,37 +98,23 @@ static int32_t PIOS_SPEKTRUM_Get(uint32_t chan_id)
|
||||
*/
|
||||
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg)
|
||||
{
|
||||
GPIO_Init(cfg->bind.gpio, &cfg->bind.init);
|
||||
#define BIND_PULSES 5
|
||||
|
||||
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
//PIOS_DELAY_WaitmS(75);
|
||||
/* RX line, drive high for 10us */
|
||||
GPIO_Init(cfg->bind.gpio, &cfg->bind.init);
|
||||
/* RX line, set high */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(10);
|
||||
/* RX line, drive low for 120us */
|
||||
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive low for 120us */
|
||||
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive low for 120us */
|
||||
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive low for 120us */
|
||||
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
|
||||
/* on CC works upto 140ms, I guess bind window is around 20-140ms after powerup */
|
||||
PIOS_DELAY_WaitmS(60);
|
||||
|
||||
for (int i = 0; i < BIND_PULSES ; i++) {
|
||||
/* RX line, drive low for 120us */
|
||||
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
}
|
||||
/* RX line, set input and wait for data, PIOS_SPEKTRUM_Init */
|
||||
|
||||
return true;
|
||||
|
@ -36,6 +36,8 @@
|
||||
.global g_pfnVectors
|
||||
.global SystemInit_ExtMemCtl_Dummy
|
||||
.global Default_Handler
|
||||
.global xPortIncreaseHeapSize
|
||||
.global Stack_Change
|
||||
|
||||
/* start address for the initialization values of the .data section.
|
||||
defined in linker script */
|
||||
@ -71,6 +73,35 @@ Reset_Handler:
|
||||
/* restore original stack pointer */
|
||||
LDR r0, =_irq_stack_top
|
||||
MSR msp, r0
|
||||
LDR r2, =_init_stack_top
|
||||
MSR psp, r2
|
||||
/* check if irq and init stack are the same */
|
||||
/* if they are, we don't do stack swap */
|
||||
/* and lets bypass the monitoring as well for now */
|
||||
cmp r0, r2
|
||||
beq SectionBssInit
|
||||
/* DO
|
||||
* - stay in thread process mode
|
||||
* - stay in privilege level
|
||||
* - use process stack
|
||||
*/
|
||||
movs r0, #2
|
||||
MSR control, r0
|
||||
ISB
|
||||
/* Fill IRQ stack for watermark monitoring */
|
||||
ldr r2, =_irq_stack_end
|
||||
b LoopFillIRQStack
|
||||
|
||||
FillIRQStack:
|
||||
movw r3, #0xA5A5
|
||||
str r3, [r2], #4
|
||||
|
||||
LoopFillIRQStack:
|
||||
ldr r3, = _irq_stack_top
|
||||
cmp r2, r3
|
||||
bcc FillIRQStack
|
||||
|
||||
SectionBssInit:
|
||||
/* Copy the data segment initializers from flash to SRAM */
|
||||
movs r1, #0
|
||||
b LoopCopyDataInit
|
||||
@ -100,9 +131,37 @@ LoopFillZerobss:
|
||||
bcc FillZerobss
|
||||
/* Call the application's entry point.*/
|
||||
bl main
|
||||
bx lr
|
||||
/* will never return here */
|
||||
bx lr
|
||||
.size Reset_Handler, .-Reset_Handler
|
||||
|
||||
/**
|
||||
* @brief This is the code that swaps stack (from end of heap to irq_stack).
|
||||
* Also reclaim the heap that was used as a stack.
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Stack_Change
|
||||
.weak Stack_Change
|
||||
.type Stack_Change, %function
|
||||
Stack_Change:
|
||||
mov r4, lr
|
||||
/* Switches stack back momentarily to MSP */
|
||||
movs r0, #0
|
||||
msr control, r0
|
||||
Heap_Reclaim:
|
||||
/* add heap_post_rtos to the heap (if the capability/function exist) */
|
||||
/* Also claim the unused memory (between end of heap to end of memory */
|
||||
/* CAREFULL: the heap section must be the last section in RAM in order this to work */
|
||||
ldr r0, = _init_stack_size
|
||||
ldr r1, = _eheap_post_rtos
|
||||
ldr r2, = _eram
|
||||
subs r2, r2, r1
|
||||
adds r0, r0, r2
|
||||
bl xPortIncreaseHeapSize
|
||||
bx r4
|
||||
.size Stack_Change, .-Stack_Change
|
||||
|
||||
/**
|
||||
* @brief Dummy SystemInit_ExtMemCtl function
|
||||
* @param None
|
||||
@ -114,12 +173,12 @@ SystemInit_ExtMemCtl_Dummy:
|
||||
.size SystemInit_ExtMemCtl_Dummy, .-SystemInit_ExtMemCtl_Dummy
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* unexpected interrupt. This simply enters an infinite loop, preserving
|
||||
* the system state for examination by a debugger.
|
||||
*
|
||||
* @param None
|
||||
* @retval : None
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Default_Handler,"ax",%progbits
|
||||
Default_Handler:
|
||||
@ -272,13 +331,13 @@ g_pfnVectors:
|
||||
|
||||
.weak NMI_Handler
|
||||
.thumb_set NMI_Handler,Default_Handler
|
||||
|
||||
|
||||
.weak HardFault_Handler
|
||||
.thumb_set HardFault_Handler,Default_Handler
|
||||
|
||||
|
||||
.weak MemManage_Handler
|
||||
.thumb_set MemManage_Handler,Default_Handler
|
||||
|
||||
|
||||
.weak BusFault_Handler
|
||||
.thumb_set BusFault_Handler,Default_Handler
|
||||
|
||||
|
@ -33,6 +33,8 @@
|
||||
|
||||
.global g_pfnVectors
|
||||
.global Default_Handler
|
||||
.global xPortIncreaseHeapSize
|
||||
.global Stack_Change
|
||||
|
||||
/* start address for the initialization values of the .data section.
|
||||
defined in linker script */
|
||||
@ -61,6 +63,47 @@ defined in linker script */
|
||||
.type Reset_Handler, %function
|
||||
Reset_Handler:
|
||||
|
||||
/*
|
||||
* From COrtex-M3 reference manual:
|
||||
* - Handler IRQ always use SP_main
|
||||
* - Process use SP_main or SP_process
|
||||
* Here, we will use beginning of SRAM for IRQ (SP_main)
|
||||
* and end of heap for initialization (SP_process).
|
||||
* Once the schedule starts, all threads will use their own stack
|
||||
* from heap and NOBOBY should use SP_process again.
|
||||
*/
|
||||
/* Do set/reset the stack pointers */
|
||||
LDR r0, =_irq_stack_top
|
||||
MSR msp, r0
|
||||
LDR r2, =_init_stack_top
|
||||
MSR psp, r2
|
||||
/* check if irq and init stack are the same */
|
||||
/* if they are, we don't do stack swap */
|
||||
/* and lets bypass the monitoring as well for now */
|
||||
cmp r0, r2
|
||||
beq SectionBssInit
|
||||
/* DO
|
||||
* - stay in thread process mode
|
||||
* - stay in privilege level
|
||||
* - use process stack
|
||||
*/
|
||||
movs r0, #2
|
||||
MSR control, r0
|
||||
ISB
|
||||
/* Fill IRQ stack for watermark monitoring */
|
||||
ldr r2, =_irq_stack_end
|
||||
b LoopFillIRQStack
|
||||
|
||||
FillIRQStack:
|
||||
movw r3, #0xA5A5
|
||||
str r3, [r2], #4
|
||||
|
||||
LoopFillIRQStack:
|
||||
ldr r3, = _irq_stack_top
|
||||
cmp r2, r3
|
||||
bcc FillIRQStack
|
||||
|
||||
SectionBssInit:
|
||||
/* Copy the data segment initializers from flash to SRAM */
|
||||
movs r1, #0
|
||||
b LoopCopyDataInit
|
||||
@ -90,16 +133,45 @@ LoopFillZerobss:
|
||||
bcc FillZerobss
|
||||
/* Call the application's entry point.*/
|
||||
bl main
|
||||
/* will never return here */
|
||||
bx lr
|
||||
.size Reset_Handler, .-Reset_Handler
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* @brief This is the code that swaps stack (from end of heap to irq_stack).
|
||||
* Also reclaim the heap that was used as a stack.
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Stack_Change
|
||||
.weak Stack_Change
|
||||
.type Stack_Change, %function
|
||||
Stack_Change:
|
||||
mov r4, lr
|
||||
/* Switches stack back momentarily to MSP */
|
||||
movs r0, #0
|
||||
msr control, r0
|
||||
Heap_Reclaim:
|
||||
/* add heap_post_rtos to the heap (if the capability/function exist) */
|
||||
/* Also claim the unused memory (between end of heap to end of memory */
|
||||
/* CAREFULL: the heap section must be the last section in RAM in order this to work */
|
||||
ldr r0, = _init_stack_size
|
||||
ldr r1, = _eheap_post_rtos
|
||||
ldr r2, = _eram
|
||||
subs r2, r2, r1
|
||||
adds r0, r0, r2
|
||||
bl xPortIncreaseHeapSize
|
||||
bx r4
|
||||
.size Stack_Change, .-Stack_Change
|
||||
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* unexpected interrupt. This simply enters an infinite loop, preserving
|
||||
* the system state for examination by a debugger.
|
||||
*
|
||||
* @param None
|
||||
* @retval : None
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Default_Handler,"ax",%progbits
|
||||
Default_Handler:
|
||||
@ -119,7 +191,7 @@ Infinite_Loop:
|
||||
|
||||
|
||||
g_pfnVectors:
|
||||
.word _estack
|
||||
.word _irq_stack_top
|
||||
.word Reset_Handler
|
||||
.word NMI_Handler
|
||||
.word HardFault_Handler
|
||||
|
@ -41,7 +41,21 @@
|
||||
/*
|
||||
* Used for initialization calls..
|
||||
*/
|
||||
#define MODULE_EXEC_NOORDER_FLAG 0xFA000000
|
||||
#define MODULE_EXEC_FIRST_FLAG 0xFA000001
|
||||
#define MODULE_EXEC_LAST_FLAG 0xFA000002
|
||||
|
||||
typedef int32_t (*initcall_t)(void);
|
||||
typedef struct {
|
||||
uint32_t flag;
|
||||
uint32_t param_minit;
|
||||
initcall_t fn_minit;
|
||||
uint32_t param_tinit;
|
||||
initcall_t fn_tinit;
|
||||
} initmodule_t;
|
||||
|
||||
/* Init module section */
|
||||
extern initmodule_t __module_initcall_start[], __module_initcall_end[];
|
||||
|
||||
/* initcalls are now grouped by functionality into separate
|
||||
* subsections. Ordering inside the subsections is determined
|
||||
@ -55,7 +69,26 @@ typedef int32_t (*initcall_t)(void);
|
||||
static initcall_t __initcall_##fn##id __attribute__((__used__)) \
|
||||
__attribute__((__section__(".initcall" level ".init"))) = fn
|
||||
|
||||
#define uavobj_initcall(fn) __define_initcall("uavobj",fn,1)
|
||||
#define __define_module_initcall(level,ifn,iparam,sfn,sparam, param) \
|
||||
static initmodule_t __initcall_##fn __attribute__((__used__)) \
|
||||
__attribute__((__section__(".initcall" level ".init"))) = { .flag = param, .param_minit = iparam, .fn_minit = ifn, .param_tinit = sparam, .fn_tinit = sfn };
|
||||
|
||||
#define UAVOBJ_INITCALL(fn) __define_initcall("uavobj",fn,1)
|
||||
#define MODULE_INITCALL(ifn, iparam, sfn, sparam, flags) __define_module_initcall("module", ifn, iparam, sfn, sparam, flags)
|
||||
|
||||
#define MODULE_INITIALISE_ALL { for (initmodule_t *fn = __module_initcall_start; fn < __module_initcall_end; fn++) \
|
||||
if (fn->fn_minit && ( (fn->flag & MODULE_EXEC_FIRST_FLAG) == MODULE_EXEC_FIRST_FLAG) ) \
|
||||
(fn->fn_minit)(); \
|
||||
for (initmodule_t *fn = __module_initcall_start; fn < __module_initcall_end; fn++) \
|
||||
if (fn->fn_minit && ( (fn->flag & (MODULE_EXEC_LAST_FLAG | MODULE_EXEC_FIRST_FLAG)) == MODULE_EXEC_NOORDER_FLAG) ) \
|
||||
(fn->fn_minit)(); \
|
||||
for (initmodule_t *fn = __module_initcall_start; fn < __module_initcall_end; fn++) \
|
||||
if (fn->fn_minit && ( (fn->flag & MODULE_EXEC_LAST_FLAG) == MODULE_EXEC_LAST_FLAG) ) \
|
||||
(fn->fn_minit)(); }
|
||||
|
||||
#define MODULE_TASKCREATE_ALL { for (initmodule_t *fn = __module_initcall_start; fn < __module_initcall_end; fn++) \
|
||||
if (fn->fn_tinit) \
|
||||
(fn->fn_tinit)(); }
|
||||
|
||||
#endif /* PIOS_INITCALL_H */
|
||||
|
||||
|
@ -64,7 +64,7 @@ int32_t $(NAME)Initialize(void)
|
||||
}
|
||||
}
|
||||
|
||||
uavobj_initcall($(NAME)Initialize);
|
||||
UAVOBJ_INITCALL($(NAME)Initialize);
|
||||
|
||||
/**
|
||||
* Initialize object fields and metadata with the default values.
|
||||
|
After Width: | Height: | Size: 96 KiB |
After Width: | Height: | Size: 125 KiB |
After Width: | Height: | Size: 132 KiB |
After Width: | Height: | Size: 84 KiB |
After Width: | Height: | Size: 84 KiB |
After Width: | Height: | Size: 1.1 KiB |
@ -30,8 +30,6 @@
|
||||
/*!
|
||||
* \defgroup light Lights
|
||||
*/
|
||||
/*!
|
||||
|
||||
|
||||
/*!
|
||||
* \ingroup light
|
||||
|
@ -110,7 +110,6 @@
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
<zorder></zorder>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
|
@ -27,6 +27,7 @@
|
||||
#include "configccattitudewidget.h"
|
||||
#include "ui_ccattitude.h"
|
||||
#include "utils/coordinateconversions.h"
|
||||
#include "attitudesettings.h"
|
||||
#include <QMutexLocker>
|
||||
#include <QMessageBox>
|
||||
#include <QDebug>
|
||||
@ -48,7 +49,7 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
|
||||
|
||||
enableControls(true);
|
||||
refreshValues(); // The 1st time this panel is instanciated, the autopilot is already connected.
|
||||
UAVObject * settings = getObjectManager()->getObject(QString("AttitudeSettings"));
|
||||
UAVObject * settings = AttitudeSettings::GetInstance(getObjectManager());
|
||||
connect(settings,SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues()));
|
||||
|
||||
// Connect the help button
|
||||
@ -79,7 +80,10 @@ void ConfigCCAttitudeWidget::attitudeRawUpdated(UAVObject * obj) {
|
||||
x_accum.append(field->getDouble(0));
|
||||
y_accum.append(field->getDouble(1));
|
||||
z_accum.append(field->getDouble(2));
|
||||
qDebug("update %d: %f, %f, %f\n",updates,field->getDouble(0),field->getDouble(1),field->getDouble(2));
|
||||
field = obj->getField(QString("gyros"));
|
||||
x_gyro_accum.append(field->getDouble(0));
|
||||
y_gyro_accum.append(field->getDouble(1));
|
||||
z_gyro_accum.append(field->getDouble(2));;
|
||||
} else if ( updates == NUM_ACCEL_UPDATES ) {
|
||||
updates++;
|
||||
timer.stop();
|
||||
@ -90,17 +94,22 @@ void ConfigCCAttitudeWidget::attitudeRawUpdated(UAVObject * obj) {
|
||||
float y_bias = listMean(y_accum) / ACCEL_SCALE;
|
||||
float z_bias = (listMean(z_accum) + 9.81) / ACCEL_SCALE;
|
||||
|
||||
float x_gyro_bias = listMean(x_gyro_accum) * 100.0f;
|
||||
float y_gyro_bias = listMean(y_gyro_accum) * 100.0f;
|
||||
float z_gyro_bias = listMean(z_gyro_accum) * 100.0f;
|
||||
obj->setMetadata(initialMdata);
|
||||
|
||||
UAVDataObject * settings = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("AttitudeSettings")));
|
||||
UAVObjectField * field = settings->getField("AccelBias");
|
||||
field->setDouble(field->getDouble(0) + x_bias,0);
|
||||
field->setDouble(field->getDouble(1) + y_bias,1);
|
||||
field->setDouble(field->getDouble(2) + z_bias,2);
|
||||
qDebug("New X bias: %f\n", field->getDouble(0)+x_bias);
|
||||
qDebug("New Y bias: %f\n", field->getDouble(1)+y_bias);
|
||||
qDebug("New Z bias: %f\n", field->getDouble(2)+z_bias);
|
||||
settings->updated();
|
||||
AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData();
|
||||
// We offset the gyro bias by current bias to help precision
|
||||
attitudeSettingsData.AccelBias[0] += x_bias;
|
||||
attitudeSettingsData.AccelBias[1] += y_bias;
|
||||
attitudeSettingsData.AccelBias[2] += z_bias;
|
||||
attitudeSettingsData.GyroBias[0] = -x_gyro_bias;
|
||||
attitudeSettingsData.GyroBias[1] = -y_gyro_bias;
|
||||
attitudeSettingsData.GyroBias[2] = -z_gyro_bias;
|
||||
attitudeSettingsData.BiasCorrectGyro = initialBiasCorrected;
|
||||
AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData);
|
||||
|
||||
ui->status->setText("Calibration done.");
|
||||
} else {
|
||||
// Possible to get here if weird threading stuff happens. Just ignore updates.
|
||||
@ -123,32 +132,22 @@ void ConfigCCAttitudeWidget::timeout() {
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::applyAttitudeSettings() {
|
||||
UAVDataObject * settings = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("AttitudeSettings")));
|
||||
UAVObjectField * field = settings->getField("BoardRotation");
|
||||
|
||||
field->setValue(ui->rollBias->value(),0);
|
||||
field->setValue(ui->pitchBias->value(),1);
|
||||
field->setValue(ui->yawBias->value(),2);
|
||||
|
||||
field = settings->getField("ZeroDuringArming");
|
||||
// Handling of boolean values is done through enums on
|
||||
// uavobjects...
|
||||
field->setValue((ui->zeroGyroBiasOnArming->isChecked()) ? "TRUE": "FALSE");
|
||||
|
||||
settings->updated();
|
||||
AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData();
|
||||
attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = ui->rollBias->value();
|
||||
attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = ui->pitchBias->value();
|
||||
attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = ui->yawBias->value();
|
||||
attitudeSettingsData.ZeroDuringArming = ui->zeroGyroBiasOnArming->isChecked() ? AttitudeSettings::ZERODURINGARMING_TRUE :
|
||||
AttitudeSettings::ZERODURINGARMING_FALSE;
|
||||
AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData);
|
||||
}
|
||||
|
||||
void ConfigCCAttitudeWidget::refreshValues() {
|
||||
UAVDataObject * settings = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("AttitudeSettings")));
|
||||
UAVObjectField * field = settings->getField("BoardRotation");
|
||||
ui->rollBias->setValue(field->getDouble(0));
|
||||
ui->pitchBias->setValue(field->getDouble(1));
|
||||
ui->yawBias->setValue(field->getDouble(2));
|
||||
field = settings->getField("ZeroDuringArming");
|
||||
// Handling of boolean values is done through enums on
|
||||
// uavobjects...
|
||||
bool enabled = (field->getValue().toString() == "FALSE") ? false : true;
|
||||
ui->zeroGyroBiasOnArming->setChecked(enabled);
|
||||
AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData();
|
||||
|
||||
ui->rollBias->setValue(attitudeSettingsData.BoardRotation[0]);
|
||||
ui->pitchBias->setValue(attitudeSettingsData.BoardRotation[1]);
|
||||
ui->yawBias->setValue(attitudeSettingsData.BoardRotation[2]);
|
||||
ui->zeroGyroBiasOnArming->setChecked(attitudeSettingsData.ZeroDuringArming == AttitudeSettings::ZERODURINGARMING_TRUE);
|
||||
|
||||
}
|
||||
|
||||
@ -159,9 +158,18 @@ void ConfigCCAttitudeWidget::startAccelCalibration() {
|
||||
x_accum.clear();
|
||||
y_accum.clear();
|
||||
z_accum.clear();
|
||||
x_gyro_accum.clear();
|
||||
y_gyro_accum.clear();
|
||||
z_gyro_accum.clear();
|
||||
|
||||
ui->status->setText(tr("Calibrating..."));
|
||||
|
||||
// Disable gyro bias correction to see raw data
|
||||
AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData();
|
||||
initialBiasCorrected = attitudeSettingsData.BiasCorrectGyro;
|
||||
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE;
|
||||
AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData);
|
||||
|
||||
// Set up to receive updates
|
||||
UAVDataObject * obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("AttitudeRaw")));
|
||||
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(attitudeRawUpdated(UAVObject*)));
|
||||
|
@ -60,10 +60,12 @@ private:
|
||||
Ui_ccattitude *ui;
|
||||
QTimer timer;
|
||||
UAVObject::Metadata initialMdata;
|
||||
quint8 initialBiasCorrected;
|
||||
|
||||
int updates;
|
||||
|
||||
QList<double> x_accum, y_accum, z_accum;
|
||||
QList<double> x_gyro_accum, y_gyro_accum, z_gyro_accum;
|
||||
|
||||
static const int NUM_ACCEL_UPDATES = 60;
|
||||
static const float ACCEL_SCALE = 0.004f * 9.81f;
|
||||
|
@ -174,11 +174,13 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
connect(m_config->ch5Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool)));
|
||||
connect(m_config->ch6Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool)));
|
||||
connect(m_config->ch7Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool)));
|
||||
|
||||
connect(m_config->doRCInputCalibration,SIGNAL(stateChanged(int)),this,SLOT(updateTips(int)));
|
||||
firstUpdate = true;
|
||||
|
||||
// Connect the help button
|
||||
connect(m_config->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
updateTips(Qt::Unchecked);
|
||||
|
||||
}
|
||||
|
||||
ConfigInputWidget::~ConfigInputWidget()
|
||||
@ -469,10 +471,15 @@ void ConfigInputWidget::updateChannels(UAVObject* controlCommand)
|
||||
QString fieldName = QString("Connected");
|
||||
UAVObjectField *field = controlCommand->getField(fieldName);
|
||||
if (field->getValue().toBool())
|
||||
{
|
||||
m_config->RCInputConnected->setText("RC Receiver connected");
|
||||
m_config->lblMissingInputs->setText("");
|
||||
}
|
||||
else
|
||||
{
|
||||
m_config->RCInputConnected->setText("RC Receiver not connected or invalid input configuration (missing channels)");
|
||||
|
||||
receiverHelp();
|
||||
}
|
||||
if (m_config->doRCInputCalibration->isChecked()) {
|
||||
if (firstUpdate) {
|
||||
// Increase the data rate from the board so that the sliders
|
||||
@ -655,4 +662,77 @@ void ConfigInputWidget::openHelp()
|
||||
|
||||
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Input+Configuration", QUrl::StrictMode) );
|
||||
}
|
||||
void ConfigInputWidget::receiverHelp()
|
||||
{
|
||||
QString unassigned;
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
UAVDataObject* controlCommand = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("ManualControlSettings")));
|
||||
|
||||
UAVObjectField *field;
|
||||
|
||||
field= controlCommand->getField("Roll");
|
||||
if(field->getValue().toString()=="None")
|
||||
unassigned.append("Roll");
|
||||
|
||||
field =controlCommand->getField("Pitch");
|
||||
if(field->getValue().toString()=="None")
|
||||
{
|
||||
if(unassigned.length()>0)
|
||||
unassigned.append(", ");
|
||||
unassigned.append("Pitch");
|
||||
}
|
||||
|
||||
field =controlCommand->getField("Yaw");
|
||||
if(field->getValue().toString()=="None")
|
||||
{
|
||||
if(unassigned.length()>0)
|
||||
unassigned.append(", ");
|
||||
unassigned.append("Yaw");
|
||||
}
|
||||
|
||||
field =controlCommand->getField("Throttle");
|
||||
if(field->getValue().toString()=="None")
|
||||
{
|
||||
if(unassigned.length()>0)
|
||||
unassigned.append(", ");
|
||||
unassigned.append("Throttle");
|
||||
}
|
||||
|
||||
field =controlCommand->getField("FlightMode");
|
||||
if(field->getValue().toString()=="None")
|
||||
{
|
||||
if(unassigned.length()>0)
|
||||
unassigned.append(", ");
|
||||
unassigned.append("FlightMode");
|
||||
}
|
||||
if(unassigned.length()>0)
|
||||
m_config->lblMissingInputs->setText(QString("Channels left to assign:")+unassigned);
|
||||
else
|
||||
m_config->lblMissingInputs->setText("");
|
||||
}
|
||||
void ConfigInputWidget::updateTips(int value)
|
||||
{
|
||||
if(value==Qt::Checked)
|
||||
{
|
||||
m_config->ch0Cur->setToolTip("Current channel value");
|
||||
m_config->ch1Cur->setToolTip("Current channel value");
|
||||
m_config->ch2Cur->setToolTip("Current channel value");
|
||||
m_config->ch3Cur->setToolTip("Current channel value");
|
||||
m_config->ch4Cur->setToolTip("Current channel value");
|
||||
m_config->ch5Cur->setToolTip("Current channel value");
|
||||
m_config->ch6Cur->setToolTip("Current channel value");
|
||||
m_config->ch7Cur->setToolTip("Current channel value");
|
||||
}
|
||||
else
|
||||
{
|
||||
m_config->ch0Cur->setToolTip("Channel neutral point");
|
||||
m_config->ch1Cur->setToolTip("Channel neutral point");
|
||||
m_config->ch2Cur->setToolTip("Channel neutral point");
|
||||
m_config->ch3Cur->setToolTip("Channel neutral point");
|
||||
m_config->ch4Cur->setToolTip("Channel neutral point");
|
||||
m_config->ch5Cur->setToolTip("Channel neutral point");
|
||||
m_config->ch6Cur->setToolTip("Channel neutral point");
|
||||
m_config->ch7Cur->setToolTip("Channel neutral point");
|
||||
}
|
||||
}
|
||||
|
@ -71,7 +71,7 @@ private:
|
||||
bool firstUpdate;
|
||||
|
||||
virtual void enableControls(bool enable);
|
||||
|
||||
void receiverHelp();
|
||||
private slots:
|
||||
void updateChannels(UAVObject* obj);
|
||||
virtual void refreshValues();
|
||||
@ -79,6 +79,7 @@ private slots:
|
||||
void saveRCInputObject();
|
||||
void reverseCheckboxClicked(bool state);
|
||||
void openHelp();
|
||||
void updateTips(int);
|
||||
};
|
||||
|
||||
#endif
|
||||
|
@ -194,17 +194,17 @@ void ConfigStabilizationWidget::refreshValues()
|
||||
// stabSettings->requestUpdate();
|
||||
StabilizationSettings::DataFields stabData = stabSettings->getData();
|
||||
// Now fill in all the fields, this is fairly tedious:
|
||||
m_stabilization->rateRollKp->setValue(stabData.RollRatePI[StabilizationSettings::ROLLRATEPI_KP]);
|
||||
m_stabilization->rateRollKi->setValue(stabData.RollRatePI[StabilizationSettings::ROLLRATEPI_KI]);
|
||||
m_stabilization->rateRollILimit->setValue(stabData.RollRatePI[StabilizationSettings::ROLLRATEPI_ILIMIT]);
|
||||
m_stabilization->rateRollKp->setValue(stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_KP]);
|
||||
m_stabilization->rateRollKi->setValue(stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_KI]);
|
||||
m_stabilization->rateRollILimit->setValue(stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_ILIMIT]);
|
||||
|
||||
m_stabilization->ratePitchKp->setValue(stabData.PitchRatePI[StabilizationSettings::PITCHRATEPI_KP]);
|
||||
m_stabilization->ratePitchKi->setValue(stabData.PitchRatePI[StabilizationSettings::PITCHRATEPI_KI]);
|
||||
m_stabilization->ratePitchILimit->setValue(stabData.PitchRatePI[StabilizationSettings::PITCHRATEPI_ILIMIT]);
|
||||
m_stabilization->ratePitchKp->setValue(stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_KP]);
|
||||
m_stabilization->ratePitchKi->setValue(stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_KI]);
|
||||
m_stabilization->ratePitchILimit->setValue(stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_ILIMIT]);
|
||||
|
||||
m_stabilization->rateYawKp->setValue(stabData.YawRatePI[StabilizationSettings::YAWRATEPI_KP]);
|
||||
m_stabilization->rateYawKi->setValue(stabData.YawRatePI[StabilizationSettings::YAWRATEPI_KI]);
|
||||
m_stabilization->rateYawILimit->setValue(stabData.YawRatePI[StabilizationSettings::YAWRATEPI_ILIMIT]);
|
||||
m_stabilization->rateYawKp->setValue(stabData.YawRatePID[StabilizationSettings::YAWRATEPID_KP]);
|
||||
m_stabilization->rateYawKi->setValue(stabData.YawRatePID[StabilizationSettings::YAWRATEPID_KI]);
|
||||
m_stabilization->rateYawILimit->setValue(stabData.YawRatePID[StabilizationSettings::YAWRATEPID_ILIMIT]);
|
||||
|
||||
m_stabilization->rollKp->setValue(stabData.RollPI[StabilizationSettings::ROLLPI_KP]);
|
||||
m_stabilization->rollKi->setValue(stabData.RollPI[StabilizationSettings::ROLLPI_KI]);
|
||||
@ -241,17 +241,17 @@ void ConfigStabilizationWidget::sendStabilizationUpdate()
|
||||
{
|
||||
StabilizationSettings::DataFields stabData = stabSettings->getData();
|
||||
|
||||
stabData.RollRatePI[StabilizationSettings::ROLLRATEPI_KP] = m_stabilization->rateRollKp->value();
|
||||
stabData.RollRatePI[StabilizationSettings::ROLLRATEPI_KI] = m_stabilization->rateRollKi->value();
|
||||
stabData.RollRatePI[StabilizationSettings::ROLLRATEPI_ILIMIT] = m_stabilization->rateRollILimit->value();
|
||||
stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_KP] = m_stabilization->rateRollKp->value();
|
||||
stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_KI] = m_stabilization->rateRollKi->value();
|
||||
stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_ILIMIT] = m_stabilization->rateRollILimit->value();
|
||||
|
||||
stabData.PitchRatePI[StabilizationSettings::PITCHRATEPI_KP] = m_stabilization->ratePitchKp->value();
|
||||
stabData.PitchRatePI[StabilizationSettings::PITCHRATEPI_KI] = m_stabilization->ratePitchKi->value();
|
||||
stabData.PitchRatePI[StabilizationSettings::PITCHRATEPI_ILIMIT] = m_stabilization->ratePitchILimit->value();
|
||||
stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_KP] = m_stabilization->ratePitchKp->value();
|
||||
stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_KI] = m_stabilization->ratePitchKi->value();
|
||||
stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_ILIMIT] = m_stabilization->ratePitchILimit->value();
|
||||
|
||||
stabData.YawRatePI[StabilizationSettings::YAWRATEPI_KP] = m_stabilization->rateYawKp->value();
|
||||
stabData.YawRatePI[StabilizationSettings::YAWRATEPI_KI] = m_stabilization->rateYawKi->value();
|
||||
stabData.YawRatePI[StabilizationSettings::YAWRATEPI_ILIMIT] = m_stabilization->rateYawILimit->value();
|
||||
stabData.YawRatePID[StabilizationSettings::YAWRATEPID_KP] = m_stabilization->rateYawKp->value();
|
||||
stabData.YawRatePID[StabilizationSettings::YAWRATEPID_KI] = m_stabilization->rateYawKi->value();
|
||||
stabData.YawRatePID[StabilizationSettings::YAWRATEPID_ILIMIT] = m_stabilization->rateYawILimit->value();
|
||||
|
||||
stabData.RollPI[StabilizationSettings::ROLLPI_KP] = m_stabilization->rollKp->value();
|
||||
stabData.RollPI[StabilizationSettings::ROLLPI_KI] = m_stabilization->rollKi->value();
|
||||
|
@ -6,7 +6,7 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>557</width>
|
||||
<width>560</width>
|
||||
<height>467</height>
|
||||
</rect>
|
||||
</property>
|
||||
@ -24,6 +24,186 @@
|
||||
<string>RC Input</string>
|
||||
</attribute>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Receiver Type:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1" colspan="2">
|
||||
<widget class="QComboBox" name="receiverType">
|
||||
<property name="toolTip">
|
||||
<string>Select the receiver type here:
|
||||
- PWM is the most usual type
|
||||
- PPM is connected to input XXX
|
||||
- Spektrum is used with Spektrum 'satellite' receivers</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_3">
|
||||
<item>
|
||||
<widget class="QLabel" name="RCInputConnected">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>234</width>
|
||||
<height>54</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>11</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Indicates whether OpenPilot is getting a signal from the RC receiver.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RC Receiver not connected or invalid input configuration (missing channels)</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="0" column="8">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Rev.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QComboBox" name="ch0Assign">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>MS Shell Dlg 2</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>16</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QLabel" name="ch0Cur">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>1500</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QLabel" name="ch0Min">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>1000</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4" colspan="3">
|
||||
<widget class="QSlider" name="inSlider0">
|
||||
<property name="mouseTracking">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>1000</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>2000</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="7">
|
||||
<widget class="QLabel" name="ch0Max">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>2000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="8">
|
||||
<widget class="QCheckBox" name="ch0Rev">
|
||||
<property name="toolTip">
|
||||
<string>Check this to reverse the channel.
|
||||
(Useful for transmitters without channel
|
||||
reversal capabilities).</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QComboBox" name="ch1Assign">
|
||||
<property name="font">
|
||||
@ -80,7 +260,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3" colspan="3">
|
||||
<item row="2" column="4" colspan="3">
|
||||
<widget class="QSlider" name="inSlider1">
|
||||
<property name="mouseTracking">
|
||||
<bool>true</bool>
|
||||
@ -99,7 +279,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<item row="2" column="7">
|
||||
<widget class="QLabel" name="ch1Max">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -120,7 +300,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="7">
|
||||
<item row="2" column="8">
|
||||
<widget class="QCheckBox" name="ch1Rev">
|
||||
<property name="toolTip">
|
||||
<string>Check this to reverse the channel.
|
||||
@ -188,7 +368,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3" colspan="3">
|
||||
<item row="3" column="4" colspan="3">
|
||||
<widget class="QSlider" name="inSlider2">
|
||||
<property name="mouseTracking">
|
||||
<bool>true</bool>
|
||||
@ -207,7 +387,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<item row="3" column="7">
|
||||
<widget class="QLabel" name="ch2Max">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -228,7 +408,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="7">
|
||||
<item row="3" column="8">
|
||||
<widget class="QCheckBox" name="ch2Rev">
|
||||
<property name="toolTip">
|
||||
<string>Check this to reverse the channel.
|
||||
@ -296,7 +476,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="3" colspan="3">
|
||||
<item row="4" column="4" colspan="3">
|
||||
<widget class="QSlider" name="inSlider3">
|
||||
<property name="mouseTracking">
|
||||
<bool>true</bool>
|
||||
@ -315,7 +495,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="6">
|
||||
<item row="4" column="7">
|
||||
<widget class="QLabel" name="ch3Max">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -336,7 +516,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="7">
|
||||
<item row="4" column="8">
|
||||
<widget class="QCheckBox" name="ch3Rev">
|
||||
<property name="toolTip">
|
||||
<string>Check this to reverse the channel.
|
||||
@ -404,7 +584,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="3" colspan="3">
|
||||
<item row="5" column="4" colspan="3">
|
||||
<widget class="QSlider" name="inSlider4">
|
||||
<property name="mouseTracking">
|
||||
<bool>true</bool>
|
||||
@ -423,7 +603,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="6">
|
||||
<item row="5" column="7">
|
||||
<widget class="QLabel" name="ch4Max">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -444,7 +624,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="7">
|
||||
<item row="5" column="8">
|
||||
<widget class="QCheckBox" name="ch4Rev">
|
||||
<property name="toolTip">
|
||||
<string>Check this to reverse the channel.
|
||||
@ -512,7 +692,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3" colspan="3">
|
||||
<item row="6" column="4" colspan="3">
|
||||
<widget class="QSlider" name="inSlider5">
|
||||
<property name="mouseTracking">
|
||||
<bool>true</bool>
|
||||
@ -531,7 +711,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="6">
|
||||
<item row="6" column="7">
|
||||
<widget class="QLabel" name="ch5Max">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -552,7 +732,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="7">
|
||||
<item row="6" column="8">
|
||||
<widget class="QCheckBox" name="ch5Rev">
|
||||
<property name="toolTip">
|
||||
<string>Check this to reverse the channel.
|
||||
@ -620,7 +800,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="3" colspan="3">
|
||||
<item row="7" column="4" colspan="3">
|
||||
<widget class="QSlider" name="inSlider6">
|
||||
<property name="mouseTracking">
|
||||
<bool>true</bool>
|
||||
@ -639,7 +819,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="6">
|
||||
<item row="7" column="7">
|
||||
<widget class="QLabel" name="ch6Max">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -660,7 +840,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="7">
|
||||
<item row="7" column="8">
|
||||
<widget class="QCheckBox" name="ch6Rev">
|
||||
<property name="toolTip">
|
||||
<string>Check this to reverse the channel.
|
||||
@ -728,7 +908,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="3" colspan="3">
|
||||
<item row="8" column="4" colspan="3">
|
||||
<widget class="QSlider" name="inSlider7">
|
||||
<property name="mouseTracking">
|
||||
<bool>true</bool>
|
||||
@ -747,7 +927,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="6">
|
||||
<item row="8" column="7">
|
||||
<widget class="QLabel" name="ch7Max">
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -768,7 +948,7 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="7">
|
||||
<item row="8" column="8">
|
||||
<widget class="QCheckBox" name="ch7Rev">
|
||||
<property name="toolTip">
|
||||
<string>Check this to reverse the channel.
|
||||
@ -800,7 +980,7 @@ Neutral should be put at the bottom of the slider for the throttle.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0" colspan="8">
|
||||
<item row="13" column="0" colspan="9">
|
||||
<widget class="QLabel" name="label_20">
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
@ -811,176 +991,19 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="7">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Rev.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="7">
|
||||
<widget class="QCheckBox" name="ch0Rev">
|
||||
<property name="toolTip">
|
||||
<string>Check this to reverse the channel.
|
||||
(Useful for transmitters without channel
|
||||
reversal capabilities).</string>
|
||||
<item row="10" column="0" colspan="9">
|
||||
<widget class="QLabel" name="lblMissingInputs">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<widget class="QLabel" name="ch0Max">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>2000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3" colspan="3">
|
||||
<widget class="QSlider" name="inSlider0">
|
||||
<property name="mouseTracking">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>1000</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>2000</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QLabel" name="ch0Min">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>1000</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QLabel" name="ch0Cur">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>FreeSans</family>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>1500</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QComboBox" name="ch0Assign">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>MS Shell Dlg 2</family>
|
||||
<pointsize>8</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>16</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3" colspan="4">
|
||||
<widget class="QLabel" name="RCInputConnected">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>11</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Indicates whether OpenPilot is getting a signal from the RC receiver.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RC Receiver not connected or invalid input configuration (missing channels)</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1" colspan="2">
|
||||
<widget class="QComboBox" name="receiverType">
|
||||
<property name="toolTip">
|
||||
<string>Select the receiver type here:
|
||||
- PWM is the most usual type
|
||||
- PPM is connected to input XXX
|
||||
- Spektrum is used with Spektrum 'satellite' receivers</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Receiver Type:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<widget class="QWidget" name="tab_3">
|
||||
|
@ -1539,6 +1539,50 @@
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Hexacopter>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-Q_+.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20X__PCT__20>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-Q_X.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20Quad__PCT__20X__PCT__20>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-QT_+.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20__PCT__2B>
|
||||
<Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20X>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
<version>0.0.0</version>
|
||||
</configInfo>
|
||||
<data>
|
||||
<acFilename>%%DATAPATH%%models/multi/joes_cnc/J14-QT_X.3DS</acFilename>
|
||||
<bgFilename>%%DATAPATH%%models/backgrounds/default_background.png</bgFilename>
|
||||
<enableVbo>false</enableVbo>
|
||||
</data>
|
||||
</Joe__PCT__27s__PCT__2014__PCT__22__PCT__20T__PCT__20Quad__PCT__20X>
|
||||
<Quadcopter>
|
||||
<configInfo>
|
||||
<locked>false</locked>
|
||||
|
@ -46,23 +46,23 @@ HITLWidget::HITLWidget(QWidget *parent)
|
||||
: QWidget(parent),
|
||||
simulator(0)
|
||||
{
|
||||
widget = new Ui_HITLWidget();
|
||||
widget->setupUi(this);
|
||||
widget = new Ui_HITLWidget();
|
||||
widget->setupUi(this);
|
||||
widget->startButton->setEnabled(true);
|
||||
widget->stopButton->setEnabled(false);
|
||||
|
||||
greenColor = "rgb(35, 221, 35)";
|
||||
|
||||
strAutopilotDisconnected = " Autopilot disconnected ";
|
||||
strSimulatorDisconnected = " Simulator disconnected ";
|
||||
strAutopilotConnected = " Autopilot connected ";
|
||||
strSimulatorConnected = " Simulator connected ";
|
||||
strAutopilotDisconnected = " Autopilot OFF ";
|
||||
strSimulatorDisconnected = " Simulator OFF ";
|
||||
strAutopilotConnected = " Autopilot ON ";
|
||||
strSimulatorConnected = " Simulator ON ";
|
||||
|
||||
widget->apLabel->setText(strAutopilotDisconnected);
|
||||
widget->simLabel->setText(strSimulatorDisconnected);
|
||||
|
||||
connect(widget->startButton, SIGNAL(clicked()), this, SLOT(startButtonClicked()));
|
||||
connect(widget->stopButton, SIGNAL(clicked()), this, SLOT(stopButtonClicked()));
|
||||
connect(widget->startButton, SIGNAL(clicked()), this, SLOT(startButtonClicked()));
|
||||
connect(widget->stopButton, SIGNAL(clicked()), this, SLOT(stopButtonClicked()));
|
||||
connect(widget->buttonClearLog, SIGNAL(clicked()), this, SLOT(buttonClearLogClicked()));
|
||||
|
||||
}
|
||||
@ -188,10 +188,9 @@ void HITLWidget::buttonClearLogClicked()
|
||||
|
||||
void HITLWidget::onAutopilotConnect()
|
||||
{
|
||||
widget->simLabel->setStyleSheet(QString::fromUtf8("QFrame{\n""background-color: %1; color: white}").arg(greenColor));
|
||||
|
||||
widget->apLabel->setStyleSheet(QString::fromUtf8("QFrame{\n""background-color: %1; color: white}").arg(greenColor));
|
||||
widget->apLabel->setText(strAutopilotConnected);
|
||||
qxtLog->info("HITL: Autopilot connected, initializing for HITL simulation");
|
||||
qxtLog->info("HITL: Autopilot connected, initializing for HITL simulation");
|
||||
}
|
||||
|
||||
void HITLWidget::onAutopilotDisconnect()
|
||||
@ -214,5 +213,3 @@ void HITLWidget::onSimulatorDisconnect()
|
||||
widget->simLabel->setText(" " + simulator->Name() +" disconnected ");
|
||||
qxtLog->info(QString("HITL: %1 disconnected").arg(simulator->Name()));
|
||||
}
|
||||
|
||||
|
||||
|
@ -31,7 +31,7 @@
|
||||
<property name="title">
|
||||
<string>Sound Collection</string>
|
||||
</property>
|
||||
<widget class="QWidget" name="layoutWidget">
|
||||
<widget class="QWidget" name="layoutWidget_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>10</x>
|
||||
|
@ -14,16 +14,16 @@ public:
|
||||
{
|
||||
switch (id | 0x0011) {
|
||||
case 0x0111://MB
|
||||
return QString("Board name: OpenPilot MainBoard");
|
||||
return QString("OpenPilot MainBoard");
|
||||
break;
|
||||
case 0x0311://PipX
|
||||
return QString("Board name: PipXtreame");
|
||||
return QString("PipXtreame");
|
||||
break;
|
||||
case 0x0411://Coptercontrol
|
||||
return QString("Board name: CopterControl");
|
||||
return QString("CopterControl");
|
||||
break;
|
||||
case 0x0211://INS
|
||||
return QString("Board name: OpenPilot INS");
|
||||
return QString("OpenPilot INS");
|
||||
break;
|
||||
default:
|
||||
return QString("");
|
||||
|
@ -82,16 +82,16 @@ QString deviceWidget::idToBoardName(int id)
|
||||
{
|
||||
switch (id | 0x0011) {
|
||||
case 0x0111://MB
|
||||
return QString("Board name: OpenPilot MainBoard");
|
||||
return QString("OpenPilot MainBoard");
|
||||
break;
|
||||
case 0x0311://PipX
|
||||
return QString("Board name: PipXtreame");
|
||||
return QString("PipXtreme");
|
||||
break;
|
||||
case 0x0411://Coptercontrol
|
||||
return QString("Board name: CopterControl");
|
||||
return QString("CopterControl");
|
||||
break;
|
||||
case 0x0211://INS
|
||||
return QString("Board name: OpenPilot INS");
|
||||
return QString("OpenPilot INS");
|
||||
break;
|
||||
default:
|
||||
return QString("");
|
||||
@ -141,7 +141,7 @@ void deviceWidget::populate()
|
||||
|
||||
myDevice->lblAccess->setText(QString("Flash access: ") + QString(r ? "R" : "-") + QString(w ? "W" : "-"));
|
||||
myDevice->lblMaxCode->setText(QString("Max code size: ") +QString::number(m_dfu->devices[deviceID].SizeOfCode));
|
||||
myDevice->lblCRC->setText(QString("Firmware CRC: ") + QString::number(m_dfu->devices[deviceID].FW_CRC));
|
||||
myDevice->lblCRC->setText(QString::number(m_dfu->devices[deviceID].FW_CRC));
|
||||
myDevice->lblBLVer->setText(QString("BL version: ") + QString::number(m_dfu->devices[deviceID].BL_Version));
|
||||
int size=((OP_DFU::device)m_dfu->devices[deviceID]).SizeOfDesc;
|
||||
m_dfu->enterDFU(deviceID);
|
||||
@ -182,8 +182,8 @@ bool deviceWidget::populateBoardStructuredDescription(QByteArray desc)
|
||||
{
|
||||
if(UploaderGadgetWidget::descriptionToStructure(desc,&onBoardDescrition))
|
||||
{
|
||||
myDevice->lblGitTag->setText("Git commit tag: "+onBoardDescrition.gitTag);
|
||||
myDevice->lblBuildDate->setText(QString("Firmware date: ") + onBoardDescrition.buildDate);
|
||||
myDevice->lblGitTag->setText(onBoardDescrition.gitTag);
|
||||
myDevice->lblBuildDate->setText(onBoardDescrition.buildDate);
|
||||
if(onBoardDescrition.description.startsWith("release",Qt::CaseInsensitive))
|
||||
{
|
||||
myDevice->lblDescription->setText(QString("Firmware tag: ")+onBoardDescrition.description);
|
||||
@ -194,7 +194,7 @@ bool deviceWidget::populateBoardStructuredDescription(QByteArray desc)
|
||||
}
|
||||
else
|
||||
{
|
||||
myDevice->lblDescription->setText(QString("Firmware tag: ")+onBoardDescrition.description+QString(" (beta or custom build)"));
|
||||
myDevice->lblDescription->setText(onBoardDescrition.description);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
|
||||
myDevice->lblCertified->setPixmap(pix);
|
||||
myDevice->lblCertified->setToolTip(tr("Custom Firmware Build"));
|
||||
@ -212,11 +212,11 @@ bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc)
|
||||
{
|
||||
if(UploaderGadgetWidget::descriptionToStructure(desc,&LoadedDescrition))
|
||||
{
|
||||
myDevice->lblGitTagL->setText("Git commit tag: "+LoadedDescrition.gitTag);
|
||||
myDevice->lblBuildDateL->setText(QString("Firmware date: ") + LoadedDescrition.buildDate);
|
||||
myDevice->lblGitTagL->setText(LoadedDescrition.gitTag);
|
||||
myDevice->lblBuildDateL->setText( LoadedDescrition.buildDate);
|
||||
if(LoadedDescrition.description.startsWith("release",Qt::CaseInsensitive))
|
||||
{
|
||||
myDevice->lblDescritpionL->setText(QString("Firmware tag: ")+LoadedDescrition.description);
|
||||
myDevice->lblDescritpionL->setText(LoadedDescrition.description);
|
||||
myDevice->description->setText(LoadedDescrition.description);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg"));
|
||||
myDevice->lblCertifiedL->setPixmap(pix);
|
||||
@ -224,7 +224,7 @@ bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc)
|
||||
}
|
||||
else
|
||||
{
|
||||
myDevice->lblDescritpionL->setText(QString("Firmware tag: ")+LoadedDescrition.description+QString(" (beta or custom build)"));
|
||||
myDevice->lblDescritpionL->setText(LoadedDescrition.description);
|
||||
myDevice->description->setText(LoadedDescrition.description);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
|
||||
myDevice->lblCertifiedL->setPixmap(pix);
|
||||
@ -303,8 +303,8 @@ void deviceWidget::loadFirmware()
|
||||
myDevice->youdont->setChecked(false);
|
||||
QByteArray desc = loadedFW.right(100);
|
||||
QPixmap px;
|
||||
myDevice->lblCRCL->setText(QString("FW CRC: ") + QString::number(DFUObject::CRCFromQBArray(loadedFW,m_dfu->devices[deviceID].SizeOfCode)));
|
||||
myDevice->lblFirmwareSizeL->setText(QString("Firmware size: ")+QVariant(loadedFW.length()).toString()+ QString(" bytes"));
|
||||
myDevice->lblCRCL->setText( QString::number(DFUObject::CRCFromQBArray(loadedFW,m_dfu->devices[deviceID].SizeOfCode)));
|
||||
//myDevice->lblFirmwareSizeL->setText(QString("Firmware size: ")+QVariant(loadedFW.length()).toString()+ QString(" bytes"));
|
||||
if (populateLoadedStructuredDescription(desc))
|
||||
{
|
||||
myDevice->youdont->setChecked(true);
|
||||
@ -312,7 +312,7 @@ void deviceWidget::loadFirmware()
|
||||
myDevice->groupCustom->setVisible(false);
|
||||
if(myDevice->lblCRC->text()==myDevice->lblCRCL->text())
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware maches the firmware on the board. You shouldn't upload it"));
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware the same as on the board. You should not upload it"));
|
||||
px.load(QString(":/uploader/images/warning.svg"));
|
||||
}
|
||||
else if(myDevice->lblDevName->text()!=myDevice->lblBrdNameL->text())
|
||||
@ -322,7 +322,7 @@ void deviceWidget::loadFirmware()
|
||||
}
|
||||
else if(QDateTime::fromString(onBoardDescrition.buildDate)>QDateTime::fromString(LoadedDescrition.buildDate))
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware is older then the firmware on the board. You shouldn't upload it"));
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware is older than the firmware on the board. You should not upload it"));
|
||||
px.load(QString(":/uploader/images/warning.svg"));
|
||||
}
|
||||
else if(!LoadedDescrition.description.startsWith("release",Qt::CaseInsensitive))
|
||||
@ -332,13 +332,13 @@ void deviceWidget::loadFirmware()
|
||||
}
|
||||
else
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("Everything seems OK. You should upload the loaded firmware by pressing 'upload'"));
|
||||
myDevice->statusLabel->setText(tr("Everything seems OK. You should upload the loaded firmware by pressing 'Flash'"));
|
||||
px.load(QString(":/uploader/images/gtk-info.svg"));
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware was not packaged with a compatible format. You shouldn't' upload it, if you know what you are doing and still want to upload it confirm it by checking the checkbox bellow"));
|
||||
myDevice->statusLabel->setText(tr("The loaded firmware was not packaged with the OpenPilot format. You should not upload it unless you know what you are doing."));
|
||||
px.load(QString(":/uploader/images/warning.svg"));
|
||||
myDevice->youdont->setChecked(false);
|
||||
myDevice->youdont->setVisible(true);
|
||||
@ -406,7 +406,7 @@ void deviceWidget::uploadFirmware()
|
||||
connect(m_dfu, SIGNAL(progressUpdated(int)), this, SLOT(setProgress(int)));
|
||||
connect(m_dfu, SIGNAL(operationProgress(QString)), this, SLOT(dfuStatus(QString)));
|
||||
connect(m_dfu, SIGNAL(uploadFinished(OP_DFU::Status)), this, SLOT(uploadFinished(OP_DFU::Status)));
|
||||
bool retstatus = m_dfu->UploadFirmware(filename.toAscii(),verify, deviceID);
|
||||
bool retstatus = m_dfu->UploadFirmware(filename,verify, deviceID);
|
||||
if(!retstatus ) {
|
||||
status("Could not start upload", STATUSICON_FAIL);
|
||||
return;
|
||||
|
@ -6,8 +6,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>516</width>
|
||||
<height>582</height>
|
||||
<width>576</width>
|
||||
<height>500</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
@ -33,86 +33,114 @@
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background: transparent</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_4">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_10">
|
||||
<item>
|
||||
<widget class="QLabel" name="lblDevName">
|
||||
<property name="text">
|
||||
<string>lblDevName</string>
|
||||
</property>
|
||||
</widget>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_7">
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_4">
|
||||
<item>
|
||||
<widget class="QLabel" name="lblDevName">
|
||||
<property name="text">
|
||||
<string>lblDevName</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lbldevID">
|
||||
<property name="text">
|
||||
<string>DeviceID</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblHWRev">
|
||||
<property name="text">
|
||||
<string>lblHWRev</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblAccess">
|
||||
<property name="text">
|
||||
<string>RW</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblBLVer">
|
||||
<property name="text">
|
||||
<string>BL Version</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblMaxCode">
|
||||
<property name="text">
|
||||
<string>MaxCodeSize</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_6">
|
||||
<item>
|
||||
<widget class="QPushButton" name="pbLoad">
|
||||
<property name="toolTip">
|
||||
<string>Loads the firmware</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Load...</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="youdont">
|
||||
<property name="text">
|
||||
<string>I know what I'm doing</string>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="updateButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Update the firmware on this board.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Flash</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="retrieveButton">
|
||||
<property name="toolTip">
|
||||
<string>Download the current board firmware to your computer</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Retrieve...</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lbldevID">
|
||||
<property name="text">
|
||||
<string>DeviceID</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblHWRev">
|
||||
<property name="text">
|
||||
<string>lblHWRev</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblAccess">
|
||||
<property name="text">
|
||||
<string>RW</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblBLVer">
|
||||
<property name="text">
|
||||
<string>BL Version</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblMaxCode">
|
||||
<property name="text">
|
||||
<string>MaxCodeSize</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_6">
|
||||
<item>
|
||||
<widget class="QPushButton" name="pbLoad">
|
||||
<property name="toolTip">
|
||||
<string>Loads the firmware</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Open</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="updateButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Update the firmware on this board.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Flash</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="retrieveButton">
|
||||
<property name="toolTip">
|
||||
<string>Download the current board firmware to your computer</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Retrieve...</string>
|
||||
<widget class="QProgressBar" name="progressBar">
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
@ -120,13 +148,6 @@
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QProgressBar" name="progressBar">
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
@ -160,149 +181,211 @@
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="youdont">
|
||||
<property name="text">
|
||||
<string>I know what I'm doing</string>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="verticalGroupBox_3">
|
||||
<property name="title">
|
||||
<string>Firmware currently on the device</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_5">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_4">
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="title">
|
||||
<string>Firmware:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_9">
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_8">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string>Board name:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>Description:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="text">
|
||||
<string>Build date:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="text">
|
||||
<string>GIT Tag:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>CRC:</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="verticalGroupBox_3">
|
||||
<property name="title">
|
||||
<string>On Device</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_5">
|
||||
<item>
|
||||
<widget class="QLabel" name="lblBrdName">
|
||||
<property name="text">
|
||||
<string>lblBrdName</string>
|
||||
</property>
|
||||
</widget>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_8">
|
||||
<item>
|
||||
<widget class="QLabel" name="lblBrdName">
|
||||
<property name="text">
|
||||
<string>lblBrdName</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblDescription">
|
||||
<property name="text">
|
||||
<string>lblDescription</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblBuildDate">
|
||||
<property name="text">
|
||||
<string>lblBuildDate</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblGitTag">
|
||||
<property name="text">
|
||||
<string>lblGitTag</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblCRC">
|
||||
<property name="text">
|
||||
<string>lblCRC</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblDescription">
|
||||
<widget class="QLabel" name="lblCertified">
|
||||
<property name="text">
|
||||
<string>lblDescription</string>
|
||||
<string>lblCertified</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblBuildDate">
|
||||
<property name="text">
|
||||
<string>lblBuildDate</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblGitTag">
|
||||
<property name="text">
|
||||
<string>lblGitTag</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblCRC">
|
||||
<property name="text">
|
||||
<string>lblCRC</string>
|
||||
<property name="scaledContents">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblCertified">
|
||||
<property name="text">
|
||||
<string>lblCertified</string>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="verticalGroupBox_loaded">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Loaded Firmware</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="verticalGroupBox_loaded">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Loaded</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<widget class="QLabel" name="lblBrdNameL">
|
||||
<property name="text">
|
||||
<string>lblBrdName</string>
|
||||
</property>
|
||||
</widget>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<item>
|
||||
<widget class="QLabel" name="lblBrdNameL">
|
||||
<property name="text">
|
||||
<string>lblBrdName</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblDescritpionL">
|
||||
<property name="text">
|
||||
<string>lblDescritpionL</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblBuildDateL">
|
||||
<property name="text">
|
||||
<string>lblBuildDate</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblGitTagL">
|
||||
<property name="text">
|
||||
<string>lblGitTag</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblCRCL">
|
||||
<property name="text">
|
||||
<string>lblCRC</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblDescritpionL">
|
||||
<widget class="QLabel" name="lblCertifiedL">
|
||||
<property name="text">
|
||||
<string>lblDescritpionL</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblBuildDateL">
|
||||
<property name="text">
|
||||
<string>lblBuildDate</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblGitTagL">
|
||||
<property name="text">
|
||||
<string>lblGitTag</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblCRCL">
|
||||
<property name="text">
|
||||
<string>lblCRC</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblFirmwareSizeL">
|
||||
<property name="text">
|
||||
<string>lblFirmwareSizeL</string>
|
||||
<string>lblCertifiedL</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblCertifiedL">
|
||||
<property name="text">
|
||||
<string>lblCertifiedL</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupCustom">
|
||||
|
@ -1,102 +1,35 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Generator: Adobe Illustrator 15.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
|
||||
|
||||
<svg
|
||||
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||
xmlns:cc="http://creativecommons.org/ns#"
|
||||
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||
xmlns:svg="http://www.w3.org/2000/svg"
|
||||
xmlns="http://www.w3.org/2000/svg"
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
version="1.1"
|
||||
id="Layer_1"
|
||||
x="0px"
|
||||
y="0px"
|
||||
width="51.537998"
|
||||
height="46.021885"
|
||||
viewBox="0 0 51.538001 46.021886"
|
||||
enable-background="new 0 0 514.475 473.977"
|
||||
xml:space="preserve"
|
||||
inkscape:version="0.48.1 "
|
||||
sodipodi:docname="warning_s.svg"><metadata
|
||||
id="metadata3095"><rdf:RDF><cc:Work
|
||||
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
|
||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title /></cc:Work></rdf:RDF></metadata><defs
|
||||
id="defs3093" /><sodipodi:namedview
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1"
|
||||
objecttolerance="10"
|
||||
gridtolerance="10"
|
||||
guidetolerance="10"
|
||||
inkscape:pageopacity="0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:window-width="1280"
|
||||
inkscape:window-height="738"
|
||||
id="namedview3091"
|
||||
showgrid="false"
|
||||
inkscape:zoom="1.0949899"
|
||||
inkscape:cx="249.10624"
|
||||
inkscape:cy="125.11088"
|
||||
inkscape:window-x="-8"
|
||||
inkscape:window-y="-8"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:current-layer="Layer_1"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
fit-margin-bottom="0" />
|
||||
<radialGradient
|
||||
id="SVGID_1_"
|
||||
cx="255.45261"
|
||||
cy="231.6748"
|
||||
r="206.35049"
|
||||
gradientTransform="matrix(0.1182761,0,0,0.12913623,-4.4457028,-6.9088686)"
|
||||
gradientUnits="userSpaceOnUse">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFDE17"
|
||||
id="stop3074" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#ABA01F"
|
||||
id="stop3076" />
|
||||
</radialGradient>
|
||||
<path
|
||||
stroke-miterlimit="10"
|
||||
d="M 1.2974519,42.730481 C -1.4443604,39.150401 21.620352,1.0717714 25.887967,1.0717714 c 4.269682,0 27.060213,38.8621096 24.35608,41.6587096 -3.013913,3.11312 -46.8075615,2.80177 -48.9465951,0 z"
|
||||
id="path3078"
|
||||
style="fill:url(#SVGID_1_);stroke:#000000;stroke-width:2.14355946;stroke-miterlimit:10"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 22.987071,36.405661 c 0,-1.55651 1.465096,-2.59423 3.118544,-2.59423 1.674394,0 3.013911,1.03772 3.013911,2.59423 0,1.55658 -1.255794,2.59427 -3.118542,2.59427 -1.674391,0 -3.034841,-1.03769 -3.034841,-2.59427 z m 1.465096,-5.24042 c -0.627898,-0.77824 -1.67439,-20.36495 -0.627898,-21.3507596 0.837188,-0.77831 3.872026,-0.77831 4.604571,0 0.8372,0.7782796 -0.209304,20.8059796 -0.627897,21.3507596 -0.418602,0.51889 -2.762741,0.51889 -3.265057,0 z"
|
||||
id="path3080"
|
||||
inkscape:connector-curvature="0" />
|
||||
<linearGradient
|
||||
id="SVGID_2_"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="256.45209"
|
||||
y1="304.9277"
|
||||
x2="256.45209"
|
||||
y2="48.449699"
|
||||
gradientTransform="matrix(0.11827613,0,0,0.10761355,-4.4457031,-1.9220086)">
|
||||
<stop
|
||||
offset="0"
|
||||
style="stop-color:#FFFFFF"
|
||||
id="stop3083" />
|
||||
<stop
|
||||
offset="0.0896"
|
||||
style="stop-color:#FFFFFF;stop-opacity:0.9104"
|
||||
id="stop3085" />
|
||||
<stop
|
||||
offset="1"
|
||||
style="stop-color:#FFFFFF;stop-opacity:0"
|
||||
id="stop3087" />
|
||||
</linearGradient>
|
||||
<path
|
||||
d="M 10.709612,23.014111 C 16.695555,12.974321 23.623336,3.2976914 25.779115,3.2976914 c 2.197635,0 9.313793,10.2991996 15.320665,20.7021496 5.651063,9.75447 -36.2902985,8.92436 -30.396443,-1.03772 z"
|
||||
id="path3089"
|
||||
style="opacity:0.31999996;fill:url(#SVGID_2_)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</svg>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
<svg id="svg3247" xmlns="http://www.w3.org/2000/svg" height="48" width="48" version="1.0" xmlns:xlink="http://www.w3.org/1999/xlink">
|
||||
<defs id="defs3249">
|
||||
<linearGradient id="linearGradient2411" y2="5.4676" gradientUnits="userSpaceOnUse" x2="63.397" gradientTransform="matrix(2.1154 0 0 2.1153 -107.58 32.427)" y1="-12.489" x1="63.397">
|
||||
<stop id="stop4875" style="stop-color:#fff" offset="0"/>
|
||||
<stop id="stop4877" style="stop-color:#fff;stop-opacity:0" offset="1"/>
|
||||
</linearGradient>
|
||||
<linearGradient id="linearGradient2416" y2="3.0816" gradientUnits="userSpaceOnUse" x2="18.379" gradientTransform="matrix(.95844 0 0 .95844 .99752 1.9975)" y1="44.98" x1="18.379">
|
||||
<stop id="stop2492" style="stop-color:#791235" offset="0"/>
|
||||
<stop id="stop2494" style="stop-color:#dd3b27" offset="1"/>
|
||||
</linearGradient>
|
||||
<radialGradient id="radialGradient2414" gradientUnits="userSpaceOnUse" cy="3.99" cx="23.896" gradientTransform="matrix(0 2.2875 -3.0194 0 36.047 -50.63)" r="20.397">
|
||||
<stop id="stop3244" style="stop-color:#f8b17e" offset="0"/>
|
||||
<stop id="stop3246" style="stop-color:#e35d4f" offset=".26238"/>
|
||||
<stop id="stop3248" style="stop-color:#c6262e" offset=".66094"/>
|
||||
<stop id="stop3250" style="stop-color:#690b54" offset="1"/>
|
||||
</radialGradient>
|
||||
<radialGradient id="radialGradient2419" gradientUnits="userSpaceOnUse" cy="4.625" cx="62.625" gradientTransform="matrix(2.1647 0 0 .75294 -111.56 36.518)" r="10.625">
|
||||
<stop id="stop8840" offset="0"/>
|
||||
<stop id="stop8842" style="stop-opacity:0" offset="1"/>
|
||||
</radialGradient>
|
||||
</defs>
|
||||
<g id="layer1">
|
||||
<g id="g3275">
|
||||
<path id="path8836" style="opacity:.3;fill-rule:evenodd;fill:url(#radialGradient2419)" d="m47 40c0 4.418-10.297 8-23 8s-23-3.582-23-8 10.297-8 23-8 23 3.582 23 8z"/>
|
||||
<path id="path2555" style="stroke-linejoin:round;stroke:url(#linearGradient2416);stroke-linecap:round;stroke-width:1.0037;fill:url(#radialGradient2414)" d="m24 5.5018c-10.758 0-19.498 8.7402-19.498 19.498-0.0002 10.758 8.74 19.498 19.498 19.498s19.498-8.74 19.498-19.498-8.74-19.498-19.498-19.498z"/>
|
||||
<path id="path8655" style="opacity:.4;stroke:url(#linearGradient2411);fill:none" d="m42.5 24.999c0 10.218-8.283 18.501-18.5 18.501s-18.5-8.283-18.5-18.501c0-10.217 8.283-18.499 18.5-18.499s18.5 8.282 18.5 18.499z"/>
|
||||
</g>
|
||||
<g id="g3243" transform="translate(51.075 .56862)">
|
||||
<path id="path3295" style="opacity:.2" d="m-29.451 12.554c0.563 5.5 1.208 10.961 1.687 16.482h1.53c0.397-5.302 1.038-10.571 1.501-15.867 0.236-1.254-0.408-2.742-1.732-3.047-1.308-0.3824-2.77 0.565-2.944 1.918-0.029 0.17-0.042 0.342-0.042 0.514zm-0.167 22.359c-0.059 1.637 1.742 2.92 3.28 2.401 1.489-0.38 2.274-2.252 1.51-3.583-0.683-1.375-2.687-1.829-3.84-0.776-0.582 0.479-0.968 1.194-0.95 1.958z"/>
|
||||
<path id="text2315" style="fill:#fff" d="m-29.451 13.555c0.563 5.499 1.208 10.96 1.687 16.481h1.53c0.397-5.301 1.038-10.571 1.501-15.866 0.236-1.254-0.408-2.743-1.732-3.048-1.308-0.382-2.77 0.565-2.944 1.918-0.029 0.17-0.042 0.342-0.042 0.515zm-0.167 22.358c-0.059 1.637 1.742 2.921 3.28 2.402 1.489-0.381 2.274-2.253 1.51-3.584-0.683-1.375-2.687-1.828-3.84-0.776-0.582 0.479-0.968 1.194-0.95 1.958z"/>
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
||||
|
Before Width: | Height: | Size: 3.6 KiB After Width: | Height: | Size: 3.2 KiB |
@ -37,8 +37,10 @@ runningDeviceWidget::runningDeviceWidget(QWidget *parent) :
|
||||
// Initialization of the Device icon display
|
||||
myDevice->devicePicture->setScene(new QGraphicsScene(this));
|
||||
|
||||
/*
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/view-refresh.svg"));
|
||||
myDevice->statusIcon->setPixmap(pix);
|
||||
*/
|
||||
}
|
||||
|
||||
|
||||
@ -104,7 +106,7 @@ void runningDeviceWidget::populate()
|
||||
myDevice->devicePicture->fitInView(devicePic,Qt::KeepAspectRatio);
|
||||
|
||||
QString serial = utilMngr->getBoardCPUSerial().toHex();
|
||||
myDevice->lblCPU->setText(QString("CPU serial number: "+serial));
|
||||
myDevice->CPUSerial->setText(serial);
|
||||
|
||||
QByteArray description = utilMngr->getBoardDescription();
|
||||
deviceDescriptorStruct devDesc;
|
||||
@ -120,7 +122,7 @@ void runningDeviceWidget::populate()
|
||||
}
|
||||
else
|
||||
{
|
||||
myDevice->lblFWTag->setText(QString("Firmware tag: ")+devDesc.description+QString(" (beta or custom build)"));
|
||||
myDevice->lblFWTag->setText(QString("Firmware tag: ")+devDesc.description);
|
||||
QPixmap pix = QPixmap(QString(":uploader/images/warning.svg"));
|
||||
myDevice->lblCertified->setPixmap(pix);
|
||||
myDevice->lblCertified->setToolTip(tr("Custom Firmware Build"));
|
||||
@ -138,13 +140,14 @@ void runningDeviceWidget::populate()
|
||||
myDevice->lblCertified->setPixmap(pix);
|
||||
myDevice->lblCertified->setToolTip(tr("Custom Firmware Build"));
|
||||
}
|
||||
status("Ready...", STATUSICON_INFO);
|
||||
//status("Ready...", STATUSICON_INFO);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
Updates status message
|
||||
*/
|
||||
/*
|
||||
void runningDeviceWidget::status(QString str, StatusIcon ic)
|
||||
{
|
||||
QPixmap px;
|
||||
@ -164,3 +167,4 @@ void runningDeviceWidget::status(QString str, StatusIcon ic)
|
||||
}
|
||||
myDevice->statusIcon->setPixmap(px);
|
||||
}
|
||||
*/
|
||||
|
@ -55,7 +55,7 @@ private:
|
||||
Ui_runningDeviceWidget *myDevice;
|
||||
int deviceID;
|
||||
QGraphicsSvgItem *devicePic;
|
||||
void status(QString str, StatusIcon ic);
|
||||
//void status(QString str, StatusIcon ic);
|
||||
|
||||
|
||||
signals:
|
||||
|
@ -7,7 +7,7 @@
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>516</width>
|
||||
<height>253</height>
|
||||
<height>299</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
@ -34,6 +34,15 @@
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Plain</enum>
|
||||
</property>
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
@ -60,11 +69,22 @@
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="lblCPU">
|
||||
<property name="text">
|
||||
<string>TextLabel</string>
|
||||
</property>
|
||||
</widget>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="lblCPU">
|
||||
<property name="text">
|
||||
<string>CPU Serial:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLineEdit" name="CPUSerial">
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
@ -119,40 +139,6 @@
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<item row="3" column="0" colspan="2">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="statusIcon">
|
||||
<property name="text">
|
||||
<string>ic</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="statusLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Status</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
|
@ -19,14 +19,10 @@ PACKAGE_DIR := $(BUILD_DIR)/package-$(PACKAGE_LBL)
|
||||
FW_DIR := $(PACKAGE_DIR)/firmware-$(PACKAGE_LBL)
|
||||
BL_DIR := $(FW_DIR)/bootloaders
|
||||
BU_DIR := $(FW_DIR)/bootloader-updaters
|
||||
FE_DIR := $(FW_DIR)/flash-erase-tools
|
||||
|
||||
# Clean build options (recommended for package testing only)
|
||||
ifeq ($(CLEAN_BUILD), NO)
|
||||
CLEAN_GROUND := NO
|
||||
CLEAN_FLIGHT := YES
|
||||
else ifeq ($(CLEAN_BUILD), NEVER)
|
||||
CLEAN_GROUND := NO
|
||||
CLEAN_FLIGHT := NO
|
||||
else
|
||||
CLEAN_GROUND := YES
|
||||
@ -34,11 +30,7 @@ CLEAN_FLIGHT := YES
|
||||
endif
|
||||
|
||||
# Set up targets (PPM target seems to be broken at the moment)
|
||||
FW_TARGETS_COMMON := $(addprefix fw_, ahrs pipxtreme)
|
||||
FW_TARGETS_PWM := $(addprefix fw_, coptercontrol openpilot)
|
||||
FW_TARGETS_DSM2 := $(addprefix fw_, coptercontrol openpilot)
|
||||
FW_TARGETS_SBUS := $(addprefix fw_, coptercontrol)
|
||||
FW_TARGETS_PPM := $(addprefix fw_, openpilot)
|
||||
FW_TARGETS := $(addprefix fw_, ahrs pipxtreme coptercontrol openpilot)
|
||||
FW_TARGETS_TOOLS := $(addprefix fw_, coptercontrol)
|
||||
BL_TARGETS := $(addprefix bl_, coptercontrol openpilot ahrs pipxtreme)
|
||||
BU_TARGETS := $(addprefix bu_, coptercontrol openpilot ahrs pipxtreme)
|
||||
@ -57,16 +49,9 @@ help:
|
||||
@echo " Notes:"
|
||||
@echo " - package will be placed in $(PACKAGE_DIR)"
|
||||
@echo
|
||||
@echo " - the build directory will be removed first on every run unless one"
|
||||
@echo " of CLEAN_BUILD=NO or CLEAN_BUILD=NEVER options is defined."
|
||||
@echo
|
||||
@echo " CLEAN_BUILD=NO means no clean before build except for multi-input"
|
||||
@echo " firmware binaries like CopterControl or OpenPilot. This usually is"
|
||||
@echo " safe."
|
||||
@echo
|
||||
@echo " CLEAN_BUILD=NEVER means no clean will be done at all. This will,"
|
||||
@echo " probably, give invalid multi-input firmware and is recommended"
|
||||
@echo " for package testing only. Do not use for release builds."
|
||||
@echo " - the build directory will be removed first on every run unless"
|
||||
@echo " CLEAN_BUILD=NO is defined. It means no clean before build."
|
||||
@echo " This usually is safe."
|
||||
@echo
|
||||
|
||||
# Clean and build uavobjects since all parts depend on them
|
||||
@ -99,12 +84,8 @@ endif
|
||||
.PHONY: $(1)
|
||||
endef
|
||||
|
||||
# Firmware for different input drivers
|
||||
$(eval $(call INSTALL_TEMPLATE,fw_common,uavobjects,$(FW_DIR),,-$(PACKAGE_LBL),,,$(FW_TARGETS_COMMON),install))
|
||||
$(eval $(call INSTALL_TEMPLATE,fw_pwm,uavobjects,$(FW_DIR),,-pwm-$(PACKAGE_LBL),,clean,$(FW_TARGETS_PWM),install))
|
||||
$(eval $(call INSTALL_TEMPLATE,fw_dsm2,uavobjects,$(FW_DIR),,-dsm2sat-$(PACKAGE_LBL),USE_SPEKTRUM=YES,clean,$(FW_TARGETS_DSM2),install))
|
||||
$(eval $(call INSTALL_TEMPLATE,fw_sbus,uavobjects,$(FW_DIR),,-sbus-$(PACKAGE_LBL),USE_SBUS=YES USE_TELEMETRY=3,clean,$(FW_TARGETS_SBUS),install))
|
||||
$(eval $(call INSTALL_TEMPLATE,fw_ppm,uavobjects,$(FW_DIR),,-ppm-$(PACKAGE_LBL),USE_PPM=YES,clean,$(FW_TARGETS_PPM),install))
|
||||
# Firmware
|
||||
$(eval $(call INSTALL_TEMPLATE,all_fw,uavobjects,$(FW_DIR),,-$(PACKAGE_LBL),,,$(FW_TARGETS),install))
|
||||
|
||||
# Bootloaders (change 'install' to 'bin' if you don't want to install bootloaders)
|
||||
$(eval $(call INSTALL_TEMPLATE,all_bl,uavobjects,$(BL_DIR),,-$(PACKAGE_LBL),,,$(BL_TARGETS),install))
|
||||
@ -112,34 +93,14 @@ $(eval $(call INSTALL_TEMPLATE,all_bl,uavobjects,$(BL_DIR),,-$(PACKAGE_LBL),,,$(
|
||||
# Bootloader updaters
|
||||
$(eval $(call INSTALL_TEMPLATE,all_bu,all_bl,$(BU_DIR),,-$(PACKAGE_LBL),,,$(BU_TARGETS),install))
|
||||
|
||||
# CopterControl flash eraser tool
|
||||
$(eval $(call INSTALL_TEMPLATE,fw_tools,uavobjects,$(FE_DIR),,-flash-erase-$(PACKAGE_LBL),ERASE_FLASH=YES,clean,$(FW_TARGETS_TOOLS),install))
|
||||
|
||||
# Order-only dependencies
|
||||
# They are bit complicated to support parallel (-j) builds and to create
|
||||
# the pwm/ppm/spektrum and CC flash eraser targets in some fixed order
|
||||
|
||||
fw_pwm: | # default dependencies, will be built first
|
||||
|
||||
fw_dsm2: | fw_pwm # ordered build
|
||||
|
||||
fw_sbus: | fw_dsm2 # ordered build
|
||||
|
||||
fw_ppm: | fw_sbus # ordered build
|
||||
|
||||
fw_tools: | fw_ppm # ordered build
|
||||
|
||||
package_fw: | fw_common fw_pwm fw_dsm2 fw_sbus fw_ppm
|
||||
|
||||
package_bu: | all_bu
|
||||
|
||||
package_flight: | package_fw package_bu fw_tools
|
||||
package_flight: | all_fw all_bu
|
||||
|
||||
package_ground: | ground_package
|
||||
|
||||
package: | package_flight package_ground
|
||||
|
||||
.PHONY: help uavobjects all_clean package package_flight package_fw package_bu package_ground
|
||||
.PHONY: help uavobjects all_clean package_flight package_ground package
|
||||
|
||||
# Decide on a verbosity level based on the V= parameter
|
||||
export AT := @
|
||||
|
@ -2,12 +2,14 @@
|
||||
<object name="AttitudeSettings" singleinstance="true" settings="true">
|
||||
<description>Settings for the @ref Attitude module used on CopterControl</description>
|
||||
<field name="AccelBias" units="lsb" type="int16" elementnames="X,Y,Z" defaultvalue="0"/>
|
||||
<field name="GyroBias" units="deg/s * 100" type="int16" elementnames="X,Y,Z" defaultvalue="0"/>
|
||||
<field name="BoardRotation" units="deg" type="int16" elementnames="Roll,Pitch,Yaw" defaultvalue="0,0,0"/>
|
||||
<field name="GyroGain" units="(rad/s)/lsb" type="float" elements="1" defaultvalue="0.42"/>
|
||||
<field name="AccelKp" units="channel" type="float" elements="1" defaultvalue="0.03"/>
|
||||
<field name="AccelKi" units="channel" type="float" elements="1" defaultvalue="0.0001"/>
|
||||
<field name="YawBiasRate" units="channel" type="float" elements="1" defaultvalue="0.000001"/>
|
||||
<field name="ZeroDuringArming" units="channel" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="ZeroDuringArming" units="channel" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<field name="BiasCorrectGyro" units="channel" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -11,15 +11,15 @@
|
||||
<field name="Accessory1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="Accessory2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
|
||||
<field name="Arming" units="" type="enum" elements="1" options="Always Disarmed,Always Armed,Roll Left,Roll Right,Pitch Forward,Pitch Aft,Yaw Left,Yaw Right" defaultvalue="Always Disarmed"/>
|
||||
|
||||
|
||||
<!-- Note these options should be identical to those in StabilizationDesired.StabilizationMode -->
|
||||
<field name="Stabilization1Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude" defaultvalue="Attitude,Attitude,Rate"/>
|
||||
<field name="Stabilization2Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude" defaultvalue="Attitude,Attitude,Rate"/>
|
||||
<field name="Stabilization3Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude" defaultvalue="Attitude,Attitude,Rate"/>
|
||||
|
||||
<field name="Stabilization1Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling" defaultvalue="Attitude,Attitude,Rate"/>
|
||||
<field name="Stabilization2Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling" defaultvalue="Attitude,Attitude,Rate"/>
|
||||
<field name="Stabilization3Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling" defaultvalue="Attitude,Attitude,Rate"/>
|
||||
|
||||
<!-- Note these options values should be identical to those defined in FlightMode -->
|
||||
<field name="FlightModePosition" units="" type="enum" elements="3" options="Manual,Stabilized1,Stabilized2,Stabilized3,VelocityControl,PositionHold" defaultvalue="Manual,Stabilized1,Stabilized2"/>
|
||||
|
||||
|
||||
<field name="ChannelMax" units="us" type="int16" elements="8" defaultvalue="2000"/>
|
||||
<field name="ChannelNeutral" units="us" type="int16" elements="8" defaultvalue="1500"/>
|
||||
<field name="ChannelMin" units="us" type="int16" elements="8" defaultvalue="1000"/>
|
||||
|
@ -6,7 +6,7 @@
|
||||
<field name="Yaw" units="degrees" type="float" elements="1"/>
|
||||
<field name="Throttle" units="%" type="float" elements="1"/>
|
||||
<!-- These values should match those in ManualControlCommand.Stabilization{1,2,3}Settings -->
|
||||
<field name="StabilizationMode" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude"/>
|
||||
<field name="StabilizationMode" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="false" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="false" updatemode="periodic" period="1000"/>
|
||||
|
@ -7,13 +7,21 @@
|
||||
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,150"/>
|
||||
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300"/>
|
||||
|
||||
<field name="RollRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.002,0,0.3"/>
|
||||
<field name="PitchRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.002,0,0.3"/>
|
||||
<field name="YawRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.0035,0.0035,0.3"/>
|
||||
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.002,0,0,0.3"/>
|
||||
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.002,0,0,0.3"/>
|
||||
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3"/>
|
||||
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
|
||||
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
|
||||
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
|
||||
|
||||
|
||||
<field name="GyroTau" units="" type="float" elements="1" defaultvalue="0.005"/>
|
||||
|
||||
<field name="MaxAxisLock" units="deg" type="uint8" elements="1" defaultvalue="5"/>
|
||||
<field name="MaxAxisLockRate" units="deg/s" type="uint8" elements="1" defaultvalue="2"/>
|
||||
|
||||
<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"/>
|
||||
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -3,6 +3,7 @@
|
||||
<description>CPU and memory usage from OpenPilot computer. </description>
|
||||
<field name="FlightTime" units="ms" type="uint32" elements="1"/>
|
||||
<field name="HeapRemaining" units="bytes" type="uint16" elements="1"/>
|
||||
<field name="IRQStackRemaining" units="bytes" type="uint16" elements="1"/>
|
||||
<field name="CPULoad" units="%" type="uint8" elements="1"/>
|
||||
<field name="CPUTemp" units="C" type="int8" elements="1"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
|