1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-11-29 07:24:13 +01:00

Merge branch 'next' into thread/OP-39

This commit is contained in:
Fredrik Arvidsson 2012-09-29 09:43:50 +02:00
commit 3b9e50ad51
41 changed files with 7457 additions and 2128 deletions

View File

@ -434,7 +434,7 @@ int32_t PIOS_BMA180_Test()
* @brief IRQ Handler. Read data from the BMA180 FIFO and push onto a local fifo. * @brief IRQ Handler. Read data from the BMA180 FIFO and push onto a local fifo.
*/ */
int32_t bma180_irqs = 0; int32_t bma180_irqs = 0;
void PIOS_BMA180_IRQHandler(void) bool PIOS_BMA180_IRQHandler(void)
{ {
bma180_irqs++; bma180_irqs++;
@ -471,6 +471,7 @@ void PIOS_BMA180_IRQHandler(void)
fifoBuf_putData(&dev->fifo, (uint8_t *) &data, sizeof(data)); fifoBuf_putData(&dev->fifo, (uint8_t *) &data, sizeof(data));
return false;
} }
#endif /* PIOS_INCLUDE_BMA180 */ #endif /* PIOS_INCLUDE_BMA180 */

View File

@ -391,9 +391,11 @@ int32_t PIOS_HMC5883_Test(void)
/** /**
* @brief IRQ Handler * @brief IRQ Handler
*/ */
void PIOS_HMC5883_IRQHandler(void) bool PIOS_HMC5883_IRQHandler(void)
{ {
pios_hmc5883_data_ready = true; pios_hmc5883_data_ready = true
return false;
} }
#endif /* PIOS_INCLUDE_HMC5883 */ #endif /* PIOS_INCLUDE_HMC5883 */

View File

@ -353,7 +353,7 @@ uint8_t PIOS_L3GD20_Test(void)
/** /**
* @brief IRQ Handler. Read all the data from onboard buffer * @brief IRQ Handler. Read all the data from onboard buffer
*/ */
void PIOS_L3GD20_IRQHandler(void) bool PIOS_L3GD20_IRQHandler(void)
{ {
l3gd20_irq++; l3gd20_irq++;
@ -375,7 +375,10 @@ void PIOS_L3GD20_IRQHandler(void)
memcpy((uint8_t *) &(data.gyro_x), &rec[1], 6); memcpy((uint8_t *) &(data.gyro_x), &rec[1], 6);
data.temperature = PIOS_L3GD20_GetReg(PIOS_L3GD20_OUT_TEMP); data.temperature = PIOS_L3GD20_GetReg(PIOS_L3GD20_OUT_TEMP);
xQueueSend(dev->queue, (void *) &data, 0); portBASE_TYPE xHigherPriorityTaskWoken;
xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken);
return xHigherPriorityTaskWoken == pdTRUE;
} }
#endif /* L3GD20 */ #endif /* L3GD20 */

View File

@ -400,21 +400,21 @@ uint32_t mpu6000_interval_us;
uint32_t mpu6000_time_us; uint32_t mpu6000_time_us;
uint32_t mpu6000_transfer_size; uint32_t mpu6000_transfer_size;
void PIOS_MPU6000_IRQHandler(void) bool PIOS_MPU6000_IRQHandler(void)
{ {
static uint32_t timeval; static uint32_t timeval;
mpu6000_interval_us = PIOS_DELAY_DiffuS(timeval); mpu6000_interval_us = PIOS_DELAY_DiffuS(timeval);
timeval = PIOS_DELAY_GetRaw(); timeval = PIOS_DELAY_GetRaw();
if(!mpu6000_configured) if(!mpu6000_configured)
return; return false;
mpu6000_count = PIOS_MPU6000_FifoDepth(); mpu6000_count = PIOS_MPU6000_FifoDepth();
if(mpu6000_count < sizeof(struct pios_mpu6000_data)) if(mpu6000_count < sizeof(struct pios_mpu6000_data))
return; return false;
if(PIOS_MPU6000_ClaimBus() != 0) if(PIOS_MPU6000_ClaimBus() != 0)
return; return false;
uint8_t mpu6000_send_buf[1+sizeof(struct pios_mpu6000_data)] = {PIOS_MPU6000_FIFO_REG | 0x80, 0, 0, 0, 0, 0, 0, 0, 0}; uint8_t mpu6000_send_buf[1+sizeof(struct pios_mpu6000_data)] = {PIOS_MPU6000_FIFO_REG | 0x80, 0, 0, 0, 0, 0, 0, 0, 0};
uint8_t mpu6000_rec_buf[1+sizeof(struct pios_mpu6000_data)]; uint8_t mpu6000_rec_buf[1+sizeof(struct pios_mpu6000_data)];
@ -422,7 +422,7 @@ void PIOS_MPU6000_IRQHandler(void)
if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) {
PIOS_MPU6000_ReleaseBus(); PIOS_MPU6000_ReleaseBus();
mpu6000_fails++; mpu6000_fails++;
return; return false;
} }
PIOS_MPU6000_ReleaseBus(); PIOS_MPU6000_ReleaseBus();
@ -433,15 +433,12 @@ void PIOS_MPU6000_IRQHandler(void)
if (mpu6000_count >= (sizeof(data) * 2)) { if (mpu6000_count >= (sizeof(data) * 2)) {
mpu6000_fifo_backup++; mpu6000_fifo_backup++;
if(PIOS_MPU6000_ClaimBus() != 0) if(PIOS_MPU6000_ClaimBus() != 0)
return; return false;
uint8_t mpu6000_send_buf[1+sizeof(struct pios_mpu6000_data)] = {PIOS_MPU6000_FIFO_REG | 0x80, 0, 0, 0, 0, 0, 0, 0, 0};
uint8_t mpu6000_rec_buf[1+sizeof(struct pios_mpu6000_data)];
if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) {
PIOS_MPU6000_ReleaseBus(); PIOS_MPU6000_ReleaseBus();
mpu6000_fails++; mpu6000_fails++;
return; return false;
} }
PIOS_MPU6000_ReleaseBus(); PIOS_MPU6000_ReleaseBus();
@ -462,11 +459,14 @@ void PIOS_MPU6000_IRQHandler(void)
data.gyro_z = mpu6000_rec_buf[7] << 8 | mpu6000_rec_buf[8]; data.gyro_z = mpu6000_rec_buf[7] << 8 | mpu6000_rec_buf[8];
#endif #endif
xQueueSend(dev->queue, (void *) &data, 0); portBASE_TYPE xHigherPriorityTaskWoken;
xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken);
mpu6000_irq++; mpu6000_irq++;
mpu6000_time_us = PIOS_DELAY_DiffuS(timeval); mpu6000_time_us = PIOS_DELAY_DiffuS(timeval);
return xHigherPriorityTaskWoken == pdTRUE;
} }
#endif #endif

View File

@ -172,7 +172,7 @@ uint32_t random32 = 0x459ab8d8;
/* Local function forwared declarations */ /* Local function forwared declarations */
static void PIOS_RFM22B_Supervisor(uint32_t ppm_id); static void PIOS_RFM22B_Supervisor(uint32_t ppm_id);
static void rfm22_processInt(void); static void rfm22_processInt(void);
static void PIOS_RFM22_EXT_Int(void); static bool PIOS_RFM22_EXT_Int(void);
static void rfm22_setTxMode(uint8_t mode); static void rfm22_setTxMode(uint8_t mode);
// SPI read/write functions // SPI read/write functions
@ -751,12 +751,13 @@ uint8_t rfm22_read(uint8_t addr)
// external interrupt // external interrupt
static void PIOS_RFM22_EXT_Int(void) static bool PIOS_RFM22_EXT_Int(void)
{ {
rfm22_setDebug("Ext Int"); rfm22_setDebug("Ext Int");
if (!exec_using_spi) if (!exec_using_spi)
rfm22_processInt(); rfm22_processInt();
rfm22_setDebug("Ext Done"); rfm22_setDebug("Ext Done");
return false;
} }
void rfm22_disableExtInt(void) void rfm22_disableExtInt(void)

View File

@ -149,7 +149,7 @@ out_fail:
return -1; return -1;
} }
static void PIOS_EXTI_generic_irq_handler(uint8_t line_index) static bool PIOS_EXTI_generic_irq_handler(uint8_t line_index)
{ {
uint8_t cfg_index = pios_exti_line_to_cfg_map[line_index]; uint8_t cfg_index = pios_exti_line_to_cfg_map[line_index];
@ -158,69 +158,133 @@ static void PIOS_EXTI_generic_irq_handler(uint8_t line_index)
if (cfg_index > NELEMENTS(pios_exti_line_to_cfg_map) || if (cfg_index > NELEMENTS(pios_exti_line_to_cfg_map) ||
cfg_index == PIOS_EXTI_INVALID) { cfg_index == PIOS_EXTI_INVALID) {
/* Unconfigured interrupt just fired! */ /* Unconfigured interrupt just fired! */
return; return false;
} }
struct pios_exti_cfg * cfg = &__start__exti + cfg_index; struct pios_exti_cfg * cfg = &__start__exti + cfg_index;
cfg->vector(); return cfg->vector();
} }
/* Bind Interrupt Handlers */ #ifdef PIOS_INCLUDE_FREERTOS
#define PIOS_EXTI_HANDLE_LINE(line, woken) \
#define PIOS_EXTI_HANDLE_LINE(line) \ if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \
EXTI_ClearITPendingBit(EXTI_Line##line); \
woken = PIOS_EXTI_generic_irq_handler(line) ? pdTRUE : woken; \
}
#else
#define PIOS_EXTI_HANDLE_LINE(line, woken) \
if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \ if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \
EXTI_ClearITPendingBit(EXTI_Line##line); \ EXTI_ClearITPendingBit(EXTI_Line##line); \
PIOS_EXTI_generic_irq_handler(line); \ PIOS_EXTI_generic_irq_handler(line); \
} }
#endif
/* Bind Interrupt Handlers */
static void PIOS_EXTI_0_irq_handler (void) static void PIOS_EXTI_0_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(0); #ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
#endif
PIOS_EXTI_HANDLE_LINE(0, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI0_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_0_irq_handler"))); void EXTI0_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_0_irq_handler")));
static void PIOS_EXTI_1_irq_handler (void) static void PIOS_EXTI_1_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(1); #ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
#endif
PIOS_EXTI_HANDLE_LINE(1, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI1_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_1_irq_handler"))); void EXTI1_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_1_irq_handler")));
static void PIOS_EXTI_2_irq_handler (void) static void PIOS_EXTI_2_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(2); #ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
#endif
PIOS_EXTI_HANDLE_LINE(2, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI2_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_2_irq_handler"))); void EXTI2_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_2_irq_handler")));
static void PIOS_EXTI_3_irq_handler (void) static void PIOS_EXTI_3_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(3); #ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
#endif
PIOS_EXTI_HANDLE_LINE(3, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI3_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_3_irq_handler"))); void EXTI3_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_3_irq_handler")));
static void PIOS_EXTI_4_irq_handler (void) static void PIOS_EXTI_4_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(4); #ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken; // dummy variable
#endif
PIOS_EXTI_HANDLE_LINE(4, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI4_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_4_irq_handler"))); void EXTI4_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_4_irq_handler")));
static void PIOS_EXTI_9_5_irq_handler (void) static void PIOS_EXTI_9_5_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(5); #ifdef PIOS_INCLUDE_FREERTOS
PIOS_EXTI_HANDLE_LINE(6); portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
PIOS_EXTI_HANDLE_LINE(7); #else
PIOS_EXTI_HANDLE_LINE(8); bool xHigherPriorityTaskWoken; // dummy variable
PIOS_EXTI_HANDLE_LINE(9); #endif
PIOS_EXTI_HANDLE_LINE(5, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(6, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(7, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(8, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(9, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI9_5_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_9_5_irq_handler"))); void EXTI9_5_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_9_5_irq_handler")));
static void PIOS_EXTI_15_10_irq_handler (void) static void PIOS_EXTI_15_10_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(10); #ifdef PIOS_INCLUDE_FREERTOS
PIOS_EXTI_HANDLE_LINE(11); portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
PIOS_EXTI_HANDLE_LINE(12); #else
PIOS_EXTI_HANDLE_LINE(13); bool xHigherPriorityTaskWoken; // dummy variable
PIOS_EXTI_HANDLE_LINE(14); #endif
PIOS_EXTI_HANDLE_LINE(15); PIOS_EXTI_HANDLE_LINE(10, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(11, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(12, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(13, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(14, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(15, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI15_10_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_15_10_irq_handler"))); void EXTI15_10_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_15_10_irq_handler")));

View File

@ -321,7 +321,10 @@ RESULT PIOS_USB_CDC_SetControlLineState(void)
struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
PIOS_Assert(valid); if (!valid) {
/* No CDC interface is configured */
return USB_UNSUPPORT;
}
uint8_t wValue0 = pInformation->USBwValue0; uint8_t wValue0 = pInformation->USBwValue0;
uint8_t wValue1 = pInformation->USBwValue1; uint8_t wValue1 = pInformation->USBwValue1;
@ -338,14 +341,25 @@ static struct usb_cdc_line_coding line_coding = {
.bDataBits = 8, .bDataBits = 8,
}; };
RESULT PIOS_USB_CDC_SetLineCoding(void) uint8_t *PIOS_USB_CDC_SetLineCoding(uint16_t Length)
{ {
struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
PIOS_Assert(valid); if (!valid) {
/* No CDC interface is configured */
return NULL;
}
return USB_SUCCESS; if (Length == 0) {
/* Report the number of bytes we're prepared to consume */
pInformation->Ctrl_Info.Usb_wLength = sizeof(line_coding);
pInformation->Ctrl_Info.Usb_rLength = sizeof(line_coding);
return NULL;
} else {
/* Give out a pointer to the data struct */
return ((uint8_t *) &line_coding);
}
} }
const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length) const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length)
@ -353,7 +367,10 @@ const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length)
struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
PIOS_Assert(valid); if (!valid) {
/* No CDC interface is configured */
return NULL;
}
if (Length == 0) { if (Length == 0) {
pInformation->Ctrl_Info.Usb_wLength = sizeof(line_coding); pInformation->Ctrl_Info.Usb_wLength = sizeof(line_coding);

View File

@ -293,13 +293,16 @@ static void PIOS_USBHOOK_Status_Out(void)
* Output : None. * Output : None.
* Return : USB_UNSUPPORT or USB_SUCCESS. * Return : USB_UNSUPPORT or USB_SUCCESS.
*******************************************************************************/ *******************************************************************************/
extern uint8_t *PIOS_USB_CDC_SetLineCoding(uint16_t Length);
extern const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length); extern const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length);
static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo) static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
{ {
const uint8_t *(*CopyRoutine) (uint16_t); uint8_t *(*CopyOutRoutine) (uint16_t);
const uint8_t *(*CopyInRoutine) (uint16_t);
CopyRoutine = NULL; CopyInRoutine = NULL;
CopyOutRoutine = NULL;
switch (Type_Recipient) { switch (Type_Recipient) {
case (STANDARD_REQUEST | INTERFACE_RECIPIENT): case (STANDARD_REQUEST | INTERFACE_RECIPIENT):
@ -313,10 +316,10 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
case GET_DESCRIPTOR: case GET_DESCRIPTOR:
switch (pInformation->USBwValue1) { switch (pInformation->USBwValue1) {
case USB_DESC_TYPE_REPORT: case USB_DESC_TYPE_REPORT:
CopyRoutine = PIOS_USBHOOK_GetReportDescriptor; CopyInRoutine = PIOS_USBHOOK_GetReportDescriptor;
break; break;
case USB_DESC_TYPE_HID: case USB_DESC_TYPE_HID:
CopyRoutine = PIOS_USBHOOK_GetHIDDescriptor; CopyInRoutine = PIOS_USBHOOK_GetHIDDescriptor;
break; break;
} }
} }
@ -332,7 +335,7 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
#endif #endif
switch (RequestNo) { switch (RequestNo) {
case USB_HID_REQ_GET_PROTOCOL: case USB_HID_REQ_GET_PROTOCOL:
CopyRoutine = PIOS_USBHOOK_GetProtocolValue; CopyInRoutine = PIOS_USBHOOK_GetProtocolValue;
break; break;
} }
@ -340,8 +343,11 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
#if defined(PIOS_INCLUDE_USB_CDC) #if defined(PIOS_INCLUDE_USB_CDC)
case 0: /* CDC Call Control Interface */ case 0: /* CDC Call Control Interface */
switch (RequestNo) { switch (RequestNo) {
case USB_CDC_REQ_SET_LINE_CODING:
CopyOutRoutine = PIOS_USB_CDC_SetLineCoding;
break;
case USB_CDC_REQ_GET_LINE_CODING: case USB_CDC_REQ_GET_LINE_CODING:
//CopyRoutine = PIOS_USB_CDC_GetLineCoding; CopyInRoutine = PIOS_USB_CDC_GetLineCoding;
break; break;
} }
@ -359,13 +365,27 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
break; break;
} }
if (CopyRoutine == NULL) { /* No registered copy routine */
if ((CopyInRoutine == NULL) && (CopyOutRoutine == NULL)) {
return USB_UNSUPPORT; return USB_UNSUPPORT;
} }
pInformation->Ctrl_Info.CopyDataIn = CopyRoutine; /* Registered copy in AND copy out routine */
if ((CopyInRoutine != NULL) && (CopyOutRoutine != NULL)) {
/* This should never happen */
return USB_UNSUPPORT;
}
if (CopyInRoutine != NULL) {
pInformation->Ctrl_Info.CopyDataIn = CopyInRoutine;
pInformation->Ctrl_Info.Usb_wOffset = 0; pInformation->Ctrl_Info.Usb_wOffset = 0;
(*CopyRoutine) (0); (*CopyInRoutine) (0);
} else if (CopyOutRoutine != NULL) {
pInformation->Ctrl_Info.CopyDataOut = CopyOutRoutine;
pInformation->Ctrl_Info.Usb_rOffset = 0;
(*CopyOutRoutine) (0);
}
return USB_SUCCESS; return USB_SUCCESS;
} }
@ -377,7 +397,6 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
* Return : USB_UNSUPPORT or USB_SUCCESS. * Return : USB_UNSUPPORT or USB_SUCCESS.
*******************************************************************************/ *******************************************************************************/
extern RESULT PIOS_USB_CDC_SetControlLineState(void); extern RESULT PIOS_USB_CDC_SetControlLineState(void);
extern RESULT PIOS_USB_CDC_SetLineCoding(void);
static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo) static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo)
{ {
@ -400,9 +419,6 @@ static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo)
#if defined(PIOS_INCLUDE_USB_CDC) #if defined(PIOS_INCLUDE_USB_CDC)
case 0: /* CDC Call Control Interface */ case 0: /* CDC Call Control Interface */
switch (RequestNo) { switch (RequestNo) {
case USB_CDC_REQ_SET_LINE_CODING:
return PIOS_USB_CDC_SetLineCoding();
break;
case USB_CDC_REQ_SET_CONTROL_LINE_STATE: case USB_CDC_REQ_SET_CONTROL_LINE_STATE:
return PIOS_USB_CDC_SetControlLineState(); return PIOS_USB_CDC_SetControlLineState();
break; break;

View File

@ -149,7 +149,7 @@ out_fail:
return -1; return -1;
} }
static void PIOS_EXTI_generic_irq_handler(uint8_t line_index) static bool PIOS_EXTI_generic_irq_handler(uint8_t line_index)
{ {
uint8_t cfg_index = pios_exti_line_to_cfg_map[line_index]; uint8_t cfg_index = pios_exti_line_to_cfg_map[line_index];
@ -158,69 +158,133 @@ static void PIOS_EXTI_generic_irq_handler(uint8_t line_index)
if (cfg_index > NELEMENTS(pios_exti_line_to_cfg_map) || if (cfg_index > NELEMENTS(pios_exti_line_to_cfg_map) ||
cfg_index == PIOS_EXTI_INVALID) { cfg_index == PIOS_EXTI_INVALID) {
/* Unconfigured interrupt just fired! */ /* Unconfigured interrupt just fired! */
return; return false;
} }
struct pios_exti_cfg * cfg = &__start__exti + cfg_index; struct pios_exti_cfg * cfg = &__start__exti + cfg_index;
cfg->vector(); return cfg->vector();
} }
/* Bind Interrupt Handlers */ /* Bind Interrupt Handlers */
#define PIOS_EXTI_HANDLE_LINE(line) \ #ifdef PIOS_INCLUDE_FREERTOS
#define PIOS_EXTI_HANDLE_LINE(line, woken) \
if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \
EXTI_ClearITPendingBit(EXTI_Line##line); \
woken = PIOS_EXTI_generic_irq_handler(line) ? pdTRUE : woken; \
}
#else
#define PIOS_EXTI_HANDLE_LINE(line, woken) \
if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \ if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \
EXTI_ClearITPendingBit(EXTI_Line##line); \ EXTI_ClearITPendingBit(EXTI_Line##line); \
PIOS_EXTI_generic_irq_handler(line); \ PIOS_EXTI_generic_irq_handler(line); \
} }
#endif
static void PIOS_EXTI_0_irq_handler (void) static void PIOS_EXTI_0_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(0); #ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(0, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI0_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_0_irq_handler"))); void EXTI0_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_0_irq_handler")));
static void PIOS_EXTI_1_irq_handler (void) static void PIOS_EXTI_1_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(1); #ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(1, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI1_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_1_irq_handler"))); void EXTI1_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_1_irq_handler")));
static void PIOS_EXTI_2_irq_handler (void) static void PIOS_EXTI_2_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(2); #ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(2, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI2_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_2_irq_handler"))); void EXTI2_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_2_irq_handler")));
static void PIOS_EXTI_3_irq_handler (void) static void PIOS_EXTI_3_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(3); #ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(3, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI3_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_3_irq_handler"))); void EXTI3_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_3_irq_handler")));
static void PIOS_EXTI_4_irq_handler (void) static void PIOS_EXTI_4_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(4); #ifdef PIOS_INCLUDE_FREERTOS
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
#else
bool xHigherPriorityTaskWoken;
#endif
PIOS_EXTI_HANDLE_LINE(4, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI4_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_4_irq_handler"))); void EXTI4_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_4_irq_handler")));
static void PIOS_EXTI_9_5_irq_handler (void) static void PIOS_EXTI_9_5_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(5); #ifdef PIOS_INCLUDE_FREERTOS
PIOS_EXTI_HANDLE_LINE(6); portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
PIOS_EXTI_HANDLE_LINE(7); #else
PIOS_EXTI_HANDLE_LINE(8); bool xHigherPriorityTaskWoken;
PIOS_EXTI_HANDLE_LINE(9); #endif
PIOS_EXTI_HANDLE_LINE(5, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(6, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(7, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(8, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(9, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI9_5_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_9_5_irq_handler"))); void EXTI9_5_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_9_5_irq_handler")));
static void PIOS_EXTI_15_10_irq_handler (void) static void PIOS_EXTI_15_10_irq_handler (void)
{ {
PIOS_EXTI_HANDLE_LINE(10); #ifdef PIOS_INCLUDE_FREERTOS
PIOS_EXTI_HANDLE_LINE(11); portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
PIOS_EXTI_HANDLE_LINE(12); #else
PIOS_EXTI_HANDLE_LINE(13); bool xHigherPriorityTaskWoken;
PIOS_EXTI_HANDLE_LINE(14); #endif
PIOS_EXTI_HANDLE_LINE(15); PIOS_EXTI_HANDLE_LINE(10, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(11, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(12, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(13, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(14, xHigherPriorityTaskWoken);
PIOS_EXTI_HANDLE_LINE(15, xHigherPriorityTaskWoken);
#ifdef PIOS_INCLUDE_FREERTOS
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
#endif
} }
void EXTI15_10_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_15_10_irq_handler"))); void EXTI15_10_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_15_10_irq_handler")));

View File

@ -103,7 +103,7 @@ extern float PIOS_BMA180_GetScale();
extern int32_t PIOS_BMA180_ReadFifo(struct pios_bma180_data * buffer); extern int32_t PIOS_BMA180_ReadFifo(struct pios_bma180_data * buffer);
extern int32_t PIOS_BMA180_ReadAccels(struct pios_bma180_data * data); extern int32_t PIOS_BMA180_ReadAccels(struct pios_bma180_data * data);
extern int32_t PIOS_BMA180_Test(); extern int32_t PIOS_BMA180_Test();
extern void PIOS_BMA180_IRQHandler(); extern bool PIOS_BMA180_IRQHandler();
#endif /* PIOS_BMA180_H */ #endif /* PIOS_BMA180_H */

View File

@ -36,7 +36,7 @@
#include <pios_stm32.h> #include <pios_stm32.h>
struct pios_exti_cfg { struct pios_exti_cfg {
void (* vector)(void); bool (* vector)(void);
uint32_t line; /* use EXTI_LineN macros */ uint32_t line; /* use EXTI_LineN macros */
struct stm32_gpio pin; struct stm32_gpio pin;
struct stm32_irq irq; struct stm32_irq irq;

View File

@ -107,7 +107,7 @@ extern bool PIOS_HMC5883_NewDataAvailable(void);
extern int32_t PIOS_HMC5883_ReadMag(int16_t out[3]); extern int32_t PIOS_HMC5883_ReadMag(int16_t out[3]);
extern uint8_t PIOS_HMC5883_ReadID(uint8_t out[4]); extern uint8_t PIOS_HMC5883_ReadID(uint8_t out[4]);
extern int32_t PIOS_HMC5883_Test(void); extern int32_t PIOS_HMC5883_Test(void);
extern void PIOS_HMC5883_IRQHandler(); bool void PIOS_HMC5883_IRQHandler();
#endif /* PIOS_HMC5883_H */ #endif /* PIOS_HMC5883_H */
/** /**

View File

@ -141,7 +141,7 @@ extern int32_t PIOS_L3GD20_SetRange(enum pios_l3gd20_range range);
extern float PIOS_L3GD20_GetScale(); extern float PIOS_L3GD20_GetScale();
extern int32_t PIOS_L3GD20_ReadID(); extern int32_t PIOS_L3GD20_ReadID();
extern uint8_t PIOS_L3GD20_Test(); extern uint8_t PIOS_L3GD20_Test();
extern void PIOS_L3GD20_IRQHandler(); bool void PIOS_L3GD20_IRQHandler();
#endif /* PIOS_L3GD20_H */ #endif /* PIOS_L3GD20_H */

View File

@ -156,7 +156,7 @@ extern int32_t PIOS_MPU6000_ReadID();
extern uint8_t PIOS_MPU6000_Test(); extern uint8_t PIOS_MPU6000_Test();
extern float PIOS_MPU6000_GetScale(); extern float PIOS_MPU6000_GetScale();
extern float PIOS_MPU6000_GetAccelScale(); extern float PIOS_MPU6000_GetAccelScale();
extern void PIOS_MPU6000_IRQHandler(void); extern bool PIOS_MPU6000_IRQHandler(void);
#endif /* PIOS_MPU6000_H */ #endif /* PIOS_MPU6000_H */

View File

@ -267,7 +267,7 @@ enum usb_cdc_requests {
USB_CDC_REQ_SET_LINE_CODING = 0x20, USB_CDC_REQ_SET_LINE_CODING = 0x20,
USB_CDC_REQ_GET_LINE_CODING = 0x21, USB_CDC_REQ_GET_LINE_CODING = 0x21,
USB_CDC_REQ_SET_CONTROL_LINE_STATE = 0x23, USB_CDC_REQ_SET_CONTROL_LINE_STATE = 0x22,
}; };
struct usb_cdc_header_func_desc { struct usb_cdc_header_func_desc {

View File

@ -38,15 +38,18 @@
namespace Utils { namespace Utils {
HomeLocationUtil::HomeLocationUtil() HomeLocationUtil::HomeLocationUtil()
{ {
// Initialize(); }
}
// input params: LLA /*
// /**
// output params: ECEF, RNE and Be * @brief Get local magnetic field
int HomeLocationUtil::getDetails(double LLA[3], double ECEF[3], double RNE[9], double Be[3]) * @param[in] LLA The longitude-latitude-altitude coordinate to compute the magnetic field at
* @param[out] Be The resulting magnetic field at that location and time in [mGau](?)
* @returns 0 if successful, -1 otherwise.
*/
int HomeLocationUtil::getDetails(double LLA[3], double Be[3])
{ {
// ************* // *************
// check input parms // check input parms
@ -66,10 +69,8 @@ namespace Utils {
QDateTime dt = QDateTime::currentDateTime().toUTC(); QDateTime dt = QDateTime::currentDateTime().toUTC();
CoordinateConversions().LLA2ECEF(LLA, ECEF); //Fetch world magnetic model
CoordinateConversions().RneFromLLA(LLA, (double (*)[3])RNE); Q_ASSERT(WorldMagModel().GetMagVector(LLA, dt.date().month(), dt.date().day(), dt.date().year(), Be) >= 0);
if (WorldMagModel().GetMagVector(LLA, dt.date().month(), dt.date().day(), dt.date().year(), Be) < 0)
return -6;
return 0; // OK return 0; // OK
} }

View File

@ -40,7 +40,7 @@ namespace Utils {
public: public:
HomeLocationUtil(); HomeLocationUtil();
int getDetails(double LLA[3], double ECEF[3], double RNE[9], double Be[3]); int getDetails(double LLA[3], double Be[3]);
private: private:

View File

@ -14,9 +14,6 @@
<string>Form</string> <string>Form</string>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_10"> <layout class="QVBoxLayout" name="verticalLayout_10">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>
@ -132,7 +129,7 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>935</width> <width>935</width>
<height>554</height> <height>537</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QVBoxLayout" name="verticalLayout">
@ -145,9 +142,6 @@
<string/> <string/>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_2"> <layout class="QVBoxLayout" name="verticalLayout_2">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>
@ -705,12 +699,12 @@ margin:1px;</string>
</widget> </widget>
<widget class="QWidget" name="multiRotor"> <widget class="QWidget" name="multiRotor">
<layout class="QGridLayout" name="gridLayout_7" columnstretch="0,0,0"> <layout class="QGridLayout" name="gridLayout_7" columnstretch="0,0,0">
<property name="verticalSpacing">
<number>24</number>
</property>
<property name="margin"> <property name="margin">
<number>0</number> <number>0</number>
</property> </property>
<property name="verticalSpacing">
<number>-1</number>
</property>
<item row="0" column="0"> <item row="0" column="0">
<widget class="QGroupBox" name="groupBox_10"> <widget class="QGroupBox" name="groupBox_10">
<property name="minimumSize"> <property name="minimumSize">
@ -853,7 +847,7 @@ margin:1px;</string>
<item row="0" column="2"> <item row="0" column="2">
<widget class="QGroupBox" name="groupBox_6"> <widget class="QGroupBox" name="groupBox_6">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -1098,7 +1092,7 @@ margin:1px;</string>
Typical value is 50% for + or X configuration on quads.</string> Typical value is 50% for + or X configuration on quads.</string>
</property> </property>
<property name="minimum"> <property name="minimum">
<number>-100</number> <number>0</number>
</property> </property>
<property name="maximum"> <property name="maximum">
<number>100</number> <number>100</number>
@ -1191,7 +1185,7 @@ margin:1px;</string>
<item row="1" column="0" colspan="3"> <item row="1" column="0" colspan="3">
<widget class="QGroupBox" name="groupBox"> <widget class="QGroupBox" name="groupBox">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -1456,7 +1450,7 @@ font: bold 12px;
margin:1px;</string> margin:1px;</string>
</property> </property>
<property name="text"> <property name="text">
<string>Multirotor Yaw Direction</string> <string>Multirotor Motor Direction</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignCenter</set> <set>Qt::AlignCenter</set>
@ -1512,9 +1506,9 @@ margin:1px;</string>
</widget> </widget>
</item> </item>
<item row="3" column="4"> <item row="3" column="4">
<widget class="QCheckBox" name="TricopterRevMixercheckBox"> <widget class="QCheckBox" name="MultirotorRevMixercheckBox">
<property name="text"> <property name="text">
<string>Reverse Yaw Mix</string> <string>Reverse all motors</string>
</property> </property>
</widget> </widget>
</item> </item>
@ -2820,7 +2814,7 @@ margin:1px;</string>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>935</width> <width>935</width>
<height>554</height> <height>537</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_18"> <layout class="QVBoxLayout" name="verticalLayout_18">
@ -2836,9 +2830,6 @@ margin:1px;</string>
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>
<property name="spacing">
<number>6</number>
</property>
<item row="2" column="0" colspan="3"> <item row="2" column="0" colspan="3">
<layout class="QHBoxLayout" name="horizontalLayout_10"> <layout class="QHBoxLayout" name="horizontalLayout_10">
<item> <item>
@ -3206,14 +3197,15 @@ p, li { white-space: pre-wrap; }
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt; <string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt; &lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; } p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&gt; &lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt; &lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt;
&lt;tr&gt; &lt;tr&gt;
&lt;td style=&quot;border: none;&quot;&gt; &lt;td style=&quot;border: none;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD REQUIRES CAUTION&lt;/span&gt;&lt;/p&gt; &lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD REQUIRES CAUTION&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;&lt;/p&gt; &lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;&lt;br /&gt;&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.&lt;/span&gt;&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string> &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!&lt;/p&gt;
&lt;p style=&quot; margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property> </property>
</widget> </widget>
</item> </item>
@ -3264,7 +3256,7 @@ p, li { white-space: pre-wrap; }
<string/> <string/>
</property> </property>
<property name="icon"> <property name="icon">
<iconset resource="E:/Users/Chris/Desktop/src/plugins/coreplugin/core.qrc"> <iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset> <normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property> </property>
<property name="iconSize"> <property name="iconSize">
@ -3317,7 +3309,7 @@ p, li { white-space: pre-wrap; }
</customwidget> </customwidget>
</customwidgets> </customwidgets>
<resources> <resources>
<include location="E:/Users/Chris/Desktop/src/plugins/coreplugin/core.qrc"/> <include location="../coreplugin/core.qrc"/>
</resources> </resources>
<connections> <connections>
<connection> <connection>

View File

@ -6,22 +6,214 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>443</width> <width>739</width>
<height>575</height> <height>688</height>
</rect> </rect>
</property> </property>
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="windowTitle"> <property name="windowTitle">
<string>Form</string> <string>Form</string>
</property> </property>
<widget class="QGroupBox" name="groupBox"> <layout class="QVBoxLayout" name="verticalLayout_2">
<property name="spacing">
<number>6</number>
</property>
<property name="margin">
<number>12</number>
</property>
<item>
<widget class="QTabWidget" name="Autotune_tabs">
<property name="currentIndex">
<number>0</number>
</property>
<widget class="QWidget" name="Preautotune_tab">
<attribute name="title">
<string>Pre-Autotune</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_5">
<property name="margin">
<number>12</number>
</property>
<item row="3" column="0" colspan="3">
<widget class="QTextEdit" name="textEdit">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Sunken</enum>
</property>
<property name="html">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:20pt; font-weight:600; color:#ff0000;&quot;&gt;WARNING:&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;&lt;br /&gt;&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;This is an experimental plugin for the GCS that is going to make your aircraft shake, etc, so test with lots of space and be &lt;/span&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt; font-weight:600;&quot;&gt;very very wary&lt;/span&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt; for it creating bad tuning values.  Basically there is no reason to think this will work at all.&lt;br /&gt;&lt;br /&gt;To use autotuning, here are the steps:&lt;br /&gt;&lt;/span&gt;&lt;/p&gt;
&lt;ul style=&quot;margin-top: 0px; margin-bottom: 0px; margin-left: 0px; margin-right: 0px; -qt-list-indent: 1;&quot;&gt;&lt;li style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;On the &lt;span style=&quot; font-style:italic;&quot;&gt;Input configuration&lt;/span&gt; tab, &lt;span style=&quot; font-style:italic;&quot;&gt;Flight Mode Switch Settings&lt;/span&gt;, set one of your flight modes to &amp;quot;Autotune&amp;quot;.&lt;br /&gt;&lt;/li&gt;
&lt;li style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Take off, change flight mode to autotune, keep it in the air while it's shaking.&lt;br /&gt;&lt;/li&gt;
&lt;li style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Land and disarm.  (note - you &lt;span style=&quot; font-weight:600;&quot;&gt;MUST&lt;/span&gt; stay in autotune mode through this point, leaving autotune before disarming aborts the process)&lt;br /&gt;&lt;/li&gt;
&lt;li style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;We'd recommend checking your stabilization settings before trying them out (ie: compare to what you currently use, if they are VASTLY different, probably a good indication bad things will happen).&lt;br /&gt;&lt;/li&gt;
&lt;li style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot; style=&quot; margin-top:0px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Test fly the new settings.&lt;/li&gt;
&lt;li style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot; style=&quot; margin-top:0px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;If you're ready to proceed, click the &lt;span style=&quot; font-style:italic;&quot;&gt;Enable Autotune Module&lt;/span&gt; checkbox above this text, click &lt;span style=&quot; font-style:italic;&quot;&gt;save&lt;/span&gt; and go to the next tab.&lt;/li&gt;&lt;/ul&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
<item row="2" column="0" colspan="3">
<widget class="QGroupBox" name="groupBox_5">
<property name="title">
<string>Module Control</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QCheckBox" name="enableAutoTune">
<property name="text">
<string>Enable Autotune Module</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>454</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
<zorder>horizontalSpacer_5</zorder>
<zorder>enableAutoTune</zorder>
<zorder>horizontalSpacer_4</zorder>
<zorder>enableAutoTune</zorder>
<zorder>horizontalSpacer_5</zorder>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="autotune_tab">
<attribute name="title">
<string>Autotune Setup</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_3">
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>20</x> <x>0</x>
<y>10</y> <y>0</y>
<width>401</width> <width>711</width>
<height>131</height> <height>596</height>
</rect> </rect>
</property> </property>
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="autoFillBackground">
<bool>true</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<property name="spacing">
<number>12</number>
</property>
<property name="margin">
<number>12</number>
</property>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="title"> <property name="title">
<string>Tuning Aggressiveness</string> <string>Tuning Aggressiveness</string>
</property> </property>
@ -78,128 +270,9 @@
</item> </item>
</layout> </layout>
</widget> </widget>
<widget class="QGroupBox" name="groupBox_2">
<property name="geometry">
<rect>
<x>20</x>
<y>250</y>
<width>401</width>
<height>121</height>
</rect>
</property>
<property name="title">
<string>Computed Values</string>
</property>
<layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="1">
<widget class="QLabel" name="label_5">
<property name="text">
<string>RateKp</string>
</property>
</widget>
</item> </item>
<item row="1" column="0"> <item>
<widget class="QLabel" name="label_4">
<property name="text">
<string>Roll</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_9">
<property name="text">
<string>RateKi</string>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_10">
<property name="text">
<string>AttitudeKp</string>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="label_11">
<property name="text">
<string>AttitudeKi</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_12">
<property name="text">
<string>Pitch</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="rollRateKp">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLabel" name="pitchRateKp">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="rollRateKi">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLabel" name="pitchRateKi">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="rollAttitudeKp">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QLabel" name="pitchAttitudeKp">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="rollAttitudeKi">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QLabel" name="pitchAttitudeKi">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QGroupBox" name="groupBox_3"> <widget class="QGroupBox" name="groupBox_3">
<property name="geometry">
<rect>
<x>20</x>
<y>140</y>
<width>401</width>
<height>111</height>
</rect>
</property>
<property name="title"> <property name="title">
<string>Measured Properties</string> <string>Measured Properties</string>
</property> </property>
@ -302,770 +375,144 @@
</item> </item>
</layout> </layout>
</widget> </widget>
<widget class="QGroupBox" name="RateStabilizationGroup_21"> </item>
<property name="geometry"> <item>
<rect> <widget class="QGroupBox" name="groupBox_2">
<x>20</x>
<y>480</y>
<width>401</width>
<height>79</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>79</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>79</height>
</size>
</property>
<property name="palette">
<palette>
<active>
<colorrole role="WindowText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="Button">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Light">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Midlight">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>251</red>
<green>251</green>
<blue>251</blue>
</color>
</brush>
</colorrole>
<colorrole role="Dark">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="Mid">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>165</red>
<green>165</green>
<blue>165</blue>
</color>
</brush>
</colorrole>
<colorrole role="Text">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="BrightText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="ButtonText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="Base">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Shadow">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="AlternateBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>251</red>
<green>251</green>
<blue>251</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>220</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="WindowText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="Button">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Light">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Midlight">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>251</red>
<green>251</green>
<blue>251</blue>
</color>
</brush>
</colorrole>
<colorrole role="Dark">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="Mid">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>165</red>
<green>165</green>
<blue>165</blue>
</color>
</brush>
</colorrole>
<colorrole role="Text">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="BrightText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="ButtonText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="Base">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Shadow">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="AlternateBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>251</red>
<green>251</green>
<blue>251</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>220</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="WindowText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="Button">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Light">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Midlight">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>251</red>
<green>251</green>
<blue>251</blue>
</color>
</brush>
</colorrole>
<colorrole role="Dark">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="Mid">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>165</red>
<green>165</green>
<blue>165</blue>
</color>
</brush>
</colorrole>
<colorrole role="Text">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="BrightText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="ButtonText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>124</red>
<green>124</green>
<blue>124</blue>
</color>
</brush>
</colorrole>
<colorrole role="Base">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="LinearGradientPattern">
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
<gradientstop position="0.000000000000000">
<color alpha="255">
<red>243</red>
<green>243</green>
<blue>243</blue>
</color>
</gradientstop>
<gradientstop position="1.000000000000000">
<color alpha="255">
<red>250</red>
<green>250</green>
<blue>250</blue>
</color>
</gradientstop>
</gradient>
</brush>
</colorrole>
<colorrole role="Shadow">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
<colorrole role="AlternateBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>248</red>
<green>248</green>
<blue>248</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipBase">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>220</blue>
</color>
</brush>
</colorrole>
<colorrole role="ToolTipText">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>0</red>
<green>0</green>
<blue>0</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="title"> <property name="title">
<string/> <string>Computed Values</string>
</property> </property>
<property name="alignment"> <layout class="QGridLayout" name="gridLayout_3">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<layout class="QGridLayout" name="gridLayout_10">
<item row="0" column="0">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>111</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="1">
<widget class="QPushButton" name="stabilizationReloadBoardData_6">
<property name="minimumSize">
<size>
<width>120</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Reloads the saved settings into GCS.
Useful if you have accidentally changed some settings.</string>
</property>
<property name="styleSheet">
<string notr="true">QPushButton {
border: 1px outset #999;
border-radius: 5;
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255));
}
QPushButton:pressed {
border-style: inset;
background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255));
}
QPushButton:hover {
border: 1px outset #999;
border-color: rgb(83, 83, 83);
border-radius: 4;
}</string>
</property>
<property name="text">
<string>Reload Board Data</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>button:reload</string>
<string>buttongroup:10</string>
</stringlist>
</property>
</widget>
</item>
<item row="0" column="2"> <item row="0" column="2">
<widget class="QPushButton" name="saveStabilizationToRAM_6"> <widget class="QLabel" name="label_9">
<property name="minimumSize">
<size>
<width>60</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="styleSheet">
<string notr="true">QPushButton {
border: 1px outset #999;
border-radius: 5;
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255));
}
QPushButton:pressed {
border-style: inset;
background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255));
}
QPushButton:hover {
border: 1px outset #999;
border-color: rgb(83, 83, 83);
border-radius: 4;
}</string>
</property>
<property name="text"> <property name="text">
<string>Apply</string> <string>RateKi</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>button:apply</string>
</stringlist>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="3"> <item row="0" column="3">
<widget class="QPushButton" name="saveStabilizationToSD_6"> <widget class="QLabel" name="label_10">
<property name="minimumSize">
<size>
<width>60</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="styleSheet">
<string notr="true">QPushButton {
border: 1px outset #999;
border-radius: 5;
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255));
}
QPushButton:pressed {
border-style: inset;
background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255));
}
QPushButton:hover {
border: 1px outset #999;
border-color: rgb(83, 83, 83);
border-radius: 4;
}</string>
</property>
<property name="text"> <property name="text">
<string>Save</string> <string>AttitudeKp</string>
</property> </property>
<property name="objrelation" stdset="0"> </widget>
<stringlist> </item>
<string>button:save</string> <item row="2" column="2">
</stringlist> <widget class="QLabel" name="pitchRateKi">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_12">
<property name="text">
<string>Pitch</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_5">
<property name="text">
<string>RateKp</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="rollRateKp">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="label_11">
<property name="text">
<string>AttitudeKi</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_4">
<property name="text">
<string>Roll</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="rollAttitudeKp">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QLabel" name="pitchAttitudeKi">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QLabel" name="pitchAttitudeKp">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLabel" name="pitchRateKp">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="rollRateKi">
<property name="text">
<string>0</string>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="rollAttitudeKi">
<property name="text">
<string>0</string>
</property> </property>
</widget> </widget>
</item> </item>
</layout> </layout>
</widget> </widget>
<widget class="QLabel" name="label_22"> </item>
<property name="geometry"> <item>
<rect> <widget class="QGroupBox" name="groupBox_4">
<x>30</x> <property name="title">
<y>440</y> <string/>
<width>401</width>
<height>31</height>
</rect>
</property> </property>
<property name="text"> <layout class="QHBoxLayout" name="horizontalLayout_2">
<string>The buttons below change the autotuning settings which <item>
will alter things for the next autotuning flight</string> <layout class="QGridLayout" name="gridLayout_4">
</property> <item row="0" column="1" colspan="2">
</widget>
<widget class="QPushButton" name="useComputedValues"> <widget class="QPushButton" name="useComputedValues">
<property name="geometry">
<rect>
<x>250</x>
<y>380</y>
<width>171</width>
<height>31</height>
</rect>
</property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">QPushButton { <string notr="true"/>
border: 1px outset #999;
border-radius: 5;
background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255));
}
QPushButton:pressed {
border-style: inset;
background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255));
}
QPushButton:hover {
border: 1px outset #999;
border-color: rgb(83, 83, 83);
border-radius: 4;
}</string>
</property> </property>
<property name="text"> <property name="text">
<string>Apply Computed Values</string> <string>Apply Computed Values</string>
</property> </property>
</widget> </widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="label_21"> <widget class="QLabel" name="label_21">
<property name="geometry">
<rect>
<x>40</x>
<y>410</y>
<width>104</width>
<height>20</height>
</rect>
</property>
<property name="text"> <property name="text">
<string>Step Size</string> <string>Step Size</string>
</property> </property>
</widget> <property name="alignment">
<widget class="QSlider" name="stepSizeSlider"> <set>Qt::AlignCenter</set>
<property name="geometry">
<rect>
<x>149</x>
<y>410</y>
<width>266</width>
<height>20</height>
</rect>
</property> </property>
</widget>
</item>
<item row="1" column="2">
<widget class="QSlider" name="stepSizeSlider">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
</property> </property>
@ -1078,6 +525,168 @@ border-radius: 4;
</stringlist> </stringlist>
</property> </property>
</widget> </widget>
</item>
<item row="0" column="3">
<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>
<item row="1" column="0">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="0" colspan="4">
<widget class="QLabel" name="label_22">
<property name="text">
<string>The Apply and Save buttons below save the autotuning settings which
will alter settings for the next autotuning flight</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>77</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>4</number>
</property>
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>13</width>
<height>25</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="stabilizationReloadBoardData_6">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Reloads the saved settings into GCS.
Useful if you have accidentally changed some settings.</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Reload Board Data</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>button:reload</string>
<string>buttongroup:10</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveStabilizationToRAM_6">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Apply</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>button:apply</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveStabilizationToSD_6">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>button:save</string>
</stringlist>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget> </widget>
<resources/> <resources/>
<connections/> <connections/>

View File

@ -6,22 +6,34 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>789</width> <width>786</width>
<height>615</height> <height>566</height>
</rect> </rect>
</property> </property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="windowTitle"> <property name="windowTitle">
<string>Form</string> <string>Form</string>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_5"> <layout class="QVBoxLayout" name="verticalLayout_5">
<property name="spacing">
<number>6</number>
</property>
<property name="margin">
<number>12</number>
</property>
<item> <item>
<widget class="QTabWidget" name="tabWidget"> <widget class="QTabWidget" name="tabWidget">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="currentIndex"> <property name="currentIndex">
<number>0</number> <number>0</number>
</property> </property>
@ -35,6 +47,12 @@
</property> </property>
<item> <item>
<widget class="QScrollArea" name="scrollArea"> <widget class="QScrollArea" name="scrollArea">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::NoFrame</enum> <enum>QFrame::NoFrame</enum>
</property> </property>
@ -46,19 +64,37 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>742</width> <width>741</width>
<height>560</height> <height>559</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QVBoxLayout" name="verticalLayout">
<property name="spacing"> <property name="spacing">
<number>6</number> <number>12</number>
</property> </property>
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>
<item> <item>
<widget class="QGroupBox" name="groupBox_2"> <widget class="QGroupBox" name="groupBox_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="title"> <property name="title">
<string>Module Control</string> <string>Module Control</string>
</property> </property>
@ -86,7 +122,7 @@
<item> <item>
<widget class="QGroupBox" name="groupBox_5"> <widget class="QGroupBox" name="groupBox_5">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -94,7 +130,13 @@
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>131</height> <height>130</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size> </size>
</property> </property>
<property name="title"> <property name="title">
@ -340,7 +382,7 @@ margin:1px;</string>
<item> <item>
<widget class="QGroupBox" name="groupBox"> <widget class="QGroupBox" name="groupBox">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -348,13 +390,22 @@ margin:1px;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>266</height> <height>250</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size> </size>
</property> </property>
<property name="title"> <property name="title">
<string>Advanced Settings (Control)</string> <string>Advanced Settings (Control)</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout_8"> <layout class="QGridLayout" name="gridLayout_8">
<property name="verticalSpacing">
<number>6</number>
</property>
<item row="0" column="3"> <item row="0" column="3">
<widget class="QLabel" name="label_32"> <widget class="QLabel" name="label_32">
<property name="minimumSize"> <property name="minimumSize">
@ -924,6 +975,18 @@ value.</string>
</item> </item>
<item> <item>
<widget class="QGroupBox" name="groupBox_4"> <widget class="QGroupBox" name="groupBox_4">
<property name="minimumSize">
<size>
<width>0</width>
<height>71</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="title"> <property name="title">
<string>Messages</string> <string>Messages</string>
</property> </property>
@ -946,6 +1009,9 @@ value.</string>
<property name="orientation"> <property name="orientation">
<enum>Qt::Vertical</enum> <enum>Qt::Vertical</enum>
</property> </property>
<property name="sizeType">
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>20</width> <width>20</width>
@ -963,24 +1029,24 @@ value.</string>
</widget> </widget>
</item> </item>
<item> <item>
<layout class="QHBoxLayout" name="horizontalLayout"> <layout class="QGridLayout" name="gridLayout">
<property name="spacing"> <property name="horizontalSpacing">
<number>4</number> <number>4</number>
</property> </property>
<item> <item row="0" column="0">
<spacer name="horizontalSpacer"> <spacer name="horizontalSpacer">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
</property> </property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>321</width> <width>288</width>
<height>16</height> <height>18</height>
</size> </size>
</property> </property>
</spacer> </spacer>
</item> </item>
<item> <item row="0" column="1">
<widget class="QPushButton" name="camerastabilizationHelp"> <widget class="QPushButton" name="camerastabilizationHelp">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed"> <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
@ -1029,7 +1095,7 @@ value.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="2">
<widget class="QPushButton" name="camerastabilizationResetToDefaults"> <widget class="QPushButton" name="camerastabilizationResetToDefaults">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -1060,7 +1126,7 @@ Apply or Save button afterwards.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="3">
<widget class="QPushButton" name="pushButton"> <widget class="QPushButton" name="pushButton">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -1093,7 +1159,7 @@ Apply or Save button afterwards.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="4">
<widget class="QPushButton" name="camerastabilizationSaveRAM"> <widget class="QPushButton" name="camerastabilizationSaveRAM">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
@ -1120,7 +1186,7 @@ Apply or Save button afterwards.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="5">
<widget class="QPushButton" name="camerastabilizationSaveSD"> <widget class="QPushButton" name="camerastabilizationSaveSD">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>

View File

@ -6,7 +6,7 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>666</width> <width>780</width>
<height>566</height> <height>566</height>
</rect> </rect>
</property> </property>
@ -110,14 +110,11 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>636</width> <width>750</width>
<height>483</height> <height>466</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QVBoxLayout" name="verticalLayout">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>
@ -126,18 +123,25 @@
<property name="title"> <property name="title">
<string>Rotate virtual attitude relative to board</string> <string>Rotate virtual attitude relative to board</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout"> <layout class="QGridLayout" name="gridLayout" columnstretch="0,1,0,1,0,1,0">
<item row="0" column="0"> <item row="0" column="1">
<widget class="QLabel" name="label_2"> <widget class="QLabel" name="label_2">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text"> <property name="text">
<string>Roll</string> <string>Roll</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set> <set>Qt::AlignCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="0"> <item row="1" column="1">
<widget class="QSpinBox" name="rollBias"> <widget class="QSpinBox" name="rollBias">
<property name="minimum"> <property name="minimum">
<number>-180</number> <number>-180</number>
@ -147,17 +151,77 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="1"> <item row="1" column="4">
<spacer name="horizontalSpacer_9">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="5">
<widget class="QSpinBox" name="yawBias">
<property name="minimum">
<number>-180</number>
</property>
<property name="maximum">
<number>180</number>
</property>
</widget>
</item>
<item row="0" column="5">
<widget class="QLabel" name="label_4">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_3"> <widget class="QLabel" name="label_3">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text"> <property name="text">
<string>Pitch</string> <string>Pitch</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set> <set>Qt::AlignCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="1"> <item row="1" column="3">
<widget class="QSpinBox" name="pitchBias"> <widget class="QSpinBox" name="pitchBias">
<property name="minimum"> <property name="minimum">
<number>-90</number> <number>-90</number>
@ -167,25 +231,31 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="1" column="0">
<widget class="QLabel" name="label_4"> <spacer name="horizontalSpacer_7">
<property name="text"> <property name="orientation">
<string>Yaw</string> <enum>Qt::Horizontal</enum>
</property> </property>
<property name="alignment"> <property name="sizeHint" stdset="0">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set> <size>
<width>40</width>
<height>20</height>
</size>
</property> </property>
</widget> </spacer>
</item> </item>
<item row="1" column="2"> <item row="1" column="6">
<widget class="QSpinBox" name="yawBias"> <spacer name="horizontalSpacer_10">
<property name="minimum"> <property name="orientation">
<number>-180</number> <enum>Qt::Horizontal</enum>
</property> </property>
<property name="maximum"> <property name="sizeHint" stdset="0">
<number>180</number> <size>
<width>40</width>
<height>20</height>
</size>
</property> </property>
</widget> </spacer>
</item> </item>
</layout> </layout>
</widget> </widget>

View File

@ -49,7 +49,7 @@ const QString ConfigMultiRotorWidget::CHANNELBOXNAME = QString("multiMotorChanne
/** /**
Constructor Constructor
*/ */
ConfigMultiRotorWidget::ConfigMultiRotorWidget(Ui_AircraftWidget *aircraft, QWidget *parent) : VehicleConfig(parent) ConfigMultiRotorWidget::ConfigMultiRotorWidget(Ui_AircraftWidget *aircraft, QWidget *parent) : VehicleConfig(parent), invertMotors(1)
{ {
m_aircraft = aircraft; m_aircraft = aircraft;
} }
@ -87,20 +87,18 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
if (frameType == "Tri" || frameType == "Tricopter Y") { if (frameType == "Tri" || frameType == "Tricopter Y") {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y")); setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y"));
quad->setElementId("tri");
//Enable all necessary motor channel boxes... //Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 3, true); enableComboBoxes(uiowner, CHANNELBOXNAME, 3, true);
m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100);
m_aircraft->mrYawMixLevel->setValue(50); setYawMixLevel(50);
m_aircraft->triYawChannelBox->setEnabled(true); m_aircraft->triYawChannelBox->setEnabled(true);
} }
else if (frameType == "QuadX" || frameType == "Quad X") { else if (frameType == "QuadX" || frameType == "Quad X") {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X"));
quad->setElementId("quad-x");
//Enable all necessary motor channel boxes... //Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 4, true); enableComboBoxes(uiowner, CHANNELBOXNAME, 4, true);
@ -108,104 +106,173 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
// init mixer levels // init mixer levels
m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(50); setYawMixLevel(50);
} }
else if (frameType == "QuadP" || frameType == "Quad +") { else if (frameType == "QuadP" || frameType == "Quad +") {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +"));
quad->setElementId("quad-plus");
//Enable all necessary motor channel boxes... //Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 4, true); enableComboBoxes(uiowner, CHANNELBOXNAME, 4, true);
m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100);
m_aircraft->mrYawMixLevel->setValue(50); setYawMixLevel(50);
} }
else if (frameType == "Hexa" || frameType == "Hexacopter") else if (frameType == "Hexa" || frameType == "Hexacopter")
{ {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter")); setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter"));
quad->setElementId("quad-hexa");
//Enable all necessary motor channel boxes... //Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true); enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(33); m_aircraft->mrPitchMixLevel->setValue(33);
m_aircraft->mrYawMixLevel->setValue(33); setYawMixLevel(33);
} }
else if (frameType == "HexaX" || frameType == "Hexacopter X" ) { else if (frameType == "HexaX" || frameType == "Hexacopter X" ) {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter X")); setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter X"));
quad->setElementId("quad-hexa-H");
//Enable all necessary motor channel boxes... //Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true); enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(33); m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(33); setYawMixLevel(33);
} }
else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6")
{ {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter Y6"));
quad->setElementId("hexa-coax");
//Enable all necessary motor channel boxes... //Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true); enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(66); setYawMixLevel(66);
} }
else if (frameType == "Octo" || frameType == "Octocopter") else if (frameType == "Octo" || frameType == "Octocopter")
{ {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter")); setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter"));
quad->setElementId("quad-octo");
//Enable all necessary motor channel boxes //Enable all necessary motor channel boxes
enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(33); m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(33); m_aircraft->mrPitchMixLevel->setValue(33);
m_aircraft->mrYawMixLevel->setValue(25); setYawMixLevel(25);
} }
else if (frameType == "OctoV" || frameType == "Octocopter V") else if (frameType == "OctoV" || frameType == "Octocopter V")
{ {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter V")); setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter V"));
quad->setElementId("quad-octo-v");
//Enable all necessary motor channel boxes //Enable all necessary motor channel boxes
enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(25); m_aircraft->mrRollMixLevel->setValue(25);
m_aircraft->mrPitchMixLevel->setValue(25); m_aircraft->mrPitchMixLevel->setValue(25);
m_aircraft->mrYawMixLevel->setValue(25); setYawMixLevel(25);
} }
else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +")
{ {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +")); setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +"));
quad->setElementId("octo-coax-P");
//Enable all necessary motor channel boxes //Enable all necessary motor channel boxes
enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100);
m_aircraft->mrYawMixLevel->setValue(50); setYawMixLevel(50);
} }
else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X")
{ {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X")); setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X"));
quad->setElementId("octo-coax-X");
//Enable all necessary motor channel boxes
enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(50); setYawMixLevel(50);
}
//Draw the appropriate airframe
drawAirframe(frameType);
}
void ConfigMultiRotorWidget::drawAirframe(QString frameType){
invertMotors = m_aircraft->MultirotorRevMixercheckBox->isChecked() ? -1:1;
if (frameType == "Tri" || frameType == "Tricopter Y") {
if(invertMotors > 0)
quad->setElementId("tri");
else
quad->setElementId("tri_reverse");
}
else if (frameType == "QuadX" || frameType == "Quad X") {
if(invertMotors > 0)
quad->setElementId("quad-x");
else
quad->setElementId("quad-x_reverse");
}
else if (frameType == "QuadP" || frameType == "Quad +") {
if(invertMotors > 0)
quad->setElementId("quad-plus");
else
quad->setElementId("quad-plus_reverse");
}
else if (frameType == "Hexa" || frameType == "Hexacopter")
{
if(invertMotors > 0)
quad->setElementId("quad-hexa");
else
quad->setElementId("quad-hexa_reverse");
}
else if (frameType == "HexaX" || frameType == "Hexacopter X" ) {
if(invertMotors > 0)
quad->setElementId("quad-hexa-H");
else
quad->setElementId("quad-hexa-H_reverse");
}
else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6")
{
if(invertMotors > 0)
quad->setElementId("hexa-coax");
else
quad->setElementId("hexa-coax_reverse");
}
else if (frameType == "Octo" || frameType == "Octocopter")
{
if(invertMotors > 0)
quad->setElementId("quad-octo");
else
quad->setElementId("quad-octo_reverse");
}
else if (frameType == "OctoV" || frameType == "Octocopter V")
{
if(invertMotors > 0)
quad->setElementId("quad-octo-v");
else
quad->setElementId("quad-octo-v_reverse");
}
else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +")
{
if(invertMotors > 0)
quad->setElementId("octo-coax-P");
else
quad->setElementId("octo-coax-P_reverse");
}
else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X")
{
if(invertMotors > 0)
quad->setElementId("octo-coax-X");
else
quad->setElementId("octo-coax-X_reverse");
} }
} }
@ -259,6 +326,21 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions()
return channelDesc; return channelDesc;
} }
void ConfigMultiRotorWidget::setYawMixLevel(int value)
{
if(value<0)
{
m_aircraft->mrYawMixLevel->setValue((-1)*value);
m_aircraft->MultirotorRevMixercheckBox->setChecked(true);
}
else
{
m_aircraft->mrYawMixLevel->setValue(value);
m_aircraft->MultirotorRevMixercheckBox->setChecked(false);
}
}
@ -500,7 +582,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrPitchMixLevel->setValue( value/1.27 ); m_aircraft->mrPitchMixLevel->setValue( value/1.27 );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( 1-value/1.27 ); setYawMixLevel( 1-value/1.27 );
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
@ -526,7 +608,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrPitchMixLevel->setValue( value/1.27 ); m_aircraft->mrPitchMixLevel->setValue( value/1.27 );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( 1-value/1.27 ); setYawMixLevel( 1-value/1.27 );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( value/1.27); m_aircraft->mrRollMixLevel->setValue( value/1.27);
@ -556,7 +638,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); setYawMixLevel( floor(-value/1.27) );
//change channels //change channels
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
@ -589,7 +671,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); setYawMixLevel( floor(-value/1.27) );
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
@ -617,7 +699,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrPitchMixLevel->setValue( value/1.27 ); m_aircraft->mrPitchMixLevel->setValue( value/1.27 );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( value/1.27 ); setYawMixLevel( value/1.27 );
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
@ -648,7 +730,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); setYawMixLevel( floor(-value/1.27) );
//change channels //change channels
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
@ -660,7 +742,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); setYawMixLevel( floor(-value/1.27) );
//change channels //change channels
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
@ -672,7 +754,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); setYawMixLevel( floor(-value/1.27) );
//change channels //change channels
channel = m_aircraft->multiMotorChannelBox3->currentIndex() - 1; channel = m_aircraft->multiMotorChannelBox3->currentIndex() - 1;
@ -705,7 +787,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); setYawMixLevel( floor(-value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) ); m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) );
@ -732,6 +814,8 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
} }
} }
drawAirframe(frameType);
} }
@ -959,7 +1043,8 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3])
// and enable only the relevant channels: // and enable only the relevant channels:
double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100; double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100;
double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100; double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100;
double yFactor = (double)m_aircraft->mrYawMixLevel->value()/100; invertMotors = m_aircraft->MultirotorRevMixercheckBox->isChecked() ? -1:1;
double yFactor =invertMotors * (double)m_aircraft->mrYawMixLevel->value()/100;
for (int i=0 ; i<8; i++) { for (int i=0 ; i<8; i++) {
if(mmList.at(i)->isEnabled()) if(mmList.at(i)->isEnabled())
{ {

View File

@ -64,9 +64,14 @@ private:
void setupMotors(QList<QString> motorList); void setupMotors(QList<QString> motorList);
void setupQuadMotor(int channel, double roll, double pitch, double yaw); void setupQuadMotor(int channel, double roll, double pitch, double yaw);
float invertMotors;
virtual void ResetActuators(GUIConfigDataUnion* configData); virtual void ResetActuators(GUIConfigDataUnion* configData);
static QStringList getChannelDescriptions(); static QStringList getChannelDescriptions();
static const QString CHANNELBOXNAME; static const QString CHANNELBOXNAME;
void setYawMixLevel(int);
void drawAirframe(QString multiRotorType);
private slots: private slots:
virtual void setupUI(QString airframeType); virtual void setupUI(QString airframeType);

View File

@ -13,6 +13,7 @@
#include "relaytuningsettings.h" #include "relaytuningsettings.h"
#include "relaytuning.h" #include "relaytuning.h"
#include "stabilizationsettings.h" #include "stabilizationsettings.h"
#include "hwsettings.h"
ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) : ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) :
ConfigTaskWidget(parent) ConfigTaskWidget(parent)
@ -28,6 +29,9 @@ ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) :
connect(m_autotune->rateTuning, SIGNAL(valueChanged(int)), this, SLOT(recomputeStabilization())); connect(m_autotune->rateTuning, SIGNAL(valueChanged(int)), this, SLOT(recomputeStabilization()));
connect(m_autotune->attitudeTuning, SIGNAL(valueChanged(int)), this, SLOT(recomputeStabilization())); connect(m_autotune->attitudeTuning, SIGNAL(valueChanged(int)), this, SLOT(recomputeStabilization()));
addUAVObject("HwSettings");
addWidget(m_autotune->enableAutoTune);
RelayTuning *relayTuning = RelayTuning::GetInstance(getObjectManager()); RelayTuning *relayTuning = RelayTuning::GetInstance(getObjectManager());
Q_ASSERT(relayTuning); Q_ASSERT(relayTuning);
if(relayTuning) if(relayTuning)
@ -134,3 +138,25 @@ void ConfigAutotuneWidget::recomputeStabilization()
m_autotune->pitchAttitudeKp->setText(QString().number(stabSettings.PitchPI[StabilizationSettings::PITCHPI_KP])); m_autotune->pitchAttitudeKp->setText(QString().number(stabSettings.PitchPI[StabilizationSettings::PITCHPI_KP]));
m_autotune->pitchAttitudeKi->setText(QString().number(stabSettings.PitchPI[StabilizationSettings::PITCHPI_KI])); m_autotune->pitchAttitudeKi->setText(QString().number(stabSettings.PitchPI[StabilizationSettings::PITCHPI_KI]));
} }
void ConfigAutotuneWidget::refreshWidgetsValues(UAVObject *obj)
{
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
if(obj==hwSettings)
{
bool dirtyBack=isDirty();
HwSettings::DataFields hwSettingsData = hwSettings->getData();
m_autotune->enableAutoTune->setChecked(
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_AUTOTUNE] == HwSettings::OPTIONALMODULES_ENABLED);
setDirty(dirtyBack);
}
ConfigTaskWidget::refreshWidgetsValues(obj);
}
void ConfigAutotuneWidget::updateObjectsFromWidgets()
{
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
HwSettings::DataFields hwSettingsData = hwSettings->getData();
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_AUTOTUNE] =
m_autotune->enableAutoTune->isChecked() ? HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED;
hwSettings->setData(hwSettingsData);
ConfigTaskWidget::updateObjectsFromWidgets();
}

View File

@ -51,7 +51,8 @@ private:
signals: signals:
public slots: public slots:
void refreshWidgetsValues(UAVObject *obj);
void updateObjectsFromWidgets();
private slots: private slots:
void recomputeStabilization(); void recomputeStabilization();
void saveStabilization(); void saveStabilization();

View File

@ -215,6 +215,9 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
connect(m_aircraft->ffTestBox2, SIGNAL(clicked(bool)), this, SLOT(enableFFTest())); connect(m_aircraft->ffTestBox2, SIGNAL(clicked(bool)), this, SLOT(enableFFTest()));
connect(m_aircraft->ffTestBox3, SIGNAL(clicked(bool)), this, SLOT(enableFFTest())); connect(m_aircraft->ffTestBox3, SIGNAL(clicked(bool)), this, SLOT(enableFFTest()));
//Connect the multirotor motor reverse checkbox
connect(m_aircraft->MultirotorRevMixercheckBox, SIGNAL(clicked(bool)), this, SLOT(reverseMultirotorMotor()));
// Connect the help pushbutton // Connect the help pushbutton
connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
enableControls(false); enableControls(false);
@ -483,7 +486,7 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject * o)
UAVObjectField *field = system->getField(QString("AirframeType")); UAVObjectField *field = system->getField(QString("AirframeType"));
Q_ASSERT(field); Q_ASSERT(field);
// At this stage, we will need to have some hardcoded settings in this code, this // At this stage, we will need to have some hardcoded settings in this code, this
// is not ideal, but here you go. // is not ideal, but there you go.
QString frameType = field->getValue().toString(); QString frameType = field->getValue().toString();
setupAirframeUI(frameType); setupAirframeUI(frameType);
@ -766,6 +769,12 @@ void ConfigVehicleTypeWidget::setComboCurrentIndex(QComboBox* box, int index)
box->setCurrentIndex(index); box->setCurrentIndex(index);
} }
void ConfigVehicleTypeWidget::reverseMultirotorMotor(){
QString frameType = m_aircraft->multirotorFrameType->currentText();
m_multirotor->drawAirframe(frameType);
}
/** /**
WHAT DOES THIS DO??? WHAT DOES THIS DO???
*/ */

View File

@ -95,6 +95,7 @@ private slots:
void enableFFTest(); void enableFFTest();
void openHelp(); void openHelp();
void reverseMultirotorMotor();
protected: protected:
void showEvent(QShowEvent *event); void showEvent(QShowEvent *event);

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 407 KiB

After

Width:  |  Height:  |  Size: 758 KiB

View File

@ -6,8 +6,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>670</width> <width>880</width>
<height>693</height> <height>672</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
@ -28,7 +28,7 @@
</attribute> </attribute>
<layout class="QVBoxLayout" name="verticalLayout_11"> <layout class="QVBoxLayout" name="verticalLayout_11">
<property name="spacing"> <property name="spacing">
<number>6</number> <number>0</number>
</property> </property>
<property name="margin"> <property name="margin">
<number>0</number> <number>0</number>
@ -110,8 +110,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>640</width> <width>850</width>
<height>610</height> <height>572</height>
</rect> </rect>
</property> </property>
<layout class="QGridLayout" name="gridLayout"> <layout class="QGridLayout" name="gridLayout">
@ -119,7 +119,7 @@
<number>12</number> <number>12</number>
</property> </property>
<property name="verticalSpacing"> <property name="verticalSpacing">
<number>6</number> <number>-1</number>
</property> </property>
<item row="1" column="0"> <item row="1" column="0">
<widget class="QGroupBox" name="groupBox_5"> <widget class="QGroupBox" name="groupBox_5">
@ -149,47 +149,11 @@
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>
<item>
<widget class="QPushButton" name="configurationWizard">
<property name="text">
<string>Start Configuration Wizard</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="runCalibration">
<property name="enabled">
<bool>true</bool>
</property>
<property name="text">
<string>Run Calibration</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_7">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>12</height>
</size>
</property>
</spacer>
</item>
<item> <item>
<layout class="QVBoxLayout" name="channelSettings"> <layout class="QVBoxLayout" name="channelSettings">
<property name="spacing"> <property name="spacing">
<number>0</number> <number>0</number>
</property> </property>
<property name="margin">
<number>0</number>
</property>
</layout> </layout>
</item> </item>
<item> <item>
@ -348,6 +312,98 @@
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox_3">
<property name="title">
<string>Calibration and Configuration Options</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_7">
<item>
<spacer name="horizontalSpacer_10">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="configurationWizard">
<property name="text">
<string>Start Configuration Wizard</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<property name="autoDefault">
<bool>false</bool>
</property>
<property name="default">
<bool>false</bool>
</property>
<property name="flat">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="runCalibration">
<property name="enabled">
<bool>true</bool>
</property>
<property name="minimumSize">
<size>
<width>210</width>
<height>0</height>
</size>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="text">
<string>Manual Calibration</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_9">
<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>
</widget>
</item>
</layout> </layout>
</widget> </widget>
</widget> </widget>
@ -359,9 +415,6 @@
<string>Flight Mode Switch Settings</string> <string>Flight Mode Switch Settings</string>
</attribute> </attribute>
<layout class="QVBoxLayout" name="verticalLayout_8"> <layout class="QVBoxLayout" name="verticalLayout_8">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>0</number> <number>0</number>
</property> </property>
@ -442,29 +495,297 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>640</width> <width>850</width>
<height>610</height> <height>572</height>
</rect> </rect>
</property> </property>
<layout class="QGridLayout" name="gridLayout_7"> <layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0">
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>
<property name="spacing"> <item row="1" column="0">
<number>6</number> <widget class="QGroupBox" name="groupBox">
<property name="styleSheet">
<string notr="true"/>
</property> </property>
<item row="0" column="0"> <property name="title">
<widget class="QGroupBox" name="groupBox_2"> <string>Configure each stabilization mode for each axis</string>
</property>
<layout class="QGridLayout" name="gridLayout_2" columnstretch="0,0,1,0,1,0,1,0">
<property name="leftMargin">
<number>9</number>
</property>
<property name="horizontalSpacing">
<number>12</number>
</property>
<item row="2" column="1">
<spacer name="horizontalSpacer_11">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="fmsSsPos3Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="0" column="6">
<widget class="QLabel" name="label_10">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>195</height> <height>20</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>16777215</width> <width>16777215</width>
<height>195</height> <height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="3">
<spacer name="horizontalSpacer_12">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_14">
<property name="text">
<string>Stabilized1</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="5">
<spacer name="horizontalSpacer_13">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="3" column="6">
<widget class="QComboBox" name="fmsSsPos3Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_21">
<property name="text">
<string>Stabilized2</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QComboBox" name="fmsSsPos3Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="6">
<widget class="QComboBox" name="fmsSsPos2Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="label_9">
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_8">
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QComboBox" name="fmsSsPos2Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="6">
<widget class="QComboBox" name="fmsSsPos1Yaw">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="fmsSsPos2Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="fmsSsPos1Roll">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QComboBox" name="fmsSsPos1Pitch">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_22">
<property name="text">
<string>Stabilized3</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="7">
<spacer name="horizontalSpacer_14">
<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>
</widget>
</item>
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox_2">
<property name="minimumSize">
<size>
<width>0</width>
<height>230</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>230</height>
</size> </size>
</property> </property>
<property name="title"> <property name="title">
@ -636,7 +957,7 @@
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>16777215</width> <width>16777215</width>
<height>140</height> <height>160</height>
</size> </size>
</property> </property>
<property name="focusPolicy"> <property name="focusPolicy">
@ -679,6 +1000,9 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
</item> </item>
<item row="0" column="2" rowspan="3"> <item row="0" column="2" rowspan="3">
<layout class="QVBoxLayout" name="verticalLayout_10"> <layout class="QVBoxLayout" name="verticalLayout_10">
<property name="spacing">
<number>3</number>
</property>
<item> <item>
<widget class="QComboBox" name="fmsModePos1"> <widget class="QComboBox" name="fmsModePos1">
<property name="focusPolicy"> <property name="focusPolicy">
@ -858,194 +1182,17 @@ channel value for each flight mode.</string>
<property name="orientation"> <property name="orientation">
<enum>Qt::Vertical</enum> <enum>Qt::Vertical</enum>
</property> </property>
<property name="sizeType">
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>20</width> <width>20</width>
<height>100</height> <height>20</height>
</size> </size>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="1" column="0">
<widget class="QGroupBox" name="groupBox">
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="title">
<string>Configure each stabilization mode for each axis</string>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<property name="leftMargin">
<number>0</number>
</property>
<property name="horizontalSpacing">
<number>12</number>
</property>
<item row="3" column="0">
<widget class="QLabel" name="label_22">
<property name="text">
<string>Stabilized3</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_8">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="fmsSsPos1Roll">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_9">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="fmsSsPos3Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QComboBox" name="fmsSsPos3Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="fmsSsPos2Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_14">
<property name="text">
<string>Stabilized1</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_10">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="fmsSsPos3Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QComboBox" name="fmsSsPos1Yaw">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QComboBox" name="fmsSsPos2Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="fmsSsPos2Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_21">
<property name="text">
<string>Stabilized2</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="fmsSsPos1Pitch">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout> </layout>
</widget> </widget>
</widget> </widget>
@ -1057,9 +1204,6 @@ margin:1px;</string>
<string>Arming Settings</string> <string>Arming Settings</string>
</attribute> </attribute>
<layout class="QVBoxLayout" name="verticalLayout_12"> <layout class="QVBoxLayout" name="verticalLayout_12">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>0</number> <number>0</number>
</property> </property>
@ -1140,14 +1284,11 @@ margin:1px;</string>
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>640</width> <width>850</width>
<height>610</height> <height>572</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_2"> <layout class="QVBoxLayout" name="verticalLayout_2">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>

View File

@ -14,9 +14,6 @@
<string>Form</string> <string>Form</string>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_2"> <layout class="QVBoxLayout" name="verticalLayout_2">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>
@ -120,12 +117,12 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>668</width> <width>668</width>
<height>671</height> <height>654</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_3"> <layout class="QVBoxLayout" name="verticalLayout_3">
<property name="spacing"> <property name="spacing">
<number>6</number> <number>-1</number>
</property> </property>
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
@ -148,12 +145,12 @@
<string>Output Update Speed</string> <string>Output Update Speed</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout"> <layout class="QGridLayout" name="gridLayout">
<property name="margin">
<number>12</number>
</property>
<property name="horizontalSpacing"> <property name="horizontalSpacing">
<number>6</number> <number>6</number>
</property> </property>
<property name="margin">
<number>12</number>
</property>
<item row="0" column="0"> <item row="0" column="0">
<spacer name="horizontalSpacer_3"> <spacer name="horizontalSpacer_3">
<property name="orientation"> <property name="orientation">
@ -528,15 +525,9 @@ Leave at 50Hz for fixed wing.</string>
</property> </property>
<item> <item>
<layout class="QVBoxLayout" name="channelLayout"> <layout class="QVBoxLayout" name="channelLayout">
<property name="spacing">
<number>6</number>
</property>
<property name="sizeConstraint"> <property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum> <enum>QLayout::SetDefaultConstraint</enum>
</property> </property>
<property name="margin">
<number>0</number>
</property>
</layout> </layout>
</item> </item>
<item> <item>

View File

@ -7,7 +7,7 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>965</width> <width>965</width>
<height>797</height> <height>687</height>
</rect> </rect>
</property> </property>
<property name="sizePolicy"> <property name="sizePolicy">
@ -505,9 +505,6 @@
<string>Basic</string> <string>Basic</string>
</attribute> </attribute>
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QVBoxLayout" name="verticalLayout">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>0</number> <number>0</number>
</property> </property>
@ -603,24 +600,15 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>935</width> <width>937</width>
<height>714</height> <height>595</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_12" stretch="0,0,0,0"> <layout class="QVBoxLayout" name="verticalLayout_12" stretch="0,0,0,0">
<property name="spacing"> <property name="spacing">
<number>12</number> <number>12</number>
</property> </property>
<property name="leftMargin"> <property name="margin">
<number>12</number>
</property>
<property name="topMargin">
<number>5</number>
</property>
<property name="rightMargin">
<number>12</number>
</property>
<property name="bottomMargin">
<number>12</number> <number>12</number>
</property> </property>
<item> <item>
@ -640,7 +628,7 @@
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>16777215</width> <width>16777215</width>
<height>181</height> <height>195</height>
</size> </size>
</property> </property>
<property name="title"> <property name="title">
@ -3496,7 +3484,7 @@ value as the Kp.</string>
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>16777215</width> <width>16777215</width>
<height>181</height> <height>195</height>
</size> </size>
</property> </property>
<property name="palette"> <property name="palette">
@ -6866,9 +6854,6 @@ border-radius: 5;</string>
<string>Advanced</string> <string>Advanced</string>
</attribute> </attribute>
<layout class="QVBoxLayout" name="verticalLayout_10"> <layout class="QVBoxLayout" name="verticalLayout_10">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>0</number> <number>0</number>
</property> </property>
@ -6952,17 +6937,14 @@ border-radius: 5;</string>
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>935</width> <width>540</width>
<height>714</height> <height>663</height>
</rect> </rect>
</property> </property>
<property name="autoFillBackground"> <property name="autoFillBackground">
<bool>true</bool> <bool>true</bool>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_16"> <layout class="QVBoxLayout" name="verticalLayout_16">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>
@ -6977,7 +6959,7 @@ border-radius: 5;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>210</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
@ -10299,7 +10281,7 @@ Then lower the value by 20% or so.</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>170</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
@ -13429,7 +13411,7 @@ border-radius: 5;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>195</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
@ -16792,9 +16774,6 @@ border-radius: 5;</string>
<string>Expert</string> <string>Expert</string>
</attribute> </attribute>
<layout class="QVBoxLayout" name="verticalLayout_4"> <layout class="QVBoxLayout" name="verticalLayout_4">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>0</number> <number>0</number>
</property> </property>
@ -16881,14 +16860,11 @@ border-radius: 5;</string>
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>935</width> <width>802</width>
<height>714</height> <height>607</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_9"> <layout class="QVBoxLayout" name="verticalLayout_9">
<property name="spacing">
<number>6</number>
</property>
<property name="margin"> <property name="margin">
<number>12</number> <number>12</number>
</property> </property>
@ -16903,7 +16879,7 @@ border-radius: 5;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>150</height> <height>0</height>
</size> </size>
</property> </property>
<property name="autoFillBackground"> <property name="autoFillBackground">
@ -19508,7 +19484,7 @@ border-radius: 5;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>180</height> <height>0</height>
</size> </size>
</property> </property>
<property name="title"> <property name="title">
@ -21916,7 +21892,7 @@ border-radius: 5;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>150</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">

View File

@ -7,7 +7,7 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>789</width> <width>789</width>
<height>615</height> <height>484</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
@ -113,8 +113,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>759</width> <width>745</width>
<height>532</height> <height>469</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_2"> <layout class="QVBoxLayout" name="verticalLayout_2">

View File

@ -46,7 +46,6 @@
#include "uavtalk/telemetrymanager.h" #include "uavtalk/telemetrymanager.h"
#include "uavobject.h" #include "uavobject.h"
#include "uavobjectmanager.h"
#include "positionactual.h" #include "positionactual.h"
#include "homelocation.h" #include "homelocation.h"
@ -590,6 +589,7 @@ void OPMapGadgetWidget::updatePosition()
VelocityActual *velocityActualObj = VelocityActual::GetInstance(obm); VelocityActual *velocityActualObj = VelocityActual::GetInstance(obm);
Gyros *gyrosObj = Gyros::GetInstance(obm); Gyros *gyrosObj = Gyros::GetInstance(obm);
Q_ASSERT(attitudeActualObj);
Q_ASSERT(positionActualObj); Q_ASSERT(positionActualObj);
Q_ASSERT(velocityActualObj); Q_ASSERT(velocityActualObj);
Q_ASSERT(gyrosObj); Q_ASSERT(gyrosObj);
@ -919,7 +919,7 @@ void OPMapGadgetWidget::setHome(QPointF pos)
/** /**
Sets the home position on the map widget Sets the home position on the map widget
*/ */
void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon,double altitude) void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon, double altitude)
{ {
if (!m_widget || !m_map) if (!m_widget || !m_map)
return; return;
@ -941,11 +941,11 @@ void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon,double altitu
if (longitude > 180) longitude = 180; if (longitude > 180) longitude = 180;
else else
if (longitude < -180) longitude = -180; if (longitude < -180) longitude = -180;
else if(altitude != altitude) altitude=0;
// ********* // *********
m_home_position.coord = internals::PointLatLng(latitude, longitude); m_home_position.coord = internals::PointLatLng(latitude, longitude);
m_home_position.altitude = altitude;
m_map->Home->SetCoord(m_home_position.coord); m_map->Home->SetCoord(m_home_position.coord);
m_map->Home->SetAltitude(altitude); m_map->Home->SetAltitude(altitude);
@ -1659,7 +1659,15 @@ void OPMapGadgetWidget::onSetHomeAct_triggered()
if (!m_widget || !m_map) if (!m_widget || !m_map)
return; return;
setHome(m_context_menu_lat_lon,0); float altitude=0;
bool ok;
//Get desired HomeLocation altitude from dialog box.
//TODO: Populate box with altitude already in HomeLocation UAVO
altitude = QInputDialog::getDouble(this, tr("Set home altitude"),
tr("In [m], referenced to WGS84:"), altitude, -100, 100000, 2, &ok);
setHome(m_context_menu_lat_lon, altitude);
setHomeLocationObject(); // update the HomeLocation UAVObject setHomeLocationObject(); // update the HomeLocation UAVObject
} }

View File

@ -281,15 +281,7 @@ void OsgEarthItemRenderer::initScene()
//setup caching //setup caching
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(m_model.get()); osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(m_model.get());
if (mapNode) { if (!mapNode) {
osgEarth::TMSCacheOptions cacheOptions;
//cacheOptions.cacheOnly() = true;
QString cacheDir = Utils::PathUtils().GetStoragePath()+QLatin1String("osgEarth_cache");
cacheOptions.setPath(cacheDir.toStdString());
osgEarth::Cache *cache= new osgEarth::TMSCache(cacheOptions);
mapNode->getMap()->setCache(cache);
} else {
qWarning() << Q_FUNC_INFO << sceneFile << " doesn't look like an osgEarth file"; qWarning() << Q_FUNC_INFO << sceneFile << " doesn't look like an osgEarth file";
} }

View File

@ -126,9 +126,6 @@ public slots:
signals: signals:
void frameReady(); void frameReady();
private slots:
void updateFBO();
private: private:
enum { FboCount = 3 }; enum { FboCount = 3 };
OsgEarthItem *m_item; OsgEarthItem *m_item;

View File

@ -35,7 +35,10 @@
#include <QEventLoop> #include <QEventLoop>
#include <QTimer> #include <QTimer>
#include <objectpersistence.h> #include <objectpersistence.h>
#include <firmwareiapobj.h>
#include "firmwareiapobj.h"
#include "homelocation.h"
#include "gpsposition.h"
// ****************************** // ******************************
// constructor/destructor // constructor/destructor
@ -48,6 +51,18 @@ UAVObjectUtilManager::UAVObjectUtilManager()
failureTimer.setSingleShot(true); failureTimer.setSingleShot(true);
failureTimer.setInterval(1000); failureTimer.setInterval(1000);
connect(&failureTimer, SIGNAL(timeout()),this,SLOT(objectPersistenceOperationFailed())); connect(&failureTimer, SIGNAL(timeout()),this,SLOT(objectPersistenceOperationFailed()));
pm = NULL;
obm = NULL;
obum = NULL;
pm = ExtensionSystem::PluginManager::instance();
if (pm)
{
obm = pm->getObject<UAVObjectManager>();
obum = pm->getObject<UAVObjectUtilManager>();
}
} }
UAVObjectUtilManager::~UAVObjectUtilManager() UAVObjectUtilManager::~UAVObjectUtilManager()
@ -67,10 +82,8 @@ UAVObjectUtilManager::~UAVObjectUtilManager()
UAVObjectManager* UAVObjectUtilManager::getObjectManager() { UAVObjectManager* UAVObjectUtilManager::getObjectManager() {
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); Q_ASSERT(obm);
UAVObjectManager * objMngr = pm->getObject<UAVObjectManager>(); return obm;
Q_ASSERT(objMngr);
return objMngr;
} }
@ -107,7 +120,7 @@ void UAVObjectUtilManager::saveNextObject()
// Get next object from the queue // Get next object from the queue
UAVObject* obj = queue.head(); UAVObject* obj = queue.head();
qDebug() << "Request board to save object " << obj->getName(); qDebug() << "Send save object request to board " << obj->getName();
ObjectPersistence* objper = dynamic_cast<ObjectPersistence*>( getObjectManager()->getObject(ObjectPersistence::NAME) ); ObjectPersistence* objper = dynamic_cast<ObjectPersistence*>( getObjectManager()->getObject(ObjectPersistence::NAME) );
connect(objper, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(objectPersistenceTransactionCompleted(UAVObject*,bool))); connect(objper, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(objectPersistenceTransactionCompleted(UAVObject*,bool)));
@ -233,16 +246,7 @@ FirmwareIAPObj::DataFields UAVObjectUtilManager::getFirmwareIap()
{ {
FirmwareIAPObj::DataFields dummy; FirmwareIAPObj::DataFields dummy;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); FirmwareIAPObj *firmwareIap = FirmwareIAPObj::GetInstance(obm);
Q_ASSERT(pm);
if (!pm)
return dummy;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
Q_ASSERT(om);
if (!om)
return dummy;
FirmwareIAPObj *firmwareIap = FirmwareIAPObj::GetInstance(om);
Q_ASSERT(firmwareIap); Q_ASSERT(firmwareIap);
if (!firmwareIap) if (!firmwareIap)
return dummy; return dummy;
@ -306,121 +310,47 @@ QByteArray UAVObjectUtilManager::getBoardDescription()
int UAVObjectUtilManager::setHomeLocation(double LLA[3], bool save_to_sdcard) int UAVObjectUtilManager::setHomeLocation(double LLA[3], bool save_to_sdcard)
{ {
double ECEF[3];
double RNE[9];
double Be[3]; double Be[3];
UAVObjectField *field;
QMutexLocker locker(mutex); Q_ASSERT (Utils::HomeLocationUtil().getDetails(LLA, Be) >= 0);
if (Utils::HomeLocationUtil().getDetails(LLA, ECEF, RNE, Be) < 0)
return -1; // error
// ****************** // ******************
// save the new settings // save the new settings
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); HomeLocation *homeLocation = HomeLocation::GetInstance(obm);
if (!pm) return -2; Q_ASSERT(homeLocation != NULL);
UAVObjectManager *om = pm->getObject<UAVObjectManager>(); HomeLocation::DataFields homeLocationData = homeLocation->getData();
if (!om) return -3; homeLocationData.Latitude = LLA[0] * 1e7;
homeLocationData.Longitude = LLA[1] * 1e7;
homeLocationData.Altitude = LLA[2];
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("HomeLocation"))); homeLocationData.Be[0] = Be[0];
if (!obj) return -4; homeLocationData.Be[1] = Be[1];
homeLocationData.Be[2] = Be[2];
UAVObjectField *ECEF_field = obj->getField(QString("ECEF")); homeLocationData.Set = HomeLocation::SET_TRUE;
if (!ECEF_field) return -5;
UAVObjectField *RNE_field = obj->getField(QString("RNE")); homeLocation->setData(homeLocationData);
if (!RNE_field) return -6;
UAVObjectField *Be_field = obj->getField(QString("Be"));
if (!Be_field) return -7;
field = obj->getField("Latitude");
if (!field) return -8;
field->setDouble(LLA[0] * 10e6);
field = obj->getField("Longitude");
if (!field) return -9;
field->setDouble(LLA[1] * 10e6);
field = obj->getField("Altitude");
if (!field) return -10;
field->setDouble(LLA[2]);
for (int i = 0; i < 3; i++)
ECEF_field->setDouble(ECEF[i] * 100, i);
for (int i = 0; i < 9; i++)
RNE_field->setDouble(RNE[i], i);
for (int i = 0; i < 3; i++)
Be_field->setDouble(Be[i], i);
field = obj->getField("Set");
if (!field) return -11;
field->setValue("TRUE");
obj->updated();
// ******************
// save the new setting to SD card
if (save_to_sdcard) if (save_to_sdcard)
saveObjectToSD(obj); saveObjectToSD(homeLocation);
// ****************** return 0;
// debug
/*
qDebug() << "setting HomeLocation UAV Object .. " << endl;
QString s;
s = " LAT:" + QString::number(LLA[0], 'f', 7) + " LON:" + QString::number(LLA[1], 'f', 7) + " ALT:" + QString::number(LLA[2], 'f', 1);
qDebug() << s << endl;
s = " ECEF "; for (int i = 0; i < 3; i++) s += " " + QString::number((int)(ECEF[i] * 100));
qDebug() << s << endl;
s = " RNE "; for (int i = 0; i < 9; i++) s += " " + QString::number(RNE[i], 'f', 7);
qDebug() << s << endl;
s = " Be "; for (int i = 0; i < 3; i++) s += " " + QString::number(Be[i], 'f', 2);
qDebug() << s << endl;
*/
// ******************
return 0; // OK
} }
int UAVObjectUtilManager::getHomeLocation(bool &set, double LLA[3]) int UAVObjectUtilManager::getHomeLocation(bool &set, double LLA[3])
{ {
UAVObjectField *field; HomeLocation *homeLocation = HomeLocation::GetInstance(obm);
Q_ASSERT(homeLocation != NULL);
QMutexLocker locker(mutex); HomeLocation::DataFields homeLocationData = homeLocation->getData();
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); set = homeLocationData.Set;
if (!pm) return -1;
UAVObjectManager *om = pm->getObject<UAVObjectManager>(); LLA[0] = homeLocationData.Latitude*1e-7;
if (!om) return -2; LLA[1] = homeLocationData.Longitude*1e-7;
LLA[2] = homeLocationData.Altitude;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("HomeLocation")));
if (!obj) return -3;
// obj->requestUpdate();
field = obj->getField("Set");
if (!field) return -4;
set = field->getValue().toBool();
field = obj->getField("Latitude");
if (!field) return -5;
LLA[0] = field->getDouble() * 1e-7;
field = obj->getField("Longitude");
if (!field) return -6;
LLA[1] = field->getDouble() * 1e-7;
field = obj->getField("Altitude");
if (!field) return -7;
LLA[2] = field->getDouble();
if (LLA[0] != LLA[0]) LLA[0] = 0; // nan detection if (LLA[0] != LLA[0]) LLA[0] = 0; // nan detection
else else
@ -439,88 +369,20 @@ int UAVObjectUtilManager::getHomeLocation(bool &set, double LLA[3])
return 0; // OK return 0; // OK
} }
int UAVObjectUtilManager::getHomeLocation(bool &set, double LLA[3], double ECEF[3], double RNE[9], double Be[3])
{
UAVObjectField *field;
QMutexLocker locker(mutex);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm) return -1;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om) return -2;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("HomeLocation")));
if (!obj) return -3;
// obj->requestUpdate();
field = obj->getField("Set");
if (!field) return -4;
set = field->getValue().toBool();
field = obj->getField("Latitude");
if (!field) return -5;
LLA[0] = field->getDouble() * 1e-7;
field = obj->getField("Longitude");
if (!field) return -6;
LLA[1] = field->getDouble() * 1e-7;
field = obj->getField("Altitude");
if (!field) return -7;
LLA[2] = field->getDouble();
field = obj->getField(QString("ECEF"));
if (!field) return -8;
for (int i = 0; i < 3; i++)
ECEF[i] = field->getDouble(i);
field = obj->getField(QString("RNE"));
if (!field) return -9;
for (int i = 0; i < 9; i++)
RNE[i] = field->getDouble(i);
field = obj->getField(QString("Be"));
if (!field) return -10;
for (int i = 0; i < 3; i++)
Be[i] = field->getDouble(i);
return 0; // OK
}
// ****************************** // ******************************
// GPS // GPS
int UAVObjectUtilManager::getGPSPosition(double LLA[3]) int UAVObjectUtilManager::getGPSPosition(double LLA[3])
{ {
UAVObjectField *field; GPSPosition *gpsPosition = GPSPosition::GetInstance(obm);
Q_ASSERT(gpsPosition != NULL);
QMutexLocker locker(mutex); GPSPosition::DataFields gpsPositionData = gpsPosition->getData();
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); LLA[0] = gpsPositionData.Latitude;
if (!pm) return -1; LLA[1] = gpsPositionData.Longitude;
LLA[2] = gpsPositionData.Altitude;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om) return -2;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("GPSPosition")));
if (!obj) return -3;
// obj->requestUpdate();
field = obj->getField(QString("Latitude"));
if (!field) return -4;
LLA[0] = field->getDouble() * 1e-7;
field = obj->getField(QString("Longitude"));
if (!field) return -5;
LLA[1] = field->getDouble() * 1e-7;
field = obj->getField(QString("Altitude"));
if (!field) return -6;
LLA[2] = field->getDouble();
if (LLA[0] != LLA[0]) LLA[0] = 0; // nan detection if (LLA[0] != LLA[0]) LLA[0] = 0; // nan detection
else else
@ -539,94 +401,6 @@ int UAVObjectUtilManager::getGPSPosition(double LLA[3])
return 0; // OK return 0; // OK
} }
// ******************************
// telemetry port
int UAVObjectUtilManager::setTelemetrySerialPortSpeed(QString speed, bool save_to_sdcard)
{
UAVObjectField *field;
QMutexLocker locker(mutex);
// ******************
// save the new settings
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm) return -1;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om) return -2;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("/*TelemetrySettings*/")));
if (!obj) return -3;
field = obj->getField(QString("Speed"));
if (!field) return -4;
field->setValue(speed);
obj->updated();
// ******************
// save the new setting to SD card
if (save_to_sdcard)
saveObjectToSD(obj);
// ******************
return 0; // OK
}
int UAVObjectUtilManager::getTelemetrySerialPortSpeed(QString &speed)
{
UAVObjectField *field;
QMutexLocker locker(mutex);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm) return -1;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om) return -2;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("TelemetrySettings")));
if (!obj) return -3;
// obj->requestUpdate();
field = obj->getField(QString("Speed"));
if (!field) return -4;
speed = field->getValue().toString();
return 0; // OK
}
int UAVObjectUtilManager::getTelemetrySerialPortSpeeds(QComboBox *comboBox)
{
UAVObjectField *field;
QMutexLocker locker(mutex);
if (!comboBox) return -1;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm) return -2;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om) return -3;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("TelemetrySettings")));
if (!obj) return -4;
// obj->requestUpdate();
field = obj->getField(QString("Speed"));
if (!field) return -5;
comboBox->addItems(field->getOptions());
return 0; // OK
}
deviceDescriptorStruct UAVObjectUtilManager::getBoardDescriptionStruct() deviceDescriptorStruct UAVObjectUtilManager::getBoardDescriptionStruct()
{ {
deviceDescriptorStruct ret; deviceDescriptorStruct ret;

View File

@ -55,14 +55,9 @@ public:
int setHomeLocation(double LLA[3], bool save_to_sdcard); int setHomeLocation(double LLA[3], bool save_to_sdcard);
int getHomeLocation(bool &set, double LLA[3]); int getHomeLocation(bool &set, double LLA[3]);
int getHomeLocation(bool &set, double LLA[3], double ECEF[3], double RNE[9], double Be[3]);
int getGPSPosition(double LLA[3]); int getGPSPosition(double LLA[3]);
int setTelemetrySerialPortSpeed(QString speed, bool save_to_sdcard);
int getTelemetrySerialPortSpeed(QString &speed);
int getTelemetrySerialPortSpeeds(QComboBox *comboBox);
int getBoardModel(); int getBoardModel();
QByteArray getBoardCPUSerial(); QByteArray getBoardCPUSerial();
quint32 getFirmwareCRC(); quint32 getFirmwareCRC();
@ -84,6 +79,10 @@ private:
void saveNextObject(); void saveNextObject();
QTimer failureTimer; QTimer failureTimer;
ExtensionSystem::PluginManager *pm;
UAVObjectManager *obm;
UAVObjectUtilManager *obum;
private slots: private slots:
//void transactionCompleted(UAVObject *obj, bool success); //void transactionCompleted(UAVObject *obj, bool success);
void objectPersistenceTransactionCompleted(UAVObject* obj, bool success); void objectPersistenceTransactionCompleted(UAVObject* obj, bool success);

View File

@ -161,6 +161,9 @@ int main(int argc, char *argv[])
QString res = parser->parseXML(xmlstr, filename); QString res = parser->parseXML(xmlstr, filename);
if (!res.isNull()) { if (!res.isNull()) {
if (!verbose) {
cout << "Error in XML file: " << fileinfo.fileName().toStdString() << endl;
}
cout << "Error parsing " << res.toStdString() << endl; cout << "Error parsing " << res.toStdString() << endl;
return RETURN_ERR_XML; return RETURN_ERR_XML;
} }

View File

@ -213,6 +213,9 @@ QString UAVObjectParser::parseXML(QString& xml, QString& filename)
qStableSort(info->fields.begin(), info->fields.end(), fieldTypeLessThan); qStableSort(info->fields.begin(), info->fields.end(), fieldTypeLessThan);
// Make sure that required elements were found // Make sure that required elements were found
if ( !fieldFound )
return QString("Object::field element is missing");
if ( !accessFound ) if ( !accessFound )
return QString("Object::access element is missing"); return QString("Object::access element is missing");
@ -381,11 +384,38 @@ QString UAVObjectParser::processObjectFields(QDomNode& childNode, ObjectInfo* in
// Get name attribute // Get name attribute
QDomNamedNodeMap elemAttributes = childNode.attributes(); QDomNamedNodeMap elemAttributes = childNode.attributes();
QDomNode elemAttr = elemAttributes.namedItem("name"); QDomNode elemAttr = elemAttributes.namedItem("name");
if ( elemAttr.isNull() ) if (elemAttr.isNull()) {
return QString("Object:field:name attribute is missing"); return QString("Object:field:name attribute is missing");
}
QString name = elemAttr.nodeValue();
field->name = elemAttr.nodeValue(); // Check to see is this field is a clone of another
// field that has already been declared
elemAttr = elemAttributes.namedItem("cloneof");
if (!elemAttr.isNull()) {
QString parentName = elemAttr.nodeValue();
if (!parentName.isEmpty()) {
foreach(FieldInfo * parent, info->fields) {
if (parent->name == parentName) {
// clone from this parent
*field = *parent; // safe shallow copy, no ptrs in struct
field->name = name; // set our name
// Add field to object
info->fields.append(field);
// Done
return QString();
}
}
return QString("Object:field::cloneof parent unknown");
}
else {
return QString("Object:field:cloneof attribute is empty");
}
}
else {
// this field is not a clone, so remember its name
field->name = name;
}
// Get units attribute // Get units attribute
elemAttr = elemAttributes.namedItem("units"); elemAttr = elemAttributes.namedItem("units");
@ -410,6 +440,8 @@ QString UAVObjectParser::processObjectFields(QDomNode& childNode, ObjectInfo* in
} }
// Get numelements or elementnames attribute // Get numelements or elementnames attribute
field->numElements = 0;
// Look for element names as an attribute first
elemAttr = elemAttributes.namedItem("elementnames"); elemAttr = elemAttributes.namedItem("elementnames");
if ( !elemAttr.isNull() ) { if ( !elemAttr.isNull() ) {
// Get element names // Get element names
@ -422,9 +454,26 @@ QString UAVObjectParser::processObjectFields(QDomNode& childNode, ObjectInfo* in
field->defaultElementNames = false; field->defaultElementNames = false;
} }
else { else {
// Look for a list of child elementname nodes
QDomNode listNode = childNode.firstChildElement("elementnames");
if (!listNode.isNull()) {
for (QDomElement node = listNode.firstChildElement("elementname");
!node.isNull(); node = node.nextSiblingElement("elementname")) {
QDomNode name = node.firstChild();
if (!name.isNull() && name.isText() && !name.nodeValue().isEmpty()) {
field->elementNames.append(name.nodeValue());
}
}
field->numElements = field->elementNames.length();
field->defaultElementNames = false;
}
}
// If no element names were found, then fall back to looking
// for the number of elements in the 'elements' attribute
if (field->numElements == 0) {
elemAttr = elemAttributes.namedItem("elements"); elemAttr = elemAttributes.namedItem("elements");
if ( elemAttr.isNull() ) { if ( elemAttr.isNull() ) {
return QString("Object:field:elements and Object:field:elementnames attribute is missing"); return QString("Object:field:elements and Object:field:elementnames attribute/element is missing");
} }
else { else {
field->numElements = elemAttr.nodeValue().toInt(); field->numElements = elemAttr.nodeValue().toInt();
@ -434,20 +483,35 @@ QString UAVObjectParser::processObjectFields(QDomNode& childNode, ObjectInfo* in
field->defaultElementNames = true; field->defaultElementNames = true;
} }
} }
// Get options attribute (only if an enum type) // Get options attribute or child elements (only if an enum type)
if (field->type == FIELDTYPE_ENUM) { if (field->type == FIELDTYPE_ENUM) {
// Get options attribute // Look for options attribute
elemAttr = elemAttributes.namedItem("options"); elemAttr = elemAttributes.namedItem("options");
if ( elemAttr.isNull() ) if (!elemAttr.isNull()) {
return QString("Object:field:options attribute is missing");
QStringList options = elemAttr.nodeValue().split(",", QString::SkipEmptyParts); QStringList options = elemAttr.nodeValue().split(",", QString::SkipEmptyParts);
for (int n = 0; n < options.length(); ++n) for (int n = 0; n < options.length(); ++n) {
options[n] = options[n].trimmed(); options[n] = options[n].trimmed();
}
field->options = options; field->options = options;
} }
else {
// Look for a list of child 'option' nodes
QDomNode listNode = childNode.firstChildElement("options");
if (!listNode.isNull()) {
for (QDomElement node = listNode.firstChildElement("option");
!node.isNull(); node = node.nextSiblingElement("option")) {
QDomNode name = node.firstChild();
if (!name.isNull() && name.isText() && !name.nodeValue().isEmpty()) {
field->options.append(name.nodeValue());
}
}
}
}
if (field->options.length() == 0) {
return QString("Object:field:options attribute/element is missing");
}
}
// Get the default value attribute (required for settings objects, optional for the rest) // Get the default value attribute (required for settings objects, optional for the rest)
elemAttr = elemAttributes.namedItem("defaultvalue"); elemAttr = elemAttributes.namedItem("defaultvalue");
@ -466,12 +530,14 @@ QString UAVObjectParser::processObjectFields(QDomNode& childNode, ObjectInfo* in
return QString("Object:field:incorrect number of default values"); return QString("Object:field:incorrect number of default values");
/*support legacy single default for multiple elements /*support legacy single default for multiple elements
We sould really issue a warning*/ We should really issue a warning*/
for(int ct=1; ct< field->numElements; ct++) for(int ct=1; ct< field->numElements; ct++)
defaults.append(defaults[0]); defaults.append(defaults[0]);
} }
field->defaultValues = defaults; field->defaultValues = defaults;
} }
// Limits attribute
elemAttr = elemAttributes.namedItem("limits"); elemAttr = elemAttributes.namedItem("limits");
if ( elemAttr.isNull() ) { if ( elemAttr.isNull() ) {
field->limitValues=QString(); field->limitValues=QString();

View File

@ -5,29 +5,76 @@
<field name="FeedForward" units="" type="float" elements="1" defaultvalue="0"/> <field name="FeedForward" units="" type="float" elements="1" defaultvalue="0"/>
<field name="AccelTime" units="ms" type="float" elements="1" defaultvalue="0"/> <field name="AccelTime" units="ms" type="float" elements="1" defaultvalue="0"/>
<field name="DecelTime" units="ms" type="float" elements="1" defaultvalue="0"/> <field name="DecelTime" units="ms" type="float" elements="1" defaultvalue="0"/>
<field name="ThrottleCurve1" units="percent" type="float" elements="5" elementnames="0,25,50,75,100" defaultvalue="0,0,0,0,0"/> <field name="ThrottleCurve1" units="percent" type="float" elementnames="0,25,50,75,100" defaultvalue="0,0,0,0,0"/>
<field name="Curve2Source" units="" type="enum" elements="1" options="Throttle,Roll,Pitch,Yaw,Collective,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Throttle"/> <field name="Curve2Source" units="" type="enum" elements="1" defaultvalue="Throttle">
<field name="ThrottleCurve2" units="percent" type="float" elements="5" elementnames="0,25,50,75,100" defaultvalue="0,0.25,0.5,0.75,1"/> <options>
<field name="Mixer1Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/> <option>Throttle</option>
<field name="Mixer1Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/> <option>Roll</option>
<field name="Mixer2Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/> <option>Pitch</option>
<field name="Mixer2Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/> <option>Yaw</option>
<field name="Mixer3Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/> <option>Collective</option>
<field name="Mixer3Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/> <option>Accessory0</option>
<field name="Mixer4Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/> <option>Accessory1</option>
<field name="Mixer4Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/> <option>Accessory2</option>
<field name="Mixer5Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/> <option>Accessory3</option>
<field name="Mixer5Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/> <option>Accessory4</option>
<field name="Mixer6Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/> <option>Accessory5</option>
<field name="Mixer6Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/> </options>
<field name="Mixer7Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/> </field>
<field name="Mixer7Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/> <field name="ThrottleCurve2" units="percent" type="float" elementnames="0,25,50,75,100" defaultvalue="0,0.25,0.5,0.75,1"/>
<field name="Mixer8Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/> <field name="Mixer1Type" units="" type="enum" elements="1" defaultvalue="Disabled">
<field name="Mixer8Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/> <options>
<field name="Mixer9Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/> <option>Disabled</option>
<field name="Mixer9Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/> <option>Motor</option>
<field name="Mixer10Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/> <option>Servo</option>
<field name="Mixer10Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/> <option>CameraRoll</option>
<option>CameraPitch</option>
<option>CameraYaw</option>
<option>Accessory0</option>
<option>Accessory1</option>
<option>Accessory2</option>
<option>Accessory3</option>
<option>Accessory4</option>
<option>Accessory5</option>
</options>
</field>
<field name="Mixer1Vector" units="" type="int8" defaultvalue="0">
<elementnames>
<elementname>ThrottleCurve1</elementname>
<elementname>ThrottleCurve2</elementname>
<elementname>Roll</elementname>
<elementname>Pitch</elementname>
<elementname>Yaw</elementname>
</elementnames>
</field>
<field name="Mixer2Type" cloneof="Mixer1Type"/>
<field name="Mixer2Vector" cloneof="Mixer1Vector"/>
<field name="Mixer3Type" cloneof="Mixer1Type"/>
<field name="Mixer3Vector" cloneof="Mixer1Vector"/>
<field name="Mixer4Type" cloneof="Mixer1Type"/>
<field name="Mixer4Vector" cloneof="Mixer1Vector"/>
<field name="Mixer5Type" cloneof="Mixer1Type"/>
<field name="Mixer5Vector" cloneof="Mixer1Vector"/>
<field name="Mixer6Type" cloneof="Mixer1Type"/>
<field name="Mixer6Vector" cloneof="Mixer1Vector"/>
<field name="Mixer7Type" cloneof="Mixer1Type"/>
<field name="Mixer7Vector" cloneof="Mixer1Vector"/>
<field name="Mixer8Type" cloneof="Mixer1Type"/>
<field name="Mixer8Vector" cloneof="Mixer1Vector"/>
<field name="Mixer9Type" cloneof="Mixer1Type"/>
<field name="Mixer9Vector" cloneof="Mixer1Vector"/>
<field name="Mixer10Type" cloneof="Mixer1Type"/>
<field name="Mixer10Vector" cloneof="Mixer1Vector"/>
<access gcs="readwrite" flight="readwrite"/> <access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/> <telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/> <telemetryflight acked="true" updatemode="onchange" period="0"/>

View File

@ -1,9 +1,79 @@
<xml> <xml>
<object name="TaskInfo" singleinstance="true" settings="false"> <object name="TaskInfo" singleinstance="true" settings="false">
<description>Task information</description> <description>Task information</description>
<field name="StackRemaining" units="bytes" type="uint16" elementnames="System,Actuator,Attitude,Sensors,TelemetryTx,TelemetryTxPri,TelemetryRx,GPS,ManualControl,Altitude,Stabilization,AltitudeHold,Guidance,FlightPlan,Com2UsbBridge,Usb2ComBridge,OveroSync,Autotune,EventDispatcher"/> <field name="StackRemaining" units="bytes" type="uint16">
<field name="Running" units="bool" type="enum" options="False,True" elementnames="System,Actuator,Attitude,Sensors,TelemetryTx,TelemetryTxPri,TelemetryRx,GPS,ManualControl,Altitude,Stabilization,AltitudeHold,Guidance,FlightPlan,Com2UsbBridge,Usb2ComBridge,OveroSync,Autotune,EventDispatcher"/> <elementnames>
<field name="RunningTime" units="%" type="uint8" elementnames="System,Actuator,Attitude,Sensors,TelemetryTx,TelemetryTxPri,TelemetryRx,GPS,ManualControl,Altitude,Stabilization,AltitudeHold,Guidance,FlightPlan,Com2UsbBridge,Usb2ComBridge,OveroSync,Autotune,EventDispatcher"/> <elementname>System</elementname>
<elementname>Actuator</elementname>
<elementname>Attitude</elementname>
<elementname>Sensors</elementname>
<elementname>TelemetryTx</elementname>
<elementname>TelemetryTxPri</elementname>
<elementname>TelemetryRx</elementname>
<elementname>GPS</elementname>
<elementname>ManualControl</elementname>
<elementname>Altitude</elementname>
<elementname>Stabilization</elementname>
<elementname>AltitudeHold</elementname>
<elementname>Guidance</elementname>
<elementname>FlightPlan</elementname>
<elementname>Com2UsbBridge</elementname>
<elementname>Usb2ComBridge</elementname>
<elementname>OveroSync</elementname>
<elementname>Autotune</elementname>
<elementname>EventDispatcher</elementname>
</elementnames>
</field>
<field name="Running" units="bool" type="enum">
<elementnames>
<elementname>System</elementname>
<elementname>Actuator</elementname>
<elementname>Attitude</elementname>
<elementname>Sensors</elementname>
<elementname>TelemetryTx</elementname>
<elementname>TelemetryTxPri</elementname>
<elementname>TelemetryRx</elementname>
<elementname>GPS</elementname>
<elementname>ManualControl</elementname>
<elementname>Altitude</elementname>
<elementname>Stabilization</elementname>
<elementname>AltitudeHold</elementname>
<elementname>Guidance</elementname>
<elementname>FlightPlan</elementname>
<elementname>Com2UsbBridge</elementname>
<elementname>Usb2ComBridge</elementname>
<elementname>OveroSync</elementname>
<elementname>Autotune</elementname>
<elementname>EventDispatcher</elementname>
</elementnames>
<options>
<option>False</option>
<option>True</option>
</options>
</field>
<field name="RunningTime" units="%" type="uint8">
<elementnames>
<elementname>System</elementname>
<elementname>Actuator</elementname>
<elementname>Attitude</elementname>
<elementname>Sensors</elementname>
<elementname>TelemetryTx</elementname>
<elementname>TelemetryTxPri</elementname>
<elementname>TelemetryRx</elementname>
<elementname>GPS</elementname>
<elementname>ManualControl</elementname>
<elementname>Altitude</elementname>
<elementname>Stabilization</elementname>
<elementname>AltitudeHold</elementname>
<elementname>Guidance</elementname>
<elementname>FlightPlan</elementname>
<elementname>Com2UsbBridge</elementname>
<elementname>Usb2ComBridge</elementname>
<elementname>OveroSync</elementname>
<elementname>Autotune</elementname>
<elementname>EventDispatcher</elementname>
</elementnames>
</field>
<access gcs="readwrite" flight="readwrite"/> <access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/> <telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="periodic" period="10000"/> <telemetryflight acked="true" updatemode="periodic" period="10000"/>