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

Merge branch 'next' into corvuscorax/o3fixes

This commit is contained in:
Richard Flay (Hyper) 2013-05-16 05:56:45 +09:30
commit 9572a156ce
64 changed files with 10502 additions and 8379 deletions

View File

@ -654,6 +654,7 @@ ut_$(1)_%: $$(UT_OUT_DIR)
$(V1) cd $(ROOT_DIR)/flight/tests/$(1) && \
$$(MAKE) -r --no-print-directory \
BUILD_TYPE=ut \
BOARD_SHORT_NAME=$(1) \
TOPDIR=$(ROOT_DIR)/flight/tests/$(1) \
OUTDIR="$(UT_OUT_DIR)/$(1)" \
TARGET=$(1) \

View File

@ -45,18 +45,19 @@
#include <openpilot.h>
#include "CoordinateConversions.h"
#include "altholdsmoothed.h"
#include "attitudeactual.h"
#include "altitudeholdsettings.h"
#include "altitudeholddesired.h" // object that will be updated by the module
#include "baroaltitude.h"
#include "positionactual.h"
#include "flightstatus.h"
#include "stabilizationdesired.h"
#include "accels.h"
#include "taskinfo.h"
#include <math.h>
#include <CoordinateConversions.h>
#include <altholdsmoothed.h>
#include <attitudeactual.h>
#include <altitudeholdsettings.h>
#include <altitudeholddesired.h> // object that will be updated by the module
#include <baroaltitude.h>
#include <positionactual.h>
#include <flightstatus.h>
#include <stabilizationdesired.h>
#include <accels.h>
#include <taskinfo.h>
#include <pios_constants.h>
// Private constants
#define MAX_QUEUE_SIZE 2
#define STACK_SIZE_BYTES 1024
@ -340,7 +341,8 @@ static void altitudeHoldTask(__attribute__((unused)) void *parameters)
// Verify that we are in altitude hold mode
FlightStatusData flightStatus;
FlightStatusGet(&flightStatus);
if(flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) {
if(flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD ||
flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED) {
running = false;
}

View File

@ -51,7 +51,8 @@
#include "stabilizationdesired.h"
#include "receiveractivity.h"
#include "systemsettings.h"
#include "taskinfo.h"
#include <altitudeholdsettings.h>
#include <taskinfo.h>
#if defined(PIOS_INCLUDE_USB_RCTX)
#include "pios_usb_rctx.h"
@ -799,16 +800,25 @@ static void updateLandDesired(__attribute__((unused)) ManualControlCommandData *
*/
static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed)
{
const float DEADBAND_HIGH = 0.55f;
const float DEADBAND_LOW = 0.45f;
const float DEADBAND = 0.10f;
const float DEADBAND_HIGH = 1.0f / 2 + DEADBAND / 2;
const float DEADBAND_LOW = 1.0f / 2 - DEADBAND / 2;
// this is the max speed in m/s at the extents of throttle
uint8_t throttleRate;
uint8_t throttleExp;
static portTickType lastSysTime;
static bool zeroed = false;
portTickType thisSysTime;
float dT;
AltitudeHoldDesiredData altitudeHoldDesired;
AltitudeHoldDesiredGet(&altitudeHoldDesired);
AltitudeHoldSettingsThrottleExpGet(&throttleExp);
AltitudeHoldSettingsThrottleRateGet(&throttleRate);
StabilizationSettingsData stabSettings;
StabilizationSettingsGet(&stabSettings);
@ -827,9 +837,11 @@ static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed)
altitudeHoldDesired.Altitude = 0;
zeroed = false;
} else if (cmd->Throttle > DEADBAND_HIGH && zeroed) {
altitudeHoldDesired.Altitude += (cmd->Throttle - DEADBAND_HIGH) * dT;
// being the two band symmetrical I can divide by DEADBAND_LOW to scale it to a value betweeon 0 and 1
// then apply an "exp" f(x,k) = (k∙x∙x∙x + x∙(256k)) / 256
altitudeHoldDesired.Altitude += (throttleExp * powf((cmd->Throttle - DEADBAND_HIGH) / (DEADBAND_LOW), 3) + (256 - throttleExp)) / 256 * throttleRate * dT;
} else if (cmd->Throttle < DEADBAND_LOW && zeroed) {
altitudeHoldDesired.Altitude += (cmd->Throttle - DEADBAND_LOW) * dT;
altitudeHoldDesired.Altitude -= (throttleExp * powf((DEADBAND_LOW - (cmd->Throttle < 0 ? 0 : cmd->Throttle)) / DEADBAND_LOW, 3) + (256 - throttleExp)) / 256 * throttleRate * dT;
} else if (cmd->Throttle >= DEADBAND_LOW && cmd->Throttle <= DEADBAND_HIGH) {
// Require the stick to enter the dead band before they can move height
zeroed = true;
@ -905,6 +917,7 @@ static bool okToArm(void)
{
// read alarms
SystemAlarmsData alarms;
SystemAlarmsGet(&alarms);
// Check each alarm
@ -913,11 +926,23 @@ static bool okToArm(void)
if (i == SYSTEMALARMS_ALARM_GPS || i == SYSTEMALARMS_ALARM_TELEMETRY) {
continue;
}
return false;
}
}
uint8_t flightMode;
FlightStatusFlightModeGet(&flightMode);
switch(flightMode) {
case FLIGHTSTATUS_FLIGHTMODE_MANUAL:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
return true;
default:
return false;
}
}
/**
* @brief Determine if the aircraft is forced to disarm by an explicit alarm

View File

@ -128,8 +128,9 @@ int32_t PIOS_BMA180_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_
*/
int32_t PIOS_BMA180_ClaimBus()
{
if(PIOS_BMA180_Validate(dev) != 0)
if (PIOS_BMA180_Validate(dev) != 0) {
return -1;
}
if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) {
return -1;
@ -141,15 +142,18 @@ int32_t PIOS_BMA180_ClaimBus()
}
/**
* @brief Claim the SPI bus for the accel communications and select this chip
* @brief Claim the SPI bus for the accel communications and select this chip. Call from an ISR.
* @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
* @return 0 if successful, -1 if unable to claim bus
*/
int32_t PIOS_BMA180_ClaimBusISR()
int32_t PIOS_BMA180_ClaimBusISR(bool *woken)
{
if(PIOS_BMA180_Validate(dev) != 0)
if (PIOS_BMA180_Validate(dev) != 0) {
return -1;
}
if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) {
if (PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) {
return -1;
}
@ -162,13 +166,29 @@ int32_t PIOS_BMA180_ClaimBusISR()
* @return 0 if successful
*/
int32_t PIOS_BMA180_ReleaseBus()
{
if (PIOS_BMA180_Validate(dev) != 0) {
return -1;
}
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
return PIOS_SPI_ReleaseBus(dev->spi_id);
}
/**
* @brief Release the SPI bus for the accel communications and end the transaction. Call from an ISR
* @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
* @return 0 if successful
*/
int32_t PIOS_BMA180_ReleaseBusISR(bool *woken)
{
if(PIOS_BMA180_Validate(dev) != 0)
return -1;
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
return PIOS_SPI_ReleaseBus(dev->spi_id);
return PIOS_SPI_ReleaseBusISR(dev->spi_id, woken);
}
/**
@ -431,19 +451,21 @@ int32_t PIOS_BMA180_Test()
}
/**
* @brief IRQ Handler. Read data from the BMA180 FIFO and push onto a local fifo.
* @brief EXTI IRQ Handler. Read data from the BMA180 FIFO and push onto a local fifo.
* @return a boolean to the EXTI IRQ Handler wrapper indicating if a
* higher priority task is now eligible to run
*/
int32_t bma180_irqs = 0;
bool PIOS_BMA180_IRQHandler(void)
{
bma180_irqs++;
bool woken = false;
static const uint8_t pios_bma180_req_buf[7] = {BMA_X_LSB_ADDR | 0x80,0,0,0,0,0};
uint8_t pios_bma180_dmabuf[8];
bma180_irqs++;
// If we can't get the bus then just move on for efficiency
if(PIOS_BMA180_ClaimBusISR() != 0) {
return false; // Something else is using bus, miss this data
if (PIOS_BMA180_ClaimBusISR(&woken) != 0) {
return woken; // Something else is using bus, miss this data
}
PIOS_SPI_TransferBlock(dev->spi_id,pios_bma180_req_buf,(uint8_t *) pios_bma180_dmabuf,
@ -453,11 +475,12 @@ bool PIOS_BMA180_IRQHandler(void)
struct pios_bma180_data data;
// Don't release bus till data has copied
PIOS_BMA180_ReleaseBus();
PIOS_BMA180_ReleaseBusISR(&woken);
// Must not return before releasing bus
if(fifoBuf_getFree(&dev->fifo) < sizeof(data))
return false;
if (fifoBuf_getFree(&dev->fifo) < sizeof(data)) {
return woken;
}
// Bottom two bits indicate new data and are constant zeros. Don't right
// shift because it drops sign bit
@ -471,7 +494,7 @@ bool PIOS_BMA180_IRQHandler(void)
fifoBuf_putData(&dev->fifo, (uint8_t *) &data, sizeof(data));
return false;
return woken;
}
#endif /* PIOS_INCLUDE_BMA180 */

View File

@ -29,13 +29,12 @@
#ifdef PIOS_INCLUDE_FLASH
#include "openpilot.h"
#include <stdbool.h>
#include <openpilot.h>
#include <pios_math.h>
#include "pios_flashfs_logfs_priv.h"
#include <stdbool.h>
/*
* Filesystem state data tracked in RAM
*/

View File

@ -60,9 +60,11 @@ static int32_t PIOS_L3GD20_Validate(struct l3gd20_dev * dev);
static void PIOS_L3GD20_Config(struct pios_l3gd20_cfg const * cfg);
static int32_t PIOS_L3GD20_SetReg(uint8_t address, uint8_t buffer);
static int32_t PIOS_L3GD20_GetReg(uint8_t address);
static int32_t PIOS_L3GD20_GetRegISR(uint8_t address, bool *woken);
static int32_t PIOS_L3GD20_ClaimBus();
static int32_t PIOS_L3GD20_ClaimBusIsr();
static int32_t PIOS_L3GD20_ClaimBusISR(bool *woken);
static int32_t PIOS_L3GD20_ReleaseBus();
static int32_t PIOS_L3GD20_ReleaseBusISR(bool *woken);
volatile bool l3gd20_configured = false;
@ -191,16 +193,18 @@ static int32_t PIOS_L3GD20_ClaimBus()
/**
* @brief Claim the SPI bus for the accel communications and select this chip
* @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
* @return 0 if successful, -1 for invalid device, -2 if unable to claim bus
*/
static int32_t PIOS_L3GD20_ClaimBusIsr()
static int32_t PIOS_L3GD20_ClaimBusISR(bool *woken)
{
if(PIOS_L3GD20_Validate(dev) != 0)
if(PIOS_L3GD20_Validate(dev) != 0) {
return -1;
if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0)
}
if(PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) {
return -2;
}
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
return 0;
}
@ -211,14 +215,28 @@ static int32_t PIOS_L3GD20_ClaimBusIsr()
*/
int32_t PIOS_L3GD20_ReleaseBus()
{
if(PIOS_L3GD20_Validate(dev) != 0)
if(PIOS_L3GD20_Validate(dev) != 0) {
return -1;
}
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
return PIOS_SPI_ReleaseBus(dev->spi_id);
}
/**
* @brief Release the SPI bus for the accel communications and end the transaction
* @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
* @return 0 if successful, -1 for invalid device
*/
int32_t PIOS_L3GD20_ReleaseBusISR(bool *woken)
{
if(PIOS_L3GD20_Validate(dev) != 0) {
return -1;
}
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
return PIOS_SPI_ReleaseBusISR(dev->spi_id, woken);
}
/**
* @brief Read a register from L3GD20
* @returns The register value or -1 if failure to get bus
@ -238,6 +256,26 @@ static int32_t PIOS_L3GD20_GetReg(uint8_t reg)
return data;
}
/**
* @brief Read a register from L3GD20 in an ISR context
* @param reg[in] Register address to be read
* @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
* @return The register value or -1 if failure to get bus
*/
static int32_t PIOS_L3GD20_GetRegISR(uint8_t reg, bool *woken)
{
uint8_t data;
if(PIOS_L3GD20_ClaimBusISR(woken) != 0) {
return -1;
}
PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte
data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response
PIOS_L3GD20_ReleaseBusISR(woken);
return data;
}
/**
* @brief Writes one byte to the L3GD20
* \param[in] reg Register address
@ -349,34 +387,38 @@ uint8_t PIOS_L3GD20_Test(void)
}
/**
* @brief IRQ Handler. Read all the data from onboard buffer
* @brief EXTI IRQ Handler. Read all the data from onboard buffer
* @return a boolean to the EXTI IRQ Handler wrapper indicating if a
* higher priority task is now eligible to run
*/
bool PIOS_L3GD20_IRQHandler(void)
{
l3gd20_irq++;
bool woken = false;
struct pios_l3gd20_data data;
uint8_t buf[7] = {PIOS_L3GD20_GYRO_X_OUT_LSB | 0x80 | 0x40, 0, 0, 0, 0, 0, 0};
uint8_t rec[7];
/* This code duplicates ReadGyros above but uses ClaimBusIsr */
if(PIOS_L3GD20_ClaimBusIsr() != 0)
return false;
l3gd20_irq++;
if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) {
PIOS_L3GD20_ReleaseBus();
return false;
/* This code duplicates ReadGyros above but uses ClaimBusIsr */
if (PIOS_L3GD20_ClaimBusISR(&woken) != 0) {
return woken;
}
PIOS_L3GD20_ReleaseBus();
if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) {
PIOS_L3GD20_ReleaseBusISR(&woken);
return woken;
}
PIOS_L3GD20_ReleaseBusISR(&woken);
memcpy((uint8_t *) &(data.gyro_x), &rec[1], 6);
data.temperature = PIOS_L3GD20_GetReg(PIOS_L3GD20_OUT_TEMP);
data.temperature = PIOS_L3GD20_GetRegISR(PIOS_L3GD20_OUT_TEMP, &woken);
portBASE_TYPE xHigherPriorityTaskWoken;
xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken);
signed portBASE_TYPE higherPriorityTaskWoken;
xQueueSendToBackFromISR(dev->queue, (void *) &data, &higherPriorityTaskWoken);
return xHigherPriorityTaskWoken == pdTRUE;
return (woken || higherPriorityTaskWoken == pdTRUE);
}
#endif /* PIOS_INCLUDE_L3GD20 */

View File

@ -197,7 +197,12 @@ int32_t PIOS_MPU6000_ConfigureRanges(
{
if(dev == NULL)
return -1;
// TODO: check that changing the SPI clock speed is safe
// to do here given that interrupts are enabled and the bus has
// not been claimed/is not claimed during this call
PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_256);
// update filter settings
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_DLPF_CFG_REG, filterSetting) != 0);
@ -225,17 +230,31 @@ int32_t PIOS_MPU6000_ConfigureRanges(
/**
* @brief Claim the SPI bus for the accel communications and select this chip
* @return 0 if successful, -1 for invalid device, -2 if unable to claim bus
* @param fromIsr[in] Tells if the function is being called from a ISR or not
*/
static int32_t PIOS_MPU6000_ClaimBus(bool fromIsr)
static int32_t PIOS_MPU6000_ClaimBus()
{
if(PIOS_MPU6000_Validate(dev) != 0)
if(PIOS_MPU6000_Validate(dev) != 0) {
return -1;
if(fromIsr){
if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0)
}
if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) {
return -2;
} else {
if(PIOS_SPI_ClaimBus(dev->spi_id) != 0)
}
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
return 0;
}
/**
* @brief Claim the SPI bus for the accel communications and select this chip
* @return 0 if successful, -1 for invalid device, -2 if unable to claim bus
* @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
*/
static int32_t PIOS_MPU6000_ClaimBusISR(bool *woken)
{
if (PIOS_MPU6000_Validate(dev) != 0) {
return -1;
}
if (PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) {
return -2;
}
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
@ -245,19 +264,29 @@ static int32_t PIOS_MPU6000_ClaimBus(bool fromIsr)
/**
* @brief Release the SPI bus for the accel communications and end the transaction
* @return 0 if successful
* @param fromIsr[in] Tells if the function is being called from a ISR or not
*/
int32_t PIOS_MPU6000_ReleaseBus(bool fromIsr)
static int32_t PIOS_MPU6000_ReleaseBus()
{
if(PIOS_MPU6000_Validate(dev) != 0)
if(PIOS_MPU6000_Validate(dev) != 0) {
return -1;
}
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
if(fromIsr){
return PIOS_SPI_ReleaseBusISR(dev->spi_id);
} else {
return PIOS_SPI_ReleaseBus(dev->spi_id);
}
/**
* @brief Release the SPI bus for the accel communications and end the transaction
* @return 0 if successful
* @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
*/
static int32_t PIOS_MPU6000_ReleaseBusISR(bool *woken)
{
if(PIOS_MPU6000_Validate(dev) != 0) {
return -1;
}
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
return PIOS_SPI_ReleaseBusISR(dev->spi_id, woken);
}
/**
@ -269,13 +298,14 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg)
{
uint8_t data;
if(PIOS_MPU6000_ClaimBus(false) != 0)
if(PIOS_MPU6000_ClaimBus() != 0) {
return -1;
}
PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte
data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response
PIOS_MPU6000_ReleaseBus(false);
PIOS_MPU6000_ReleaseBus();
return data;
}
@ -289,20 +319,21 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg)
*/
static int32_t PIOS_MPU6000_SetReg(uint8_t reg, uint8_t data)
{
if(PIOS_MPU6000_ClaimBus(false) != 0)
if (PIOS_MPU6000_ClaimBus() != 0) {
return -1;
}
if (PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg) != 0) {
PIOS_MPU6000_ReleaseBus(false);
PIOS_MPU6000_ReleaseBus();
return -2;
}
if (PIOS_SPI_TransferByte(dev->spi_id, data) != 0) {
PIOS_MPU6000_ReleaseBus(false);
PIOS_MPU6000_ReleaseBus();
return -3;
}
PIOS_MPU6000_ReleaseBus(false);
PIOS_MPU6000_ReleaseBus();
return 0;
}
@ -318,13 +349,15 @@ int32_t PIOS_MPU6000_ReadGyros(struct pios_mpu6000_data * data)
uint8_t buf[7] = {PIOS_MPU6000_GYRO_X_OUT_MSB | 0x80, 0, 0, 0, 0, 0, 0};
uint8_t rec[7];
if(PIOS_MPU6000_ClaimBus(false) != 0)
if (PIOS_MPU6000_ClaimBus() != 0) {
return -1;
}
if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0)
if (PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) {
return -2;
}
PIOS_MPU6000_ReleaseBus(false);
PIOS_MPU6000_ReleaseBus();
data->gyro_x = rec[1] << 8 | rec[2];
data->gyro_y = rec[3] << 8 | rec[4];
@ -407,31 +440,34 @@ int32_t PIOS_MPU6000_Test(void)
}
/**
* @brief Run self-test operation.
* \return 0 if test succeeded
* \return non-zero value if test succeeded
* @param fromIsr[in] Tells if the function is being called from a ISR or not
* @brief Obtains the number of bytes in the FIFO. Call from ISR only.
* @return the number of bytes in the FIFO
* @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
*/
static int32_t PIOS_MPU6000_FifoDepth(bool fromIsr)
static int32_t PIOS_MPU6000_FifoDepthISR(bool *woken)
{
uint8_t mpu6000_send_buf[3] = {PIOS_MPU6000_FIFO_CNT_MSB | 0x80, 0, 0};
uint8_t mpu6000_rec_buf[3];
if(PIOS_MPU6000_ClaimBus(fromIsr) != 0)
return -1;
if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) {
PIOS_MPU6000_ReleaseBus(fromIsr);
if(PIOS_MPU6000_ClaimBusISR(woken) != 0) {
return -1;
}
PIOS_MPU6000_ReleaseBus(fromIsr);
if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) {
PIOS_MPU6000_ReleaseBusISR(woken);
return -1;
}
PIOS_MPU6000_ReleaseBusISR(woken);
return (mpu6000_rec_buf[1] << 8) | mpu6000_rec_buf[2];
}
/**
* @brief IRQ Handler. Read all the data from onboard buffer
* @brief EXTI IRQ Handler. Read all the data from onboard buffer
* @return a boolean to the EXTI IRQ Handler wrapper indicating if a
* higher priority task is now eligible to run
*/
uint32_t mpu6000_irq = 0;
int32_t mpu6000_count;
@ -446,46 +482,50 @@ uint32_t mpu6000_transfer_size;
bool PIOS_MPU6000_IRQHandler(void)
{
bool woken = false;
static uint32_t timeval;
mpu6000_interval_us = PIOS_DELAY_DiffuS(timeval);
timeval = PIOS_DELAY_GetRaw();
if (!mpu6000_configured)
if (!mpu6000_configured) {
return false;
}
mpu6000_count = PIOS_MPU6000_FifoDepth(true);
if (mpu6000_count < (int32_t)sizeof(struct pios_mpu6000_data))
return false;
mpu6000_count = PIOS_MPU6000_FifoDepthISR(&woken);
if (mpu6000_count < (int32_t)sizeof(struct pios_mpu6000_data)) {
return woken;
}
if (PIOS_MPU6000_ClaimBus(true) != 0)
return false;
if (PIOS_MPU6000_ClaimBusISR(&woken) != 0) {
return woken;
}
static uint8_t mpu6000_send_buf[1 + sizeof(struct pios_mpu6000_data) ] = {PIOS_MPU6000_FIFO_REG | 0x80, 0, 0, 0, 0, 0, 0, 0, 0};
static 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) {
PIOS_MPU6000_ReleaseBus(true);
PIOS_MPU6000_ReleaseBusISR(&woken);
mpu6000_fails++;
return false;
return woken;
}
PIOS_MPU6000_ReleaseBus(true);
PIOS_MPU6000_ReleaseBusISR(&woken);
static struct pios_mpu6000_data data;
// In the case where extras samples backed up grabbed an extra
if (mpu6000_count >= (int32_t)(sizeof(data) * 2)) {
mpu6000_fifo_backup++;
if (PIOS_MPU6000_ClaimBus(true) != 0)
return false;
if (PIOS_MPU6000_ClaimBusISR(&woken) != 0)
return woken;
if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) {
PIOS_MPU6000_ReleaseBus(true);
PIOS_MPU6000_ReleaseBusISR(&woken);
mpu6000_fails++;
return false;
return woken;
}
PIOS_MPU6000_ReleaseBus(true);
PIOS_MPU6000_ReleaseBusISR(&woken);
}
// Rotate the sensor to OP convention. The datasheet defines X as towards the right
@ -548,14 +588,14 @@ bool PIOS_MPU6000_IRQHandler(void)
data.temperature = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2];
#endif
portBASE_TYPE xHigherPriorityTaskWoken;
xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken);
signed portBASE_TYPE higherPriorityTaskWoken;
xQueueSendToBackFromISR(dev->queue, (void *) &data, &higherPriorityTaskWoken);
mpu6000_irq++;
mpu6000_time_us = PIOS_DELAY_DiffuS(timeval);
return xHigherPriorityTaskWoken == pdTRUE;
return (woken || higherPriorityTaskWoken == pdTRUE);
}
#endif /* PIOS_INCLUDE_MPU6000 */

View File

@ -49,9 +49,9 @@ extern int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b);
extern int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback);
extern int32_t PIOS_SPI_Busy(uint32_t spi_id);
extern int32_t PIOS_SPI_ClaimBus(uint32_t spi_id);
extern int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id);
extern int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id, bool *woken);
extern int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id);
extern int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id);
extern int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id, bool *woken);
extern void PIOS_SPI_IRQ_Handler(uint32_t spi_id);
extern void PIOS_SPI_SetPrescalar(uint32_t spi_id, uint32_t prescalar);

View File

@ -265,22 +265,33 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id)
/**
* Claim the SPI bus semaphore from an ISR. Has no timeout.
* \param[in] spi SPI number (0 or 1)
* \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
* \return 0 if no error
* \return -1 if timeout before claiming semaphore
*/
int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id)
int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id, bool *woken)
{
#if defined(PIOS_INCLUDE_FREERTOS)
struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id;
signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE;
bool valid = PIOS_SPI_validate(spi_dev);
PIOS_Assert(valid)
if (xSemaphoreTakeFromISR(spi_dev->busy, NULL) != pdTRUE){
if (xSemaphoreTakeFromISR(spi_dev->busy, &higherPriorityTaskWoken) != pdTRUE){
return -1;
}
#endif
if (woken) {
*woken = *woken || (higherPriorityTaskWoken == pdTRUE);
}
return 0;
#else
if (woken) {
*woken = false;
}
return PIOS_SPI_ClaimBus(spi_id);
#endif
}
/**
@ -302,7 +313,6 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id)
PIOS_IRQ_Disable();
spi_dev->busy = 0;
PIOS_IRQ_Enable();
#endif
return 0;
}
@ -310,25 +320,30 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id)
/**
* Release the SPI bus semaphore from ISR. Calling the SPI functions does not require this
* \param[in] spi SPI number (0 or 1)
* \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
* \return 0 if no error
*/
int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id)
int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id, bool *woken)
{
#if defined(PIOS_INCLUDE_FREERTOS)
struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id;
signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE;
bool valid = PIOS_SPI_validate(spi_dev);
PIOS_Assert(valid)
xSemaphoreGiveFromISR(spi_dev->busy, NULL);
#else
struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id;
PIOS_IRQ_Disable();
spi_dev->busy = 0;
PIOS_IRQ_Enable();
#endif
xSemaphoreGiveFromISR(spi_dev->busy, &higherPriorityTaskWoken);
if (woken) {
*woken = *woken || (higherPriorityTaskWoken == pdTRUE);
}
return 0;
#else
if (woken) {
*woken = false;
}
return PIOS_SPI_ReleaseBus(spi_id);
#endif
}

View File

@ -257,6 +257,18 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id)
if (xSemaphoreTake(spi_dev->busy, 0xffff) != pdTRUE)
return -1;
#else
struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id;
uint32_t timeout = 0xffff;
while((PIOS_SPI_Busy(spi_id) || spi_dev->busy) && --timeout);
if(timeout == 0) //timed out
return -1;
PIOS_IRQ_Disable();
if(spi_dev->busy)
return -1;
spi_dev->busy = 1;
PIOS_IRQ_Enable();
#endif
return 0;
}
@ -264,24 +276,34 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id)
/**
* Claim the SPI bus semaphore from an ISR. Has no timeout.
* \param[in] spi SPI number (0 or 1)
* \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
* \return 0 if no error
* \return -1 if timeout before claiming semaphore
*/
int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id)
int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id, bool *woken)
{
#if defined(PIOS_INCLUDE_FREERTOS)
struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id;
signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE;
bool valid = PIOS_SPI_validate(spi_dev);
PIOS_Assert(valid)
if (xSemaphoreTakeFromISR(spi_dev->busy, NULL) != pdTRUE){
if (xSemaphoreTakeFromISR(spi_dev->busy, &higherPriorityTaskWoken) != pdTRUE){
return -1;
}
#endif
return 0;
if (woken) {
*woken = *woken || (higherPriorityTaskWoken == pdTRUE);
}
return 0;
#else
if (woken) {
*woken = false;
}
return PIOS_SPI_ClaimBus(spi_id);
#endif
}
/**
* Release the SPI bus semaphore. Calling the SPI functions does not require this
@ -297,6 +319,11 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id)
PIOS_Assert(valid)
xSemaphoreGive(spi_dev->busy);
#else
struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id;
PIOS_IRQ_Disable();
spi_dev->busy = 0;
PIOS_IRQ_Enable();
#endif
return 0;
}
@ -304,20 +331,32 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id)
/**
* Release the SPI bus semaphore from ISR. Calling the SPI functions does not require this
* \param[in] spi SPI number (0 or 1)
* \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
* task has is now eligible to run, else unchanged
* \return 0 if no error
*/
int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id)
int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id, bool *woken)
{
#if defined(PIOS_INCLUDE_FREERTOS)
struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id;
signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE;
bool valid = PIOS_SPI_validate(spi_dev);
PIOS_Assert(valid)
xSemaphoreGiveFromISR(spi_dev->busy, NULL);
#endif
return 0;
xSemaphoreGiveFromISR(spi_dev->busy, &higherPriorityTaskWoken);
if (woken) {
*woken = *woken || (higherPriorityTaskWoken == pdTRUE);
}
return 0;
#else
if (woken) {
*woken = false;
}
return PIOS_SPI_ReleaseBus(spi_id);
#endif
}
/**
* Controls the RC (Register Clock alias Chip Select) pin of a SPI port

View File

@ -23,13 +23,27 @@ QSlider::add-page:horizontal {
border-radius: 4px;
}
QSlider::add-page:horizontal:disabled {
background: #eee;
border: 1px solid #999;
width: 1px;
border-radius: 4px;
}
QSlider::sub-page:horizontal {
background: rgb(249, 117, 76);
background: rgb(78, 147, 246);
border: 1px solid #777;
height: 1px;
border-radius: 4px;
}
QSlider::sub-page:horizontal:disabled {
background: #ccc;
border: 1px solid #999;
width: 1px;
border-radius: 4px;
}
QSlider::handle:horizontal {
background: rgb(196, 196, 196);
width: 18px;
@ -56,13 +70,27 @@ QSlider::sub-page:vertical {
border-radius: 4px;
}
QSlider::sub-page:vertical:disabled {
background: #eee;
border: 1px solid #999;
width: 1px;
border-radius: 4px;
}
QSlider::add-page:vertical {
background: rgb(249, 117, 76);
background: rgb(78, 147, 246);
border: 1px solid #777;
width: 1px;
border-radius: 4px;
}
QSlider::add-page:vertical:disabled {
background: #ccc;
border: 1px solid #999;
width: 1px;
border-radius: 4px;
}
QSlider::handle:vertical {
background: rgb(196, 196, 196);
width: 18px;

View File

@ -1,18 +1 @@
/* Windows styles */
QGroupBox {
border: 1px solid gray;
border-radius: 3px;
margin-top: 1ex;
padding: 1ex 0px 0px 0px;
font-size: 11px;
font-weight: bold;
}
QGroupBox::title {
subcontrol-origin: margin;
subcontrol-position: top left;
left: 7px;
top: -1ex;
padding: 0px 3px;
}

View File

@ -91,6 +91,13 @@ void MyTabbedStackWidget::removeTab(int index)
delete item;
}
void MyTabbedStackWidget::setWidgetsEnabled(bool enabled)
{
for(int i = 0; i < m_stackWidget->count(); i++) {
m_stackWidget->widget(i)->setEnabled(enabled);
}
}
int MyTabbedStackWidget::currentIndex() const
{
return m_listWidget->currentRow();

View File

@ -47,6 +47,8 @@ public:
void removeTab(int index);
void setIconSize(int size) { m_listWidget->setIconSize(QSize(size, size)); }
void setWidgetsEnabled(bool enabled);
int currentIndex() const;
void insertCornerWidget(int index, QWidget *widget);

View File

@ -308,7 +308,9 @@ void ConfigCcpmWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->SwashLvlPositionSlider);
parent.addWidget(m_aircraft->SwashLvlPositionSpinBox);
parent.addWidget(m_aircraft->ThrottleCurve->getCurveWidget());
parent.addWidget(m_aircraft->PitchCurve->getCurveWidget());
parent.addWidget(m_aircraft->PitchCurve);
parent.addWidget(m_aircraft->ThrottleCurve->getCurveWidget());
parent.addWidget(m_aircraft->PitchCurve);
parent.addWidget(m_aircraft->ccpmAdvancedSettingsTable);
}

View File

@ -68,7 +68,6 @@ ConfigCustomWidget::ConfigCustomWidget(QWidget *parent) :
for (int i = 1; i < (int) VehicleConfig::CHANNEL_NUMELEM; i++) {
m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd);
}
}
ConfigCustomWidget::~ConfigCustomWidget()
@ -84,7 +83,9 @@ void ConfigCustomWidget::setupUI(QString frameType)
void ConfigCustomWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->customMixerTable);
parent.addWidget(m_aircraft->customThrottle1Curve->getCurveWidget());
parent.addWidget(m_aircraft->customThrottle1Curve);
parent.addWidget(m_aircraft->customThrottle2Curve->getCurveWidget());
parent.addWidget(m_aircraft->customThrottle2Curve);
}
void ConfigCustomWidget::resetActuators(GUIConfigDataUnion *configData)

View File

@ -87,11 +87,9 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) :
m_aircraft->fixedWingType->addItems(fixedWingTypes);
// Set default model to "Elevator aileron rudder"
m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder"));
//setupUI(m_aircraft->fixedWingType->currentText());
connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString)));
m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder"));
setupUI(m_aircraft->fixedWingType->currentText());
}
ConfigFixedWingWidget::~ConfigFixedWingWidget()
@ -109,64 +107,61 @@ void ConfigFixedWingWidget::setupUI(QString frameType)
if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") {
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder"));
m_aircraft->fwRudder1ChannelBox->setEnabled(true);
m_aircraft->fwRudder1Label->setEnabled(true);
m_aircraft->fwRudder2ChannelBox->setEnabled(true);
m_aircraft->fwRudder2Label->setEnabled(true);
m_aircraft->fwElevator1ChannelBox->setEnabled(true);
m_aircraft->fwElevator1Label->setEnabled(true);
m_aircraft->fwElevator2ChannelBox->setEnabled(true);
m_aircraft->fwElevator2Label->setEnabled(true);
m_aircraft->fwAileron1ChannelBox->setEnabled(true);
m_aircraft->fwAileron1Label->setEnabled(true);
m_aircraft->fwAileron2ChannelBox->setEnabled(true);
m_aircraft->fwAileron2Label->setEnabled(true);
m_aircraft->fwAileron1Label->setText("Aileron 1");
m_aircraft->fwAileron2Label->setText("Aileron 2");
m_aircraft->fwElevator1Label->setText("Elevator 1");
m_aircraft->fwElevator2Label->setText("Elevator 2");
m_aircraft->elevonMixBox->setHidden(true);
m_aircraft->elevonSlider1->setEnabled(false);
m_aircraft->elevonSlider2->setEnabled(false);
} else if (frameType == "FixedWingElevon" || frameType == "Elevon") {
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon"));
m_aircraft->fwAileron1Label->setText("Elevon 1");
m_aircraft->fwAileron2Label->setText("Elevon 2");
m_aircraft->fwElevator1ChannelBox->setEnabled(false);
m_aircraft->fwElevator1Label->setEnabled(false);
m_aircraft->fwElevator2ChannelBox->setEnabled(false);
m_aircraft->fwElevator2Label->setEnabled(false);
m_aircraft->fwRudder1ChannelBox->setEnabled(true);
m_aircraft->fwRudder1Label->setEnabled(true);
m_aircraft->fwRudder2ChannelBox->setEnabled(true);
m_aircraft->fwRudder2Label->setEnabled(true);
m_aircraft->fwElevator1Label->setText("Elevator 1");
m_aircraft->fwElevator2Label->setText("Elevator 2");
m_aircraft->elevonMixBox->setHidden(false);
m_aircraft->elevonLabel1->setText("Roll");
m_aircraft->elevonLabel2->setText("Pitch");
m_aircraft->elevonSlider1->setEnabled(true);
m_aircraft->elevonSlider2->setEnabled(true);
} else if (frameType == "FixedWingVtail" || frameType == "Vtail") {
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail"));
m_aircraft->fwRudder1ChannelBox->setEnabled(false);
m_aircraft->fwRudder1Label->setEnabled(false);
m_aircraft->fwRudder2ChannelBox->setEnabled(false);
m_aircraft->fwRudder2Label->setEnabled(false);
m_aircraft->fwElevator1ChannelBox->setEnabled(true);
m_aircraft->fwElevator1Label->setEnabled(true);
m_aircraft->fwElevator1Label->setText("Vtail 1");
m_aircraft->fwElevator1ChannelBox->setEnabled(true);
m_aircraft->fwElevator2Label->setText("Vtail 2");
m_aircraft->elevonMixBox->setHidden(false);
m_aircraft->fwElevator2ChannelBox->setEnabled(true);
m_aircraft->fwElevator2Label->setEnabled(true);
m_aircraft->fwAileron1Label->setText("Aileron 1");
m_aircraft->fwAileron2Label->setText("Aileron 2");
m_aircraft->elevonLabel1->setText("Rudder");
m_aircraft->elevonLabel2->setText("Pitch");
m_aircraft->elevonSlider1->setEnabled(true);
m_aircraft->elevonSlider2->setEnabled(true);
}
}
void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->fixedWingThrottle->getCurveWidget());
parent.addWidget(m_aircraft->fixedWingThrottle);
parent.addWidget(m_aircraft->fixedWingType);
parent.addWidget(m_aircraft->fwEngineChannelBox);
@ -508,6 +503,14 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType)
return true;
}
void ConfigFixedWingWidget::enableControls(bool enable)
{
ConfigTaskWidget::enableControls(enable);
if(enable) {
setupUI(m_aircraft->fixedWingType->currentText());
}
}
/**
This function displays text and color formatting in order to help the user understand what channels have not yet been configured.
*/

View File

@ -64,6 +64,9 @@ private:
bool setupFrameElevon(QString airframeType);
bool setupFrameVtail(QString airframeType);
protected:
void enableControls(bool enable);
private slots:
virtual void setupUI(QString airframeType);
virtual bool throwConfigError(QString airframeType);

View File

@ -79,11 +79,9 @@ ConfigGroundVehicleWidget::ConfigGroundVehicleWidget(QWidget *parent) :
m_aircraft->groundVehicleType->addItems(groundVehicleTypes);
// Set default model to "Turnable (car)"
m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Turnable (car)"));
//setupUI(m_aircraft->groundVehicleType->currentText());
connect(m_aircraft->groundVehicleType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString)));
m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Turnable (car)"));
setupUI(m_aircraft->groundVehicleType->currentText());
}
ConfigGroundVehicleWidget::~ConfigGroundVehicleWidget()
@ -96,42 +94,32 @@ ConfigGroundVehicleWidget::~ConfigGroundVehicleWidget()
*/
void ConfigGroundVehicleWidget::setupUI(QString frameType)
{
m_aircraft->differentialSteeringMixBox->setHidden(true);
//STILL NEEDS WORK
// Setup the UI
m_aircraft->gvEngineChannelBox->setEnabled(false);
m_aircraft->gvEngineLabel->setEnabled(false);
m_aircraft->gvAileron1ChannelBox->setEnabled(false);
m_aircraft->gvAileron1Label->setEnabled(false);
m_aircraft->gvAileron2ChannelBox->setEnabled(false);
m_aircraft->gvAileron2Label->setEnabled(false);
m_aircraft->differentialSteeringSlider1->setEnabled(false);
m_aircraft->differentialSteeringSlider2->setEnabled(false);
if (frameType == "GroundVehicleDifferential" || frameType == "Differential (tank)") {
// Tank
setComboCurrentIndex(m_aircraft->groundVehicleType,
m_aircraft->groundVehicleType->findText("Differential (tank)"));
m_aircraft->gvMotor1ChannelBox->setEnabled(true);
m_aircraft->gvMotor1Label->setEnabled(true);
m_aircraft->gvMotor2ChannelBox->setEnabled(true);
m_aircraft->gvMotor2Label->setEnabled(true);
m_aircraft->gvMotor1Label->setText("Left motor");
m_aircraft->gvMotor2Label->setText("Right motor");
m_aircraft->gvSteering1ChannelBox->setEnabled(false);
m_aircraft->gvSteering1Label->setEnabled(false);
m_aircraft->gvSteering2ChannelBox->setEnabled(false);
m_aircraft->gvSteering2Label->setEnabled(false);
m_aircraft->gvSteering2Label->setText("Rear steering");
m_aircraft->differentialSteeringMixBox->setHidden(false);
m_aircraft->differentialSteeringSlider1->setEnabled(true);
m_aircraft->differentialSteeringSlider2->setEnabled(true);
m_aircraft->gvThrottleCurve1GroupBox->setTitle("Left throttle curve");
m_aircraft->gvThrottleCurve2GroupBox->setTitle("Right throttle curve");
@ -140,24 +128,16 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType)
// Motorcycle
setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Motorcycle"));
m_aircraft->gvMotor1ChannelBox->setEnabled(false);
m_aircraft->gvMotor1Label->setEnabled(false);
m_aircraft->gvMotor2ChannelBox->setEnabled(true);
m_aircraft->gvMotor2Label->setEnabled(true);
m_aircraft->gvMotor1Label->setText("Front motor");
m_aircraft->gvMotor2Label->setText("Rear motor");
m_aircraft->gvSteering1ChannelBox->setEnabled(true);
m_aircraft->gvSteering1Label->setEnabled(true);
m_aircraft->gvSteering2ChannelBox->setEnabled(true);
m_aircraft->gvSteering2Label->setEnabled(true);
m_aircraft->gvSteering2Label->setText("Balancing");
m_aircraft->differentialSteeringMixBox->setHidden(true);
m_aircraft->gvThrottleCurve1GroupBox->setTitle("Front throttle curve");
m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve");
} else {
@ -165,31 +145,40 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType)
setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Turnable (car)"));
m_aircraft->gvMotor1ChannelBox->setEnabled(true);
m_aircraft->gvMotor1Label->setEnabled(true);
m_aircraft->gvMotor2ChannelBox->setEnabled(true);
m_aircraft->gvMotor2Label->setEnabled(true);
m_aircraft->gvMotor1Label->setText("Front motor");
m_aircraft->gvMotor2Label->setText("Rear motor");
m_aircraft->gvSteering1ChannelBox->setEnabled(true);
m_aircraft->gvSteering1Label->setEnabled(true);
m_aircraft->gvSteering2ChannelBox->setEnabled(true);
m_aircraft->gvSteering2Label->setEnabled(true);
m_aircraft->differentialSteeringMixBox->setHidden(true);
m_aircraft->gvThrottleCurve1GroupBox->setTitle("Front throttle curve");
m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve");
}
}
void ConfigGroundVehicleWidget::enableControls(bool enable)
{
ConfigTaskWidget::enableControls(enable);
if(enable) {
setupUI(m_aircraft->groundVehicleType->currentText());
}
}
void ConfigGroundVehicleWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->groundVehicleThrottle1->getCurveWidget());
parent.addWidget(m_aircraft->groundVehicleThrottle1);
parent.addWidget(m_aircraft->groundVehicleThrottle2->getCurveWidget());
parent.addWidget(m_aircraft->groundVehicleThrottle2);
parent.addWidget(m_aircraft->groundVehicleType);
parent.addWidget(m_aircraft->gvEngineChannelBox);
parent.addWidget(m_aircraft->gvAileron1ChannelBox);
parent.addWidget(m_aircraft->gvAileron2ChannelBox);
parent.addWidget(m_aircraft->gvMotor1ChannelBox);
parent.addWidget(m_aircraft->gvMotor2ChannelBox);
parent.addWidget(m_aircraft->gvSteering1ChannelBox);
parent.addWidget(m_aircraft->gvSteering2ChannelBox);
}
void ConfigGroundVehicleWidget::resetActuators(GUIConfigDataUnion *configData)

View File

@ -54,6 +54,9 @@ public:
virtual void refreshWidgetsValues(QString frameType);
virtual QString updateConfigObjectsFromWidgets();
protected:
void enableControls(bool enable);
private:
Ui_GroundConfigWidget *m_aircraft;

View File

@ -122,6 +122,7 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) :
// Connect the multirotor motor reverse checkbox
connect(m_aircraft->MultirotorRevMixerCheckBox, SIGNAL(clicked(bool)), this, SLOT(reverseMultirotorMotor()));
updateEnableControls();
}
ConfigMultiRotorWidget::~ConfigMultiRotorWidget()
@ -134,6 +135,81 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
Q_ASSERT(m_aircraft);
Q_ASSERT(quad);
if (frameType == "Tri" || frameType == "Tricopter Y") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y"));
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
setYawMixLevel(50);
} else if (frameType == "QuadX" || frameType == "Quad X") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X"));
// init mixer levels
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50);
setYawMixLevel(50);
} else if (frameType == "QuadP" || frameType == "Quad +") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +"));
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
setYawMixLevel(50);
} else if (frameType == "Hexa" || frameType == "Hexacopter") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter"));
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(33);
setYawMixLevel(33);
} else if (frameType == "HexaX" || frameType == "Hexacopter X") {
setComboCurrentIndex(m_aircraft->multirotorFrameType,
m_aircraft->multirotorFrameType->findText("Hexacopter X"));
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(50);
setYawMixLevel(33);
} else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") {
setComboCurrentIndex(m_aircraft->multirotorFrameType,
m_aircraft->multirotorFrameType->findText("Hexacopter Y6"));
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(50);
setYawMixLevel(66);
} else if (frameType == "Octo" || frameType == "Octocopter") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter"));
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(33);
setYawMixLevel(25);
} else if (frameType == "OctoV" || frameType == "Octocopter V") {
setComboCurrentIndex(m_aircraft->multirotorFrameType,
m_aircraft->multirotorFrameType->findText("Octocopter V"));
m_aircraft->mrRollMixLevel->setValue(25);
m_aircraft->mrPitchMixLevel->setValue(25);
setYawMixLevel(25);
} else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +"));
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
setYawMixLevel(50);
} else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X"));
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50);
setYawMixLevel(50);
}
// Enable/Disable controls
setupEnabledControls(frameType);
// Draw the appropriate airframe
updateAirframe(frameType);
}
void ConfigMultiRotorWidget::setupEnabledControls(QString frameType)
{
// disable triyaw channel
m_aircraft->triYawChannelBox->setEnabled(false);
@ -148,109 +224,32 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
}
if (frameType == "Tri" || frameType == "Tricopter Y") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y"));
// Enable all necessary motor channel boxes...
enableComboBoxes(this, CHANNELBOXNAME, 3, true);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
setYawMixLevel(50);
m_aircraft->triYawChannelBox->setEnabled(true);
} else if (frameType == "QuadX" || frameType == "Quad X") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X"));
// Enable all necessary motor channel boxes...
enableComboBoxes(this, CHANNELBOXNAME, 4, true);
// init mixer levels
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50);
setYawMixLevel(50);
} else if (frameType == "QuadP" || frameType == "Quad +") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +"));
// Enable all necessary motor channel boxes...
enableComboBoxes(this, CHANNELBOXNAME, 4, true);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
setYawMixLevel(50);
} else if (frameType == "Hexa" || frameType == "Hexacopter") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter"));
// Enable all necessary motor channel boxes...
enableComboBoxes(this, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(33);
setYawMixLevel(33);
} else if (frameType == "HexaX" || frameType == "Hexacopter X") {
setComboCurrentIndex(m_aircraft->multirotorFrameType,
m_aircraft->multirotorFrameType->findText("Hexacopter X"));
// Enable all necessary motor channel boxes...
enableComboBoxes(this, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(50);
setYawMixLevel(33);
} else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") {
setComboCurrentIndex(m_aircraft->multirotorFrameType,
m_aircraft->multirotorFrameType->findText("Hexacopter Y6"));
// Enable all necessary motor channel boxes...
enableComboBoxes(this, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(50);
setYawMixLevel(66);
} else if (frameType == "Octo" || frameType == "Octocopter") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter"));
// Enable all necessary motor channel boxes
enableComboBoxes(this, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(33);
setYawMixLevel(25);
} else if (frameType == "OctoV" || frameType == "Octocopter V") {
setComboCurrentIndex(m_aircraft->multirotorFrameType,
m_aircraft->multirotorFrameType->findText("Octocopter V"));
// Enable all necessary motor channel boxes
enableComboBoxes(this, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(25);
m_aircraft->mrPitchMixLevel->setValue(25);
setYawMixLevel(25);
} else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +"));
// Enable all necessary motor channel boxes
enableComboBoxes(this, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
setYawMixLevel(50);
} else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") {
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X"));
// Enable all necessary motor channel boxes
enableComboBoxes(this, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50);
setYawMixLevel(50);
}
// Draw the appropriate airframe
updateAirframe(frameType);
}
void ConfigMultiRotorWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->multiThrottleCurve->getCurveWidget());
parent.addWidget(m_aircraft->multiThrottleCurve);
parent.addWidget(m_aircraft->multirotorFrameType);
parent.addWidget(m_aircraft->multiMotorChannelBox1);
parent.addWidget(m_aircraft->multiMotorChannelBox2);
@ -264,6 +263,7 @@ void ConfigMultiRotorWidget::registerWidgets(ConfigTaskWidget &parent) {
parent.addWidget(m_aircraft->mrRollMixLevel);
parent.addWidget(m_aircraft->mrYawMixLevel);
parent.addWidget(m_aircraft->triYawChannelBox);
parent.addWidget(m_aircraft->MultirotorRevMixerCheckBox);
}
void ConfigMultiRotorWidget::resetActuators(GUIConfigDataUnion *configData)
@ -1048,3 +1048,11 @@ void ConfigMultiRotorWidget::resizeEvent(QResizeEvent *event)
Q_UNUSED(event);
m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio);
}
void ConfigMultiRotorWidget::enableControls(bool enable)
{
ConfigTaskWidget::enableControls(enable);
if(enable) {
setupEnabledControls(m_aircraft->multirotorFrameType->currentText());
}
}

View File

@ -58,6 +58,7 @@ public:
protected:
void showEvent(QShowEvent *event);
void resizeEvent(QResizeEvent *event);
void enableControls(bool enable);
private:
Ui_MultiRotorConfigWidget *m_aircraft;
@ -77,6 +78,7 @@ private:
void setYawMixLevel(int);
void updateAirframe(QString multiRotorType);
void setupEnabledControls(QString multiRotorType);
private slots:
virtual void setupUI(QString airframeType);

View File

@ -43,24 +43,24 @@
ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_camerastabilization = new Ui_CameraStabilizationWidget();
m_camerastabilization->setupUi(this);
ui = new Ui_CameraStabilizationWidget();
ui->setupUi(this);
addApplySaveButtons(m_camerastabilization->camerastabilizationSaveRAM,m_camerastabilization->camerastabilizationSaveSD);
addApplySaveButtons(ui->camerastabilizationSaveRAM,ui->camerastabilizationSaveSD);
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_camerastabilization->camerastabilizationSaveRAM->setVisible(false);
ui->camerastabilizationSaveRAM->setVisible(false);
// These widgets don't have direct relation to UAVObjects
// and need special processing
QComboBox *outputs[] = {
m_camerastabilization->rollChannel,
m_camerastabilization->pitchChannel,
m_camerastabilization->yawChannel,
ui->rollChannel,
ui->pitchChannel,
ui->yawChannel,
};
const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]);
@ -78,10 +78,10 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent
autoLoadWidgets();
// Add some widgets to track their UI dirty state and handle smartsave
addWidget(m_camerastabilization->enableCameraStabilization);
addWidget(m_camerastabilization->rollChannel);
addWidget(m_camerastabilization->pitchChannel);
addWidget(m_camerastabilization->yawChannel);
addWidget(ui->enableCameraStabilization);
addWidget(ui->rollChannel);
addWidget(ui->pitchChannel);
addWidget(ui->yawChannel);
// Add some UAVObjects to monitor their changes in addition to autoloaded ones.
// Note also that we want to reload some UAVObjects by "Reload" button and have
@ -97,6 +97,7 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent
connect(this, SIGNAL(defaultRequested(int)), this, SLOT(defaultRequestedSlot(int)));
disableMouseWheelEvents();
updateEnableControls();
}
ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget()
@ -120,7 +121,7 @@ void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj)
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
HwSettings::DataFields hwSettingsData = hwSettings->getData();
m_camerastabilization->enableCameraStabilization->setChecked(
ui->enableCameraStabilization->setChecked(
hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED);
// Load mixer outputs which are mapped to camera controls
@ -144,9 +145,9 @@ void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj)
const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]);
QComboBox *outputs[] = {
m_camerastabilization->rollChannel,
m_camerastabilization->pitchChannel,
m_camerastabilization->yawChannel
ui->rollChannel,
ui->pitchChannel,
ui->yawChannel
};
const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]);
@ -175,7 +176,7 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets()
// Save state of the module enable checkbox first.
// Do not use setData() member on whole object, if possible, since it triggers
// unnessesary UAVObect update.
quint8 enableModule = m_camerastabilization->enableCameraStabilization->isChecked() ?
quint8 enableModule = ui->enableCameraStabilization->isChecked() ?
HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED;
HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_CAMERASTAB, enableModule);
@ -202,13 +203,13 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets()
const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]);
QComboBox *outputs[] = {
m_camerastabilization->rollChannel,
m_camerastabilization->pitchChannel,
m_camerastabilization->yawChannel
ui->rollChannel,
ui->pitchChannel,
ui->yawChannel
};
const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]);
m_camerastabilization->message->setText("");
ui->message->setText("");
bool widgetUpdated;
do {
widgetUpdated = false;
@ -223,7 +224,7 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets()
// If the mixer channel already mapped to something, it should not be
// used for camera output, we reset it to none
outputs[i]->setCurrentIndex(0);
m_camerastabilization->message->setText("One of the channels is already assigned, reverted to none");
ui->message->setText("One of the channels is already assigned, reverted to none");
// Loop again or we may have inconsistent widget and UAVObject
widgetUpdated = true;
@ -270,9 +271,9 @@ void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group)
// For outputs we set them all to none, so don't use any UAVObject to get defaults
QComboBox *outputs[] = {
m_camerastabilization->rollChannel,
m_camerastabilization->pitchChannel,
m_camerastabilization->yawChannel,
ui->rollChannel,
ui->pitchChannel,
ui->yawChannel,
};
const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]);
@ -280,8 +281,3 @@ void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group)
outputs[i]->setCurrentIndex(0);
}
}
/**
@}
@}
*/

View File

@ -43,7 +43,7 @@ public:
~ConfigCameraStabilizationWidget();
private:
Ui_CameraStabilizationWidget *m_camerastabilization;
Ui_CameraStabilizationWidget *ui;
void refreshWidgetsValues(UAVObject *obj);
void updateObjectsFromWidgets();

View File

@ -216,15 +216,9 @@ void ConfigCCAttitudeWidget::setAccelFiltering(bool active)
void ConfigCCAttitudeWidget::enableControls(bool enable)
{
if(ui->zeroBias) {
ui->zeroBias->setEnabled(enable);
}
if(ui->zeroGyroBiasOnArming) {
ui->zeroGyroBiasOnArming->setEnabled(enable);
}
if(ui->accelTauSpinbox) {
ui->accelTauSpinbox->setEnabled(enable);
}
ConfigTaskWidget::enableControls(enable);
}

View File

@ -49,8 +49,6 @@
#include <QtGui/QVBoxLayout>
#include <QtGui/QPushButton>
ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
{
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
@ -94,7 +92,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new DefaultAttitudeWidget(this);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS"));
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon();
icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off);
@ -106,7 +104,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigCameraStabilizationWidget(this);
ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Camera Stab"));
ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Gimbal"));
icon = new QIcon();
icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off);
@ -164,15 +162,17 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event)
QWidget::resizeEvent(event);
}
void ConfigGadgetWidget::onAutopilotDisconnect() {
void ConfigGadgetWidget::onAutopilotDisconnect()
{
int selectedIndex = ftw->currentIndex();
QIcon *icon = new QIcon();
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new DefaultAttitudeWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS"));
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
@ -186,8 +186,8 @@ void ConfigGadgetWidget::onAutopilotDisconnect() {
emit autopilotDisconnected();
}
void ConfigGadgetWidget::onAutopilotConnect() {
void ConfigGadgetWidget::onAutopilotConnect()
{
qDebug() << "ConfigGadgetWidget onAutopilotConnect";
// First of all, check what Board type we are talking to, and
// if necessary, remove/add tabs in the config gadget:
@ -204,7 +204,7 @@ void ConfigGadgetWidget::onAutopilotConnect() {
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigCCAttitudeWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("CopterControl"));
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
@ -212,7 +212,6 @@ void ConfigGadgetWidget::onAutopilotConnect() {
qwd = new ConfigCCHWWidget(this);
ftw->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
} else if ((board & 0xff00) == 0x0900) {
// Revolution family
@ -221,7 +220,7 @@ void ConfigGadgetWidget::onAutopilotConnect() {
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigRevoWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Revolution"));
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
@ -229,13 +228,13 @@ void ConfigGadgetWidget::onAutopilotConnect() {
qwd = new ConfigRevoHWWidget(this);
ftw->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
} else {
// Unknown board
qDebug() << "Unknown board " << board;
}
ftw->setCurrentIndex(selectedIndex);
}
emit autopilotConnected();
}
@ -247,8 +246,7 @@ void ConfigGadgetWidget::tabAboutToChange(int i, bool * proceed)
if (!wid) {
return;
}
if(wid->isDirty())
{
if (wid->isDirty()) {
int ans = QMessageBox::warning(this, tr("Unsaved changes"), tr("The tab you are leaving has unsaved changes,"
"if you proceed they will be lost."
"Do you still want to proceed?"), QMessageBox::Yes, QMessageBox::No);
@ -267,8 +265,7 @@ void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *)
{
// Restart the disconnection timer.
oplinkTimeout->start(5000);
if (!oplinkConnected)
{
if (!oplinkConnected) {
qDebug() << "ConfigGadgetWidget onOPLinkConnect";
QIcon *icon = new QIcon();
@ -281,7 +278,8 @@ void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *)
}
}
void ConfigGadgetWidget::onOPLinkDisconnect() {
void ConfigGadgetWidget::onOPLinkDisconnect()
{
qDebug() << "ConfigGadgetWidget onOPLinkDisconnect";
oplinkTimeout->stop();
ftw->removeTab(ConfigGadgetWidget::oplink);

View File

@ -63,17 +63,17 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager());
flightStatusObj = FlightStatus::GetInstance(getObjectManager());
receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager());
m_config = new Ui_InputWidget();
m_config->setupUi(this);
ui = new Ui_InputWidget();
ui->setupUi(this);
addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD);
addApplySaveButtons(ui->saveRCInputToRAM,ui->saveRCInputToSD);
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_config->saveRCInputToRAM->setVisible(false);
ui->saveRCInputToRAM->setVisible(false);
addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD);
addApplySaveButtons(ui->saveRCInputToRAM,ui->saveRCInputToSD);
//Generate the rows of buttons in the input channel form GUI
unsigned int index=0;
@ -82,13 +82,16 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
{
Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM);
inputChannelForm * inpForm=new inputChannelForm(this,index==0);
m_config->channelSettings->layout()->addWidget(inpForm); //Add the row to the UI
ui->channelSettings->layout()->addWidget(inpForm); //Add the row to the UI
inpForm->setName(name);
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inpForm->ui->channelGroup,index);
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inpForm->ui->channelNumber,index);
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inpForm->ui->channelMin,index);
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inpForm->ui->channelNeutral,index);
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inpForm->ui->channelMax,index);
addWidget(inpForm->ui->channelNumberDropdown);
addWidget(inpForm->ui->channelRev);
addWidget(inpForm->ui->channelResponseTime);
// Input filter response time fields supported for some channels only
switch (index) {
@ -114,51 +117,53 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
++index;
}
addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", m_config->deadband, 0, 0.01f);
addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", ui->deadband, 0, 0.01f);
connect(m_config->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard()));
connect(m_config->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int)));
connect(m_config->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool)));
connect(ui->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard()));
connect(ui->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int)));
connect(ui->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool)));
connect(m_config->wzNext,SIGNAL(clicked()),this,SLOT(wzNext()));
connect(m_config->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel()));
connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack()));
connect(ui->wzNext,SIGNAL(clicked()),this,SLOT(wzNext()));
connect(ui->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel()));
connect(ui->wzBack,SIGNAL(clicked()),this,SLOT(wzBack()));
m_config->stackedWidget->setCurrentIndex(0);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos1, 0, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos2, 1, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos3, 2, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos4, 3, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos5, 4, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos6, 5, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", m_config->fmsPosNum);
ui->stackedWidget->setCurrentIndex(0);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos1, 0, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos2, 1, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos3, 2, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos4, 3, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos5, 4, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos6, 5, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", ui->fmsPosNum);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl);
addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000);
addUAVObjectToWidgetRelation("ManualControlSettings","Arming",ui->armControl);
addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",ui->armTimeout,0,1000);
connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider()));
connect( ManualControlSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(updatePositionSlider()));
enableControls(false);
addWidget(ui->configurationWizard);
addWidget(ui->runCalibration);
populateWidgets();
refreshWidgetsValues();
// Connect the help button
connect(m_config->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
connect(ui->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
m_config->graphicsView->setScene(new QGraphicsScene(this));
m_config->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
ui->graphicsView->setScene(new QGraphicsScene(this));
ui->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
m_renderer = new QSvgRenderer();
QGraphicsScene *l_scene = m_config->graphicsView->scene();
m_config->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor()));
QGraphicsScene *l_scene = ui->graphicsView->scene();
ui->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor()));
if (QFile::exists(":/configgadget/images/TX2.svg") && m_renderer->load(QString(":/configgadget/images/TX2.svg")) && m_renderer->isValid())
{
l_scene->clear(); // Deletes all items contained in the scene as well.
@ -271,7 +276,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
m_txAccess2Orig.translate(orig.x(),orig.y());
m_txAccess2->setTransform(m_txAccess2Orig,true);
}
m_config->graphicsView->fitInView(m_txMainBody, Qt::KeepAspectRatio );
ui->graphicsView->fitInView(m_txMainBody, Qt::KeepAspectRatio );
animate=new QTimer(this);
connect(animate,SIGNAL(timeout()),this,SLOT(moveTxControls()));
@ -293,7 +298,10 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
ManualControlSettings::CHANNELGROUPS_ACCESSORY0 <<
ManualControlSettings::CHANNELGROUPS_ACCESSORY1 <<
ManualControlSettings::CHANNELGROUPS_ACCESSORY2;
updateEnableControls();
}
void ConfigInputWidget::resetTxControls()
{
@ -312,10 +320,19 @@ ConfigInputWidget::~ConfigInputWidget()
}
void ConfigInputWidget::enableControls(bool enable)
{
ConfigTaskWidget::enableControls(enable);
if(enable) {
updatePositionSlider();
}
}
void ConfigInputWidget::resizeEvent(QResizeEvent *event)
{
QWidget::resizeEvent(event);
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio );
ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio );
}
void ConfigInputWidget::openHelp()
@ -335,8 +352,8 @@ void ConfigInputWidget::goToWizard()
msgBox.exec();
// Set correct tab visible before starting wizard.
if(m_config->tabWidget->currentIndex() != 0) {
m_config->tabWidget->setCurrentIndex(0);
if(ui->tabWidget->currentIndex() != 0) {
ui->tabWidget->setCurrentIndex(0);
}
// Stash current manual settings data in case the wizard is
@ -351,27 +368,27 @@ void ConfigInputWidget::goToWizard()
// start the wizard
wizardSetUpStep(wizardWelcome);
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio);
ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio);
}
void ConfigInputWidget::disableWizardButton(int value)
{
if(value!=0)
m_config->groupBox_3->setVisible(false);
ui->groupBox_3->setVisible(false);
else
m_config->groupBox_3->setVisible(true);
ui->groupBox_3->setVisible(true);
}
void ConfigInputWidget::wzCancel()
{
dimOtherControls(false);
manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata());
m_config->stackedWidget->setCurrentIndex(0);
ui->stackedWidget->setCurrentIndex(0);
if(wizardStep != wizardNone)
wizardTearDownStep(wizardStep);
wizardStep=wizardNone;
m_config->stackedWidget->setCurrentIndex(0);
ui->stackedWidget->setCurrentIndex(0);
// Load settings back from beginning of wizard
manualSettingsObj->setData(previousManualSettingsData);
@ -433,8 +450,8 @@ void ConfigInputWidget::wzNext()
}
manualSettingsObj->setData(manualSettingsData);
// move to Arming Settings tab
m_config->stackedWidget->setCurrentIndex(0);
m_config->tabWidget->setCurrentIndex(2);
ui->stackedWidget->setCurrentIndex(0);
ui->tabWidget->setCurrentIndex(2);
break;
default:
Q_ASSERT(0);
@ -481,7 +498,7 @@ void ConfigInputWidget::wzBack()
void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
{
m_config->wzText2->clear();
ui->wzText2->clear();
switch(step) {
case wizardWelcome:
@ -491,22 +508,22 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
delete wd;
}
extraWidgets.clear();
m_config->graphicsView->setVisible(false);
ui->graphicsView->setVisible(false);
setTxMovement(nothing);
m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\n\n"
ui->wzText->setText(tr("Welcome to the inputs configuration wizard.\n\n"
"Please follow the instructions on the screen and only move your controls when asked to.\n"
"Make sure you already configured your hardware settings on the proper tab and restarted your board.\n\n"
"You can press 'back' at any time to return to the previous screen or press 'Cancel' to quit the wizard.\n"));
m_config->stackedWidget->setCurrentIndex(1);
m_config->wzBack->setEnabled(false);
ui->stackedWidget->setCurrentIndex(1);
ui->wzBack->setEnabled(false);
break;
case wizardChooseType:
{
m_config->graphicsView->setVisible(true);
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio);
ui->graphicsView->setVisible(true);
ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio);
setTxMovement(nothing);
m_config->wzText->setText(tr("Please choose your transmitter type:"));
m_config->wzBack->setEnabled(true);
ui->wzText->setText(tr("Please choose your transmitter type:"));
ui->wzBack->setEnabled(true);
QRadioButton * typeAcro=new QRadioButton(tr("Acro: normal transmitter for fixed-wing or quad"),this);
QRadioButton * typeHeli=new QRadioButton(tr("Helicopter: has collective pitch and throttle input"),this);
if (transmitterType == heli) {
@ -515,20 +532,20 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
else {
typeAcro->setChecked(true);
}
m_config->wzText2->setText(tr("If selecting the Helicopter option, please engage throttle hold now."));
ui->wzText2->setText(tr("If selecting the Helicopter option, please engage throttle hold now."));
extraWidgets.clear();
extraWidgets.append(typeAcro);
extraWidgets.append(typeHeli);
m_config->radioButtonsLayout->layout()->addWidget(typeAcro);
m_config->radioButtonsLayout->layout()->addWidget(typeHeli);
ui->radioButtonsLayout->layout()->addWidget(typeAcro);
ui->radioButtonsLayout->layout()->addWidget(typeHeli);
}
break;
case wizardChooseMode:
{
m_config->wzBack->setEnabled(true);
ui->wzBack->setEnabled(true);
extraWidgets.clear();
m_config->wzText->setText(tr("Please choose your transmitter mode:"));
ui->wzText->setText(tr("Please choose your transmitter mode:"));
for (int i = 0; i <= mode4; ++i) {
QString label;
txMode mode = static_cast<txMode>(i);
@ -548,14 +565,14 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
case mode4: label = tr("Mode 4: Throttle and Ailerons on the left, Elevator and Rudder on the right"); break;
default: Q_ASSERT(0); break;
}
m_config->wzText2->setText(tr("For a Quad: Elevator is Pitch, Ailerons are Roll, and Rudder is Yaw."));
ui->wzText2->setText(tr("For a Quad: Elevator is Pitch, Ailerons are Roll, and Rudder is Yaw."));
}
QRadioButton * modeButton = new QRadioButton(label, this);
if (transmitterMode == mode) {
modeButton->setChecked(true);
}
extraWidgets.append(modeButton);
m_config->radioButtonsLayout->layout()->addWidget(modeButton);
ui->radioButtonsLayout->layout()->addWidget(modeButton);
}
}
break;
@ -565,11 +582,11 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
nextChannel();
manualSettingsData=manualSettingsObj->getData();
connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
m_config->wzNext->setEnabled(false);
ui->wzNext->setEnabled(false);
break;
case wizardIdentifyCenter:
setTxMovement(centerAll);
m_config->wzText->setText(QString(tr("Please center all controls and trims and press Next when ready.\n\n"
ui->wzText->setText(QString(tr("Please center all controls and trims and press Next when ready.\n\n"
"If your FlightMode switch has only two positions, leave it in either position.")));
break;
case wizardIdentifyLimits:
@ -578,7 +595,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1);
accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2);
setTxMovement(nothing);
m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions.\n\nPress Next when ready.")));
ui->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions.\n\nPress Next when ready.")));
fastMdata();
manualSettingsData=manualSettingsObj->getData();
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
@ -612,13 +629,13 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
QCheckBox * cb=new QCheckBox(name,this);
// Make sure checked status matches current one
cb->setChecked(manualSettingsData.ChannelMax[index] < manualSettingsData.ChannelMin[index]);
dynamic_cast<QGridLayout*>(m_config->checkBoxesLayout->layout())->addWidget(cb, extraWidgets.size()/4, extraWidgets.size()%4);
dynamic_cast<QGridLayout*>(ui->checkBoxesLayout->layout())->addWidget(cb, extraWidgets.size()/4, extraWidgets.size()%4);
extraWidgets.append(cb);
connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
}
}
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
m_config->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement. Press Next when ready.")));
ui->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement. Press Next when ready.")));
fastMdata();
break;
case wizardFinish:
@ -626,7 +643,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n\n"
ui->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n\n"
"IMPORTANT: These new settings have not been saved to the board yet. After pressing Next you will go to the Arming Settings "
"tab where you can set your desired arming sequence and save the configuration.")));
fastMdata();
@ -666,7 +683,7 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
break;
case wizardIdentifySticks:
disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
m_config->wzNext->setEnabled(true);
ui->wzNext->setEnabled(true);
setTxMovement(nothing);
break;
case wizardIdentifyCenter:
@ -742,21 +759,21 @@ void ConfigInputWidget::restoreMdata()
void ConfigInputWidget::setChannel(int newChan)
{
if(newChan == ManualControlSettings::CHANNELGROUPS_COLLECTIVE)
m_config->wzText->setText(QString(tr("Please enable throttle hold mode.\n\nMove the Collective Pitch stick.")));
ui->wzText->setText(QString(tr("Please enable throttle hold mode.\n\nMove the Collective Pitch stick.")));
else if (newChan == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE)
m_config->wzText->setText(QString(tr("Please toggle the Flight Mode switch.\n\nFor switches you may have to repeat this rapidly.")));
ui->wzText->setText(QString(tr("Please toggle the Flight Mode switch.\n\nFor switches you may have to repeat this rapidly.")));
else if((transmitterType == heli) && (newChan == ManualControlSettings::CHANNELGROUPS_THROTTLE))
m_config->wzText->setText(QString(tr("Please disable throttle hold mode.\n\nMove the Throttle stick.")));
ui->wzText->setText(QString(tr("Please disable throttle hold mode.\n\nMove the Throttle stick.")));
else
m_config->wzText->setText(QString(tr("Please move each control one at a time according to the instructions and picture below.\n\n"
ui->wzText->setText(QString(tr("Please move each control one at a time according to the instructions and picture below.\n\n"
"Move the %1 stick.")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan)));
if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory") ||
manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) {
m_config->wzNext->setEnabled(true);
m_config->wzText->setText(m_config->wzText->text() + tr(" Alternatively, click Next to skip this channel."));
ui->wzNext->setEnabled(true);
ui->wzText->setText(ui->wzText->text() + tr(" Alternatively, click Next to skip this channel."));
} else
m_config->wzNext->setEnabled(false);
ui->wzNext->setEnabled(false);
setMoveFromCommand(newChan);
@ -1249,15 +1266,6 @@ void ConfigInputWidget::dimOtherControls(bool value)
m_txFlightMode->setOpacity(opac);
}
void ConfigInputWidget::enableControls(bool enable)
{
m_config->configurationWizard->setEnabled(enable);
m_config->runCalibration->setEnabled(enable);
ConfigTaskWidget::enableControls(enable);
}
void ConfigInputWidget::invertControls()
{
manualSettingsData=manualSettingsObj->getData();
@ -1318,7 +1326,7 @@ void ConfigInputWidget::moveFMSlider()
uint8_t pos = ((int16_t)(valueScaled * 256) + 256) * manualSettingsDataPriv.FlightModeNumber >> 9;
if (pos >= manualSettingsDataPriv.FlightModeNumber)
pos = manualSettingsDataPriv.FlightModeNumber - 1;
m_config->fmsSlider->setValue(pos);
ui->fmsSlider->setValue(pos);
}
void ConfigInputWidget::updatePositionSlider()
@ -1328,22 +1336,22 @@ void ConfigInputWidget::updatePositionSlider()
switch(manualSettingsDataPriv.FlightModeNumber) {
default:
case 6:
m_config->fmsModePos6->setEnabled(true);
ui->fmsModePos6->setEnabled(true);
// pass through
case 5:
m_config->fmsModePos5->setEnabled(true);
ui->fmsModePos5->setEnabled(true);
// pass through
case 4:
m_config->fmsModePos4->setEnabled(true);
ui->fmsModePos4->setEnabled(true);
// pass through
case 3:
m_config->fmsModePos3->setEnabled(true);
ui->fmsModePos3->setEnabled(true);
// pass through
case 2:
m_config->fmsModePos2->setEnabled(true);
ui->fmsModePos2->setEnabled(true);
// pass through
case 1:
m_config->fmsModePos1->setEnabled(true);
ui->fmsModePos1->setEnabled(true);
// pass through
case 0:
break;
@ -1351,22 +1359,22 @@ void ConfigInputWidget::updatePositionSlider()
switch(manualSettingsDataPriv.FlightModeNumber) {
case 0:
m_config->fmsModePos1->setEnabled(false);
ui->fmsModePos1->setEnabled(false);
// pass through
case 1:
m_config->fmsModePos2->setEnabled(false);
ui->fmsModePos2->setEnabled(false);
// pass through
case 2:
m_config->fmsModePos3->setEnabled(false);
ui->fmsModePos3->setEnabled(false);
// pass through
case 3:
m_config->fmsModePos4->setEnabled(false);
ui->fmsModePos4->setEnabled(false);
// pass through
case 4:
m_config->fmsModePos5->setEnabled(false);
ui->fmsModePos5->setEnabled(false);
// pass through
case 5:
m_config->fmsModePos6->setEnabled(false);
ui->fmsModePos6->setEnabled(false);
// pass through
case 6:
default:
@ -1395,7 +1403,7 @@ void ConfigInputWidget::updateCalibration()
void ConfigInputWidget::simpleCalibration(bool enable)
{
if (enable) {
m_config->configurationWizard->setEnabled(false);
ui->configurationWizard->setEnabled(false);
QMessageBox msgBox;
msgBox.setText(tr("Arming Settings are now set to 'Always Disarmed' for your safety."));
@ -1421,7 +1429,7 @@ void ConfigInputWidget::simpleCalibration(bool enable)
connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration()));
} else {
m_config->configurationWizard->setEnabled(true);
ui->configurationWizard->setEnabled(true);
manualCommandData = manualCommandObj->getData();
manualSettingsData = manualSettingsObj->getData();

View File

@ -61,6 +61,7 @@ public:
enum txMovementType{vertical,horizontal,jump,mix};
enum txType {acro, heli};
void startInputWizard() { goToWizard(); }
void enableControls(bool enable);
private:
bool growing;
@ -68,7 +69,7 @@ private:
txMovements currentMovement;
int movePos;
void setTxMovement(txMovements movement);
Ui_InputWidget *m_config;
Ui_InputWidget *ui;
wizardSteps wizardStep;
QList<QPointer<QWidget> > extraWidgets;
txMode transmitterMode;
@ -166,7 +167,6 @@ private slots:
protected:
void resizeEvent(QResizeEvent *event);
virtual void enableControls(bool enable);
};
#endif

View File

@ -51,46 +51,51 @@
ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false)
{
m_config = new Ui_OutputWidget();
m_config->setupUi(this);
ui = new Ui_OutputWidget();
ui->setupUi(this);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode()) {
m_config->saveRCOutputToRAM->setVisible(false);
ui->saveRCOutputToRAM->setVisible(false);
}
UAVSettingsImportExportFactory *importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
connect(importexportplugin, SIGNAL(importAboutToBegin()), this, SLOT(stopTests()));
// NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10.
// Register for ActuatorSettings changes:
for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
OutputChannelForm *form = new OutputChannelForm(i, this, i == 0);
connect(m_config->channelOutTest, SIGNAL(toggled(bool)), form, SLOT(enableChannelTest(bool)));
connect(form, SIGNAL(channelChanged(int,int)), this, SLOT(sendChannelTest(int,int)));
m_config->channelLayout->addWidget(form);
}
connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool)));
connect(ui->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool)));
// Configure the task widget
// Connect the help button
connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
connect(ui->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
addApplySaveButtons(ui->saveRCOutputToRAM, ui->saveRCOutputToSD);
// Track the ActuatorSettings object
addUAVObject("ActuatorSettings");
// NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10.
// Register for ActuatorSettings changes:
for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
OutputChannelForm *form = new OutputChannelForm(i, this, i == 0);
connect(ui->channelOutTest, SIGNAL(toggled(bool)), form, SLOT(enableChannelTest(bool)));
connect(form, SIGNAL(channelChanged(int,int)), this, SLOT(sendChannelTest(int,int)));
ui->channelLayout->addWidget(form);
addWidget(form->ui.actuatorMin);
addWidget(form->ui.actuatorNeutral);
addWidget(form->ui.actuatorMax);
addWidget(form->ui.actuatorRev);
addWidget(form->ui.actuatorLink);
}
// Associate the buttons with their UAVO fields
addWidget(m_config->cb_outputRate6);
addWidget(m_config->cb_outputRate5);
addWidget(m_config->cb_outputRate4);
addWidget(m_config->cb_outputRate3);
addWidget(m_config->cb_outputRate2);
addWidget(m_config->cb_outputRate1);
addWidget(m_config->spinningArmed);
addWidget(ui->cb_outputRate6);
addWidget(ui->cb_outputRate5);
addWidget(ui->cb_outputRate4);
addWidget(ui->cb_outputRate3);
addWidget(ui->cb_outputRate2);
addWidget(ui->cb_outputRate1);
addWidget(ui->spinningArmed);
disconnect(this, SLOT(refreshWidgetsValues(UAVObject*)));
@ -102,15 +107,16 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
connect(obj,SIGNAL(objectUpdated(UAVObject*)), this, SLOT(disableIfNotMe(UAVObject*)));
refreshWidgetsValues();
updateEnableControls();
}
void ConfigOutputWidget::enableControls(bool enable)
{
ConfigTaskWidget::enableControls(enable);
if(!enable) {
m_config->channelOutTest->setChecked(false);
ui->channelOutTest->setChecked(false);
}
m_config->channelOutTest->setEnabled(enable);
ui->channelOutTest->setEnabled(enable);
}
ConfigOutputWidget::~ConfigOutputWidget()
@ -136,7 +142,7 @@ void ConfigOutputWidget::runChannelTests(bool state)
// Unfortunately must cache this since callback will reoccur
accInitialData = ActuatorCommand::GetInstance(getObjectManager())->getMetadata();
m_config->channelOutTest->setChecked(false);
ui->channelOutTest->setChecked(false);
return;
}
@ -149,7 +155,7 @@ void ConfigOutputWidget::runChannelTests(bool state)
if(retval != QMessageBox::Yes) {
state = false;
qDebug() << "Cancelled";
m_config->channelOutTest->setChecked(false);
ui->channelOutTest->setChecked(false);
return;
}
}
@ -209,7 +215,7 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str)
*/
void ConfigOutputWidget::sendChannelTest(int index, int value)
{
if (!m_config->channelOutTest->isChecked()) {
if (!ui->channelOutTest->isChecked()) {
return;
}
@ -260,47 +266,47 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj)
}
// Get the SpinWhileArmed setting
m_config->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE);
ui->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE);
// Setup output rates for all banks
if(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])) == -1) {
m_config->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]));
if(ui->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])) == -1) {
ui->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]));
}
if(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])) == -1) {
m_config->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]));
if(ui->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])) == -1) {
ui->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]));
}
if(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]) )== -1) {
m_config->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]));
if(ui->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]) )== -1) {
ui->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]));
}
if(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])) == -1) {
m_config->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]));
if(ui->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])) == -1) {
ui->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]));
}
if(m_config->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])) == -1) {
m_config->cb_outputRate5->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[4]));
if(ui->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])) == -1) {
ui->cb_outputRate5->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[4]));
}
if(m_config->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])) == -1) {
m_config->cb_outputRate6->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[5]));
if(ui->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])) == -1) {
ui->cb_outputRate6->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[5]));
}
m_config->cb_outputRate1->setCurrentIndex(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])));
m_config->cb_outputRate2->setCurrentIndex(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])));
m_config->cb_outputRate3->setCurrentIndex(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])));
m_config->cb_outputRate4->setCurrentIndex(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])));
m_config->cb_outputRate5->setCurrentIndex(m_config->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])));
m_config->cb_outputRate6->setCurrentIndex(m_config->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])));
ui->cb_outputRate1->setCurrentIndex(ui->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])));
ui->cb_outputRate2->setCurrentIndex(ui->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])));
ui->cb_outputRate3->setCurrentIndex(ui->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])));
ui->cb_outputRate4->setCurrentIndex(ui->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])));
ui->cb_outputRate5->setCurrentIndex(ui->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])));
ui->cb_outputRate6->setCurrentIndex(ui->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])));
// Reset to all disabled
m_config->chBank1->setText("-");
m_config->chBank2->setText("-");
m_config->chBank3->setText("-");
m_config->chBank4->setText("-");
m_config->chBank5->setText("-");
m_config->chBank6->setText("-");
m_config->cb_outputRate1->setEnabled(false);
m_config->cb_outputRate2->setEnabled(false);
m_config->cb_outputRate3->setEnabled(false);
m_config->cb_outputRate4->setEnabled(false);
m_config->cb_outputRate5->setEnabled(false);
m_config->cb_outputRate6->setEnabled(false);
ui->chBank1->setText("-");
ui->chBank2->setText("-");
ui->chBank3->setText("-");
ui->chBank4->setText("-");
ui->chBank5->setText("-");
ui->chBank6->setText("-");
ui->cb_outputRate1->setEnabled(false);
ui->cb_outputRate2->setEnabled(false);
ui->cb_outputRate3->setEnabled(false);
ui->cb_outputRate4->setEnabled(false);
ui->cb_outputRate5->setEnabled(false);
ui->cb_outputRate6->setEnabled(false);
// Get connected board model
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
@ -313,29 +319,29 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj)
// Setup labels and combos for banks according to board type
if ((board & 0xff00) == 0x0400) {
// Coptercontrol family of boards 4 timer banks
m_config->chBank1->setText("1-3");
m_config->chBank2->setText("4");
m_config->chBank3->setText("5,7-8");
m_config->chBank4->setText("6,9-10");
m_config->cb_outputRate1->setEnabled(true);
m_config->cb_outputRate2->setEnabled(true);
m_config->cb_outputRate3->setEnabled(true);
m_config->cb_outputRate4->setEnabled(true);
ui->chBank1->setText("1-3");
ui->chBank2->setText("4");
ui->chBank3->setText("5,7-8");
ui->chBank4->setText("6,9-10");
ui->cb_outputRate1->setEnabled(true);
ui->cb_outputRate2->setEnabled(true);
ui->cb_outputRate3->setEnabled(true);
ui->cb_outputRate4->setEnabled(true);
}
else if((board & 0xff00) == 0x0900) {
// Revolution family of boards 6 timer banks
m_config->chBank1->setText("1-2");
m_config->chBank2->setText("3");
m_config->chBank3->setText("4");
m_config->chBank4->setText("5-6");
m_config->chBank5->setText("7-8");
m_config->chBank6->setText("9-10");
m_config->cb_outputRate1->setEnabled(true);
m_config->cb_outputRate2->setEnabled(true);
m_config->cb_outputRate3->setEnabled(true);
m_config->cb_outputRate4->setEnabled(true);
m_config->cb_outputRate5->setEnabled(true);
m_config->cb_outputRate6->setEnabled(true);
ui->chBank1->setText("1-2");
ui->chBank2->setText("3");
ui->chBank3->setText("4");
ui->chBank4->setText("5-6");
ui->chBank5->setText("7-8");
ui->chBank6->setText("9-10");
ui->cb_outputRate1->setEnabled(true);
ui->cb_outputRate2->setEnabled(true);
ui->cb_outputRate3->setEnabled(true);
ui->cb_outputRate4->setEnabled(true);
ui->cb_outputRate5->setEnabled(true);
ui->cb_outputRate6->setEnabled(true);
}
}
@ -371,14 +377,14 @@ void ConfigOutputWidget::updateObjectsFromWidgets()
}
// Set update rates
actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[4] = m_config->cb_outputRate5->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[5] = m_config->cb_outputRate6->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[0] = ui->cb_outputRate1->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[1] = ui->cb_outputRate2->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[2] = ui->cb_outputRate3->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[3] = ui->cb_outputRate4->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[4] = ui->cb_outputRate5->currentText().toUInt();
actuatorSettingsData.ChannelUpdateFreq[5] = ui->cb_outputRate6->currentText().toUInt();
actuatorSettingsData.MotorsSpinWhileArmed = m_config->spinningArmed->isChecked() ?
actuatorSettingsData.MotorsSpinWhileArmed = ui->spinningArmed->isChecked() ?
ActuatorSettings::MOTORSSPINWHILEARMED_TRUE :
ActuatorSettings::MOTORSSPINWHILEARMED_FALSE;
@ -394,7 +400,7 @@ void ConfigOutputWidget::openHelp()
void ConfigOutputWidget::stopTests()
{
m_config->channelOutTest->setChecked(false);
ui->channelOutTest->setChecked(false);
}
void ConfigOutputWidget::disableIfNotMe(UAVObject* obj)

View File

@ -50,7 +50,7 @@ public:
private:
Ui_OutputWidget *m_config;
Ui_OutputWidget *ui;
QList<QSlider> sliders;

View File

@ -20,6 +20,9 @@
<number>0</number>
</property>
<widget class="QWidget" name="tab">
<property name="autoFillBackground">
<bool>true</bool>
</property>
<attribute name="title">
<string>HW settings</string>
</attribute>
@ -119,7 +122,7 @@
<number>12</number>
</property>
<item row="2" column="2">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
<item row="7" column="0">
<widget class="QLabel" name="label_8">
<property name="sizePolicy">

View File

@ -61,8 +61,7 @@ const double ConfigRevoWidget::maxVarValue = 0.1;
// *****************
class Thread : public QThread
{
class Thread : public QThread {
public:
static void usleep(unsigned long usecs)
{
@ -74,9 +73,10 @@ public:
ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
ConfigTaskWidget(parent),
collectingData(false),
m_ui(new Ui_RevoSensorsWidget()),
position(-1)
collectingData(false),
position(-1),
isBoardRotationStored(false)
{
m_ui->setupUi(this);
@ -214,6 +214,8 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
// will be dealing with some null pointers
addUAVObject("RevoCalibration");
addUAVObject("EKFConfiguration");
addUAVObject("HomeLocation");
addUAVObject("AttitudeSettings");
autoLoadWidgets();
// Connect the signals
@ -222,10 +224,17 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData()));
connect(m_ui->noiseMeasurementStart, SIGNAL(clicked()), this, SLOT(doStartNoiseMeasurement()));
connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation()));
addUAVObjectToWidgetRelation("RevoSettings", "FusionAlgorithm", m_ui->FusionAlgorithm);
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->rollRotation, AttitudeSettings::BOARDROTATION_ROLL);
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->pitchRotation, AttitudeSettings::BOARDROTATION_PITCH);
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->yawRotation, AttitudeSettings::BOARDROTATION_YAW);
populateWidgets();
refreshWidgetsValues();
m_ui->tabWidget->setCurrentIndex(0);
}
ConfigRevoWidget::~ConfigRevoWidget()
@ -256,6 +265,10 @@ void ConfigRevoWidget::resizeEvent(QResizeEvent *event)
*/
void ConfigRevoWidget::doStartAccelGyroBiasCalibration()
{
// Store and reset board rotation before calibration starts
isBoardRotationStored = false;
storeAndClearBoardRotation();
m_ui->accelBiasStart->setEnabled(false);
m_ui->accelBiasProgress->setValue(0);
@ -312,6 +325,7 @@ void ConfigRevoWidget::doStartAccelGyroBiasCalibration()
void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj)
{
QMutexLocker lock(&sensorsUpdateLock);
Q_UNUSED(lock);
switch (obj->getObjID()) {
@ -349,7 +363,6 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj)
if (accel_accum_x.size() >= NOISE_SAMPLES &&
gyro_accum_y.size() >= NOISE_SAMPLES &&
collectingData == true) {
collectingData = false;
Accels *accels = Accels::GetInstance(getObjectManager());
@ -385,9 +398,11 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj)
accels->setMetadata(initialAccelsMdata);
gyros->setMetadata(initialGyrosMdata);
}
}
// Recall saved board rotation
recallBoardRotation();
}
}
int LinearEquationsSolving(int nDim, double *pfMatr, double *pfVect, double *pfSolution)
@ -397,25 +412,20 @@ int LinearEquationsSolving(int nDim, double* pfMatr, double* pfVect, double* pfS
int i, j, k, m;
for(k=0; k<(nDim-1); k++) // base row of matrix
{
for (k = 0; k < (nDim - 1); k++) { // base row of matrix
// search of line with max element
fMaxElem = fabs(pfMatr[k * nDim + k]);
m = k;
for(i=k+1; i<nDim; i++)
{
if(fMaxElem < fabs(pfMatr[i*nDim + k]) )
{
for (i = k + 1; i < nDim; i++) {
if (fMaxElem < fabs(pfMatr[i * nDim + k])) {
fMaxElem = pfMatr[i * nDim + k];
m = i;
}
}
// permutation of base line (index k) and max element line(index m)
if(m != k)
{
for(i=k; i<nDim; i++)
{
if (m != k) {
for (i = k; i < nDim; i++) {
fAcc = pfMatr[k * nDim + i];
pfMatr[k * nDim + i] = pfMatr[m * nDim + i];
pfMatr[m * nDim + i] = fAcc;
@ -425,25 +435,22 @@ int LinearEquationsSolving(int nDim, double* pfMatr, double* pfVect, double* pfS
pfVect[m] = fAcc;
}
if( pfMatr[k*nDim + k] == 0.) return 0; // needs improvement !!!
if (pfMatr[k * nDim + k] == 0.) {
return 0; // needs improvement !!!
}
// triangulation of matrix with coefficients
for(j=(k+1); j<nDim; j++) // current row of matrix
{
for (j = (k + 1); j < nDim; j++) { // current row of matrix
fAcc = -pfMatr[j * nDim + k] / pfMatr[k * nDim + k];
for(i=k; i<nDim; i++)
{
for (i = k; i < nDim; i++) {
pfMatr[j * nDim + i] = pfMatr[j * nDim + i] + fAcc * pfMatr[k * nDim + i];
}
pfVect[j] = pfVect[j] + fAcc * pfVect[k]; // free member recalculation
}
}
for(k=(nDim-1); k>=0; k--)
{
for (k = (nDim - 1); k >= 0; k--) {
pfSolution[k] = pfVect[k];
for(i=(k+1); i<nDim; i++)
{
for (i = (k + 1); i < nDim; i++) {
pfSolution[k] -= (pfMatr[k * nDim + i] * pfSolution[i]);
}
pfSolution[k] = pfSolution[k] / pfMatr[k * nDim + k];
@ -475,7 +482,9 @@ int SixPointInConstFieldCal( double ConstMag, double x[6], double y[6], double z
}
// solve for c0=bx/Sx, c1=Sy^2/Sx^2; c2=Sy*by/Sx^2, c3=Sz^2/Sx^2, c4=Sz*bz/Sx^2
if ( !LinearEquationsSolving( 5, (double *)A, f, c) ) return 0;
if (!LinearEquationsSolving(5, (double *)A, f, c)) {
return 0;
}
// use one magnitude equation and c's to find Sx - doesn't matter which - all give the same answer
xp = x[0]; yp = y[0]; zp = z[0];
@ -501,16 +510,20 @@ int SixPointInConstFieldCal( double ConstMag, double x[6], double y[6], double z
*/
void ConfigRevoWidget::doStartSixPointCalibration()
{
// Store and reset board rotation before calibration starts
isBoardRotationStored = false;
storeAndClearBoardRotation();
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
Q_ASSERT(revoCalibration);
Q_ASSERT(homeLocation);
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
HomeLocation::DataFields homeLocationData = homeLocation->getData();
// check if Homelocation is set
if(!homeLocationData.Set)
{
if (!homeLocationData.Set) {
QMessageBox msgBox;
msgBox.setInformativeText(tr("<p>HomeLocation not SET.</p><p>Please set your HomeLocation and try again. Aborting calibration!</p>"));
msgBox.setStandardButtons(QMessageBox::Ok);
@ -597,6 +610,7 @@ void ConfigRevoWidget::doStartSixPointCalibration()
void ConfigRevoWidget::savePositionData()
{
QMutexLocker lock(&sensorsUpdateLock);
m_ui->sixPointsSave->setEnabled(false);
accel_accum_x.clear();
@ -709,6 +723,9 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj)
accels->setMetadata(initialAccelsMdata);
#endif
mag->setMetadata(initialMagMdata);
// Recall saved board rotation
recallBoardRotation();
}
}
}
@ -723,6 +740,7 @@ void ConfigRevoWidget::computeScaleBias()
double Be_length;
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
Q_ASSERT(revoCalibration);
Q_ASSERT(homeLocation);
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
@ -791,7 +809,7 @@ void ConfigRevoWidget::computeScaleBias()
revoCalibrationData = revoCalibration->getData();
m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat.");
}
#else
#else // ifdef SIX_POINT_CAL_ACCEL
bool good_calibration = true;
good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] ==
revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X];
@ -812,11 +830,47 @@ void ConfigRevoWidget::computeScaleBias()
revoCalibrationData = revoCalibration->getData();
m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat.");
}
#endif
#endif // ifdef SIX_POINT_CAL_ACCEL
position = -1; // set to run again
}
void ConfigRevoWidget::storeAndClearBoardRotation()
{
if(!isBoardRotationStored) {
// Store current board rotation
isBoardRotationStored = true;
AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager());
Q_ASSERT(attitudeSettings);
AttitudeSettings::DataFields data = attitudeSettings->getData();
storedBoardRotation[AttitudeSettings::BOARDROTATION_YAW] = data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW];
storedBoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL];
storedBoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH];
// Set board rotation to no rotation
data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = 0;
data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = 0;
data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = 0;
attitudeSettings->setData(data);
}
}
void ConfigRevoWidget::recallBoardRotation()
{
if(isBoardRotationStored) {
// Recall current board rotation
isBoardRotationStored = false;
AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager());
Q_ASSERT(attitudeSettings);
AttitudeSettings::DataFields data = attitudeSettings->getData();
data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = storedBoardRotation[AttitudeSettings::BOARDROTATION_YAW];
data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = storedBoardRotation[AttitudeSettings::BOARDROTATION_ROLL];
data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = storedBoardRotation[AttitudeSettings::BOARDROTATION_PITCH];
attitudeSettings->setData(data);
}
}
/**
Rotate the paper plane
*/
@ -825,7 +879,6 @@ void ConfigRevoWidget::displayPlane(QString elementID)
paperplane->setElementId(elementID);
m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect());
m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio);
}
/*********** Noise measurement functions **************/
@ -835,6 +888,11 @@ void ConfigRevoWidget::displayPlane(QString elementID)
void ConfigRevoWidget::doStartNoiseMeasurement()
{
QMutexLocker lock(&sensorsUpdateLock);
// Store and reset board rotation before calibration starts
isBoardRotationStored = false;
storeAndClearBoardRotation();
Q_UNUSED(lock);
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
@ -845,8 +903,7 @@ void ConfigRevoWidget::doStartNoiseMeasurement()
HomeLocation::DataFields homeLocationData = homeLocation->getData();
// check if Homelocation is set
if(!homeLocationData.Set)
{
if (!homeLocationData.Set) {
QMessageBox msgBox;
msgBox.setInformativeText(tr("<p>HomeLocation not SET.</p><p>Please set your HomeLocation and try again. Aborting calibration!</p>"));
msgBox.setStandardButtons(QMessageBox::Ok);
@ -907,6 +964,7 @@ void ConfigRevoWidget::doStartNoiseMeasurement()
void ConfigRevoWidget::doGetNoiseSample(UAVObject *obj)
{
QMutexLocker lock(&sensorsUpdateLock);
Q_UNUSED(lock);
Q_ASSERT(obj);
@ -982,6 +1040,9 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj)
revoCalData.R[EKFConfiguration::R_MAGZ] = listVar(mag_accum_z);
ekfConfiguration->setData(revoCalData);
}
// Recall saved board rotation
recallBoardRotation();
}
}
@ -992,44 +1053,55 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj)
void ConfigRevoWidget::drawVariancesGraph()
{
EKFConfiguration *ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager());
Q_ASSERT(ekfConfiguration);
if(!ekfConfiguration)
if (!ekfConfiguration) {
return;
}
EKFConfiguration::DataFields ekfConfigurationData = ekfConfiguration->getData();
// The expected range is from 1E-6 to 1E-1
double steps = 6; // 6 bars on the graph
float accel_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELX]));
if(accel_x)
if (accel_x) {
accel_x->setTransform(QTransform::fromScale(1, accel_x_var), false);
}
float accel_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELY]));
if(accel_y)
if (accel_y) {
accel_y->setTransform(QTransform::fromScale(1, accel_y_var), false);
}
float accel_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELZ]));
if(accel_z)
if (accel_z) {
accel_z->setTransform(QTransform::fromScale(1, accel_z_var), false);
}
float gyro_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROX]));
if(gyro_x)
if (gyro_x) {
gyro_x->setTransform(QTransform::fromScale(1, gyro_x_var), false);
}
float gyro_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROY]));
if(gyro_y)
if (gyro_y) {
gyro_y->setTransform(QTransform::fromScale(1, gyro_y_var), false);
}
float gyro_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROZ]));
if(gyro_z)
if (gyro_z) {
gyro_z->setTransform(QTransform::fromScale(1, gyro_z_var), false);
}
// Scale by 1e-3 because mag vars are much higher.
float mag_x_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGX]));
if(mag_x)
if (mag_x) {
mag_x->setTransform(QTransform::fromScale(1, mag_x_var), false);
}
float mag_y_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGY]));
if(mag_y)
if (mag_y) {
mag_y->setTransform(QTransform::fromScale(1, mag_y_var), false);
}
float mag_z_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGZ]));
if(mag_z)
if (mag_z) {
mag_z->setTransform(QTransform::fromScale(1, mag_z_var), false);
}
}
/**
* Called by the ConfigTaskWidget parent when RevoCalibration is updated
@ -1044,12 +1116,31 @@ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object)
m_ui->noiseMeasurementStart->setEnabled(true);
m_ui->sixPointsStart->setEnabled(true);
m_ui->accelBiasStart->setEnabled(true);
m_ui->startDriftCalib->setEnabled(true);
m_ui->calibInstructions->setText(QString("Press \"Start\" above to calibrate."));
m_ui->isSetCheckBox->setEnabled(false);
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
Q_ASSERT(homeLocation);
HomeLocation::DataFields homeLocationData = homeLocation->getData();
QString beStr = QString("%1:%2:%3").arg(QString::number(homeLocationData.Be[0]), QString::number(homeLocationData.Be[1]), QString::number(homeLocationData.Be[2]));
m_ui->beBox->setText(beStr);
}
/**
@}
@}
*/
void ConfigRevoWidget::clearHomeLocation()
{
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
Q_ASSERT(homeLocation);
HomeLocation::DataFields homeLocationData;
homeLocationData.Latitude = 0;
homeLocationData.Longitude = 0;
homeLocationData.Altitude = 0;
homeLocationData.Be[0] = 0;
homeLocationData.Be[1] = 0;
homeLocationData.Be[2] = 0;
homeLocationData.g_e = 9.81f;
homeLocationData.Set = HomeLocation::SET_FALSE;
homeLocation->setData(homeLocationData);
}

View File

@ -43,8 +43,7 @@
class Ui_Widget;
class ConfigRevoWidget: public ConfigTaskWidget
{
class ConfigRevoWidget : public ConfigTaskWidget {
Q_OBJECT
public:
@ -101,6 +100,13 @@ private:
static const int NOISE_SAMPLES = 100;
// Board rotation store/recall
qint16 storedBoardRotation[3];
bool isBoardRotationStored;
void storeAndClearBoardRotation();
void recallBoardRotation();
private slots:
// ! Overriden method from the configTaskWidget to update UI
virtual void refreshWidgetsValues(UAVObject *object = NULL);
@ -118,10 +124,12 @@ private slots:
void doStartNoiseMeasurement();
void doGetNoiseSample(UAVObject *);
// Slot for clearing home location
void clearHomeLocation();
protected:
void showEvent(QShowEvent *event);
void resizeEvent(QResizeEvent *event);
};
#endif // ConfigRevoWidget_H

View File

@ -1,7 +1,7 @@
/**
******************************************************************************
*
* @file configstabilizationwidget.h
* @file configstabilizationwidget.cpp
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
@ -36,132 +36,161 @@
#include <QUrl>
#include <QList>
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/generalsettings.h>
ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_stabilization = new Ui_StabilizationWidget();
m_stabilization->setupUi(this);
ui = new Ui_StabilizationWidget();
ui->setupUi(this);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_stabilization->saveStabilizationToRAM_6->setVisible(false);
if (!settings->useExpertMode()) {
ui->saveStabilizationToRAM_6->setVisible(false);
}
autoLoadWidgets();
realtimeUpdates = new QTimer(this);
connect(m_stabilization->realTimeUpdates_6,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int)));
connect(realtimeUpdates, SIGNAL(timeout()), this, SLOT(apply()));
connect(m_stabilization->checkBox_7,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int)));
connect(m_stabilization->checkBox_2,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int)));
connect(m_stabilization->checkBox_8,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int)));
connect(m_stabilization->checkBox_3,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int)));
connect(ui->realTimeUpdates_6, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool)));
addWidget(ui->realTimeUpdates_6);
connect(ui->realTimeUpdates_8, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool)));
addWidget(ui->realTimeUpdates_8);
connect(ui->realTimeUpdates_12, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool)));
addWidget(ui->realTimeUpdates_12);
connect(ui->checkBox_7, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
addWidget(ui->checkBox_7);
connect(ui->checkBox_2, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
addWidget(ui->checkBox_2);
connect(ui->checkBox_8, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
addWidget(ui->checkBox_8);
connect(ui->checkBox_3, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
addWidget(ui->checkBox_3);
addWidget(ui->pushButton_2);
addWidget(ui->pushButton_3);
addWidget(ui->pushButton_4);
addWidget(ui->pushButton_5);
addWidget(ui->pushButton_6);
addWidget(ui->pushButton_9);
addWidget(ui->pushButton_20);
addWidget(ui->pushButton_22);
addWidget(ui->pushButton_23);
addWidget(ui->basicResponsivenessGroupBox);
connect(ui->basicResponsivenessGroupBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
addWidget(ui->advancedResponsivenessGroupBox);
connect(ui->advancedResponsivenessGroupBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
connect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *)));
// Link by default
ui->checkBox_7->setChecked(true);
ui->checkBox_8->setChecked(true);
disableMouseWheelEvents();
updateEnableControls();
}
ConfigStabilizationWidget::~ConfigStabilizationWidget()
{
// Do nothing
}
void ConfigStabilizationWidget::realtimeUpdatesSlot(int value)
void ConfigStabilizationWidget::refreshWidgetsValues(UAVObject *o)
{
m_stabilization->realTimeUpdates_6->setCheckState((Qt::CheckState)value);
if(value==Qt::Checked && !realtimeUpdates->isActive())
realtimeUpdates->start(300);
else if(value==Qt::Unchecked)
realtimeUpdates->stop();
ConfigTaskWidget::refreshWidgetsValues(o);
ui->basicResponsivenessGroupBox->setChecked(ui->rateRollKp_3->value() == ui->ratePitchKp_4->value() &&
ui->rateRollKi_3->value() == ui->ratePitchKi_4->value());
}
void ConfigStabilizationWidget::linkCheckBoxes(int value)
void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value)
{
if(sender()== m_stabilization->checkBox_7)
m_stabilization->checkBox_3->setCheckState((Qt::CheckState)value);
else if(sender()== m_stabilization->checkBox_3)
m_stabilization->checkBox_7->setCheckState((Qt::CheckState)value);
else if(sender()== m_stabilization->checkBox_8)
m_stabilization->checkBox_2->setCheckState((Qt::CheckState)value);
else if(sender()== m_stabilization->checkBox_2)
m_stabilization->checkBox_8->setCheckState((Qt::CheckState)value);
ui->realTimeUpdates_6->setChecked(value);
ui->realTimeUpdates_8->setChecked(value);
ui->realTimeUpdates_12->setChecked(value);
if (value && !realtimeUpdates->isActive()) {
realtimeUpdates->start(AUTOMATIC_UPDATE_RATE);
qDebug() << "Instant Update timer started.";
} else if (!value && realtimeUpdates->isActive()) {
realtimeUpdates->stop();
qDebug() << "Instant Update timer stopped.";
}
}
void ConfigStabilizationWidget::linkCheckBoxes(bool value)
{
if (sender() == ui->checkBox_7) {
ui->checkBox_3->setChecked(value);
} else if (sender() == ui->checkBox_3) {
ui->checkBox_7->setChecked(value);
} else if (sender() == ui->checkBox_8) {
ui->checkBox_2->setChecked(value);
} else if (sender() == ui->checkBox_2) {
ui->checkBox_8->setChecked(value);
} else if (sender() == ui->basicResponsivenessGroupBox) {
ui->advancedResponsivenessGroupBox->setChecked(!value);
if (value) {
processLinkedWidgets(ui->AttitudeResponsivenessSlider);
processLinkedWidgets(ui->RateResponsivenessSlider);
}
} else if (sender() == ui->advancedResponsivenessGroupBox) {
ui->basicResponsivenessGroupBox->setChecked(!value);
}
}
void ConfigStabilizationWidget::processLinkedWidgets(QWidget *widget)
{
if(m_stabilization->checkBox_7->checkState()==Qt::Checked)
{
if(widget== m_stabilization->RateRollKp_2)
{
m_stabilization->RatePitchKp->setValue(m_stabilization->RateRollKp_2->value());
}
else if(widget== m_stabilization->RateRollKi_2)
{
m_stabilization->RatePitchKi->setValue(m_stabilization->RateRollKi_2->value());
}
else if(widget== m_stabilization->RateRollILimit_2)
{
m_stabilization->RatePitchILimit->setValue(m_stabilization->RateRollILimit_2->value());
}
else if(widget== m_stabilization->RatePitchKp)
{
m_stabilization->RateRollKp_2->setValue(m_stabilization->RatePitchKp->value());
}
else if(widget== m_stabilization->RatePitchKi)
{
m_stabilization->RateRollKi_2->setValue(m_stabilization->RatePitchKi->value());
}
else if(widget== m_stabilization->RatePitchILimit)
{
m_stabilization->RateRollILimit_2->setValue(m_stabilization->RatePitchILimit->value());
}
else if(widget== m_stabilization->RollRateKd)
{
m_stabilization->PitchRateKd->setValue(m_stabilization->RollRateKd->value());
}
else if(widget== m_stabilization->PitchRateKd)
{
m_stabilization->RollRateKd->setValue(m_stabilization->PitchRateKd->value());
}
}
if(m_stabilization->checkBox_8->checkState()==Qt::Checked)
{
if(widget== m_stabilization->AttitudeRollKp)
{
m_stabilization->AttitudePitchKp_2->setValue(m_stabilization->AttitudeRollKp->value());
}
else if(widget== m_stabilization->AttitudeRollKi)
{
m_stabilization->AttitudePitchKi_2->setValue(m_stabilization->AttitudeRollKi->value());
}
else if(widget== m_stabilization->AttitudeRollILimit)
{
m_stabilization->AttitudePitchILimit_2->setValue(m_stabilization->AttitudeRollILimit->value());
}
else if(widget== m_stabilization->AttitudePitchKp_2)
{
m_stabilization->AttitudeRollKp->setValue(m_stabilization->AttitudePitchKp_2->value());
}
else if(widget== m_stabilization->AttitudePitchKi_2)
{
m_stabilization->AttitudeRollKi->setValue(m_stabilization->AttitudePitchKi_2->value());
}
else if(widget== m_stabilization->AttitudePitchILimit_2)
{
m_stabilization->AttitudeRollILimit->setValue(m_stabilization->AttitudePitchILimit_2->value());
}
if (ui->checkBox_7->isChecked()) {
if (widget == ui->RateRollKp_2) {
ui->RatePitchKp->setValue(ui->RateRollKp_2->value());
} else if (widget == ui->RateRollKi_2) {
ui->RatePitchKi->setValue(ui->RateRollKi_2->value());
} else if (widget == ui->RateRollILimit_2) {
ui->RatePitchILimit->setValue(ui->RateRollILimit_2->value());
} else if (widget == ui->RatePitchKp) {
ui->RateRollKp_2->setValue(ui->RatePitchKp->value());
} else if (widget == ui->RatePitchKi) {
ui->RateRollKi_2->setValue(ui->RatePitchKi->value());
} else if (widget == ui->RatePitchILimit) {
ui->RateRollILimit_2->setValue(ui->RatePitchILimit->value());
} else if (widget == ui->RollRateKd) {
ui->PitchRateKd->setValue(ui->RollRateKd->value());
} else if (widget == ui->PitchRateKd) {
ui->RollRateKd->setValue(ui->PitchRateKd->value());
}
}
if (ui->checkBox_8->isChecked()) {
if (widget == ui->AttitudeRollKp) {
ui->AttitudePitchKp_2->setValue(ui->AttitudeRollKp->value());
} else if (widget == ui->AttitudeRollKi) {
ui->AttitudePitchKi_2->setValue(ui->AttitudeRollKi->value());
} else if (widget == ui->AttitudeRollILimit) {
ui->AttitudePitchILimit_2->setValue(ui->AttitudeRollILimit->value());
} else if (widget == ui->AttitudePitchKp_2) {
ui->AttitudeRollKp->setValue(ui->AttitudePitchKp_2->value());
} else if (widget == ui->AttitudePitchKi_2) {
ui->AttitudeRollKi->setValue(ui->AttitudePitchKi_2->value());
} else if (widget == ui->AttitudePitchILimit_2) {
ui->AttitudeRollILimit->setValue(ui->AttitudePitchILimit_2->value());
}
}
if (ui->basicResponsivenessGroupBox->isChecked()) {
if (widget == ui->AttitudeResponsivenessSlider) {
ui->ratePitchKp_4->setValue(ui->AttitudeResponsivenessSlider->value());
} else if (widget == ui->RateResponsivenessSlider) {
ui->ratePitchKi_4->setValue(ui->RateResponsivenessSlider->value());
}
}
}

View File

@ -46,11 +46,18 @@ public:
~ConfigStabilizationWidget();
private:
Ui_StabilizationWidget *m_stabilization;
Ui_StabilizationWidget *ui;
QTimer * realtimeUpdates;
// Milliseconds between automatic 'Instant Updates'
static const int AUTOMATIC_UPDATE_RATE = 500;
protected slots:
void refreshWidgetsValues(UAVObject *o = NULL);
private slots:
void realtimeUpdatesSlot(int);
void linkCheckBoxes(int value);
void realtimeUpdatesSlot(bool value);
void linkCheckBoxes(bool value);
void processLinkedWidgets(QWidget*);
};

View File

@ -108,9 +108,3 @@ void ConfigTxPIDWidget::saveSettings()
UAVObject *obj = HwSettings::GetInstance(getObjectManager());
saveObjectToSD(obj);
}
/**
@}
@}
*/

View File

@ -138,8 +138,6 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
// Connect the help pushbutton
connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
enableControls(false);
refreshWidgetsValues();
// register widgets for dirty state management
@ -150,8 +148,12 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
addWidget(m_aircraft->accelTime);
addWidget(m_aircraft->decelTime);
addWidget(m_aircraft->maxAccelSlider);
addWidget(m_aircraft->ffTestBox1);
addWidget(m_aircraft->ffTestBox2);
addWidget(m_aircraft->ffTestBox3);
disableMouseWheelEvents();
updateEnableControls();
}
/**

View File

@ -29,11 +29,11 @@
<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 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-weight:600;&quot;&gt;Attitude / INS calibration&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-weight:600;&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;This panel will be updated to provide the relevant controls to let you calibrate your OpenPilot INS or your CopterControl unit, depending on the board which is detected once telemetry is connected and running.&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;&quot;&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
&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;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; font-weight:600;&quot;&gt;Attitude Calibration&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; font-weight:600;&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:'Ubuntu'; font-size:11pt;&quot;&gt;This panel will be updated to provide the relevant controls to let you calibrate your OpenPilot unit, depending on the board which is detected once telemetry is connected and running.&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;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>

View File

@ -25,15 +25,18 @@
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QTextBrowser" name="textBrowser">
<property name="enabled">
<bool>true</bool>
</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:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&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; font-weight:600;&quot;&gt;Hardware Configuration&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; font-weight:600;&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; font-weight:600;&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:'Ubuntu'; font-size:11pt;&quot;&gt;This panel will be updated to provide the relevant controls to let you configure your hardware once telemetry is connected and running.&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;/body&gt;&lt;/html&gt;</string>
&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;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>

Binary file not shown.

Before

Width:  |  Height:  |  Size: 178 KiB

After

Width:  |  Height:  |  Size: 183 KiB

View File

@ -11,8 +11,7 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) :
ui->setupUi(this);
// The first time through the loop, keep the legend. All other times, delete it.
if(!showlegend)
{
if (!showlegend) {
layout()->removeWidget(ui->legend0);
layout()->removeWidget(ui->legend1);
layout()->removeWidget(ui->legend2);
@ -27,7 +26,6 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) :
delete ui->legend4;
delete ui->legend5;
delete ui->legend6;
}
connect(ui->channelMin, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated()));
@ -55,15 +53,16 @@ void inputChannelForm::setName(QString &name)
ui->channelName->setText(name);
QFontMetrics metrics(ui->channelName->font());
int width = metrics.width(name) + 5;
foreach(inputChannelForm * form,parent()->findChildren<inputChannelForm*>())
{
if(form==this)
foreach(inputChannelForm * form, parent()->findChildren<inputChannelForm *>()) {
if (form == this) {
continue;
if(form->ui->channelName->minimumSize().width()<width)
}
if (form->ui->channelName->minimumSize().width() < width) {
form->ui->channelName->setMinimumSize(width, 0);
else
} else {
width = form->ui->channelName->minimumSize().width();
}
}
ui->channelName->setMinimumSize(width, 0);
}
@ -73,6 +72,7 @@ void inputChannelForm::setName(QString &name)
void inputChannelForm::minMaxUpdated()
{
bool reverse = ui->channelMin->value() > ui->channelMax->value();
if (reverse) {
ui->channelNeutral->setMinimum(ui->channelMax->value());
ui->channelNeutral->setMaximum(ui->channelMin->value());
@ -129,8 +129,9 @@ void inputChannelForm::groupUpdated()
Q_ASSERT(0);
}
for (int i = 0; i < count; i++)
for (int i = 0; i < count; i++) {
ui->channelNumberDropdown->addItem(QString(tr("Chan %1").arg(i + 1)));
}
ui->channelNumber->setMaximum(count);
ui->channelNumber->setMinimum(0);

View File

@ -43,10 +43,6 @@ MixerCurve::MixerCurve(QWidget *parent) :
m_mixerUI->SettingsGroup->hide();
m_curve->showCommands(false);
m_curve->showCommand("Reset", false);
m_curve->showCommand("Popup", false);
m_curve->showCommand("Commands", false);
// create our spin delegate
m_spinDelegate = new DoubleSpinDelegate();
@ -54,27 +50,19 @@ MixerCurve::MixerCurve(QWidget *parent) :
// set the default mixer type
setMixerType(MixerCurve::MIXERCURVE_THROTTLE);
// setup and turn off advanced mode
CommandActivated();
// paint the ui
UpdateCurveUI();
// wire up our signals
connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(CurveTypeChanged()));
connect(m_mixerUI->ResetCurve, SIGNAL(clicked()), this, SLOT(ResetCurve()));
connect(m_mixerUI->PopupCurve, SIGNAL(clicked()), this, SLOT(PopupCurve()));
connect(m_mixerUI->GenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve()));
connect(m_curve, SIGNAL(curveUpdated()), this, SLOT(UpdateSettingsTable()));
connect(m_curve, SIGNAL(commandActivated(MixerNode*)),this, SLOT(CommandActivated(MixerNode*)));
connect(m_settings, SIGNAL(cellChanged(int, int)), this, SLOT(SettingsTableChanged()));
connect(m_mixerUI->CurveMin, SIGNAL(valueChanged(double)), this, SLOT(CurveMinChanged(double)));
connect(m_mixerUI->CurveMax, SIGNAL(valueChanged(double)), this, SLOT(CurveMaxChanged(double)));
connect(m_mixerUI->CurveStep, SIGNAL(valueChanged(double)), this, SLOT(GenerateCurve()));
}
MixerCurve::~MixerCurve()
@ -103,7 +91,6 @@ void MixerCurve::setMixerType(MixerCurveType curveType)
{
m_mixerUI->SettingsGroup->setTitle("Pitch Curve");
m_curve->setRange(-1.0, 1.0);
m_curve->setPositiveColor("#0000aa", "#0000aa");
m_mixerUI->CurveMin->setMinimum(-1.0);
m_mixerUI->CurveMax->setMinimum(-1.0);
break;
@ -126,15 +113,11 @@ void MixerCurve::ResetCurve()
initLinearCurve(MixerCurveWidget::NODE_NUMELEM, getCurveMax(), getCurveMin());
m_curve->activateCommand("Linear");
UpdateSettingsTable();
}
void MixerCurve::PopupCurve()
{
if (!m_curve->isCommandActive("Popup")) {
m_mixerUI->SettingsGroup->show();
m_mixerUI->PopupCurve->hide();
@ -143,20 +126,13 @@ void MixerCurve::PopupCurve()
m_mixerUI->SettingsGroup->hide();
m_mixerUI->PopupCurve->show();
m_curve->showCommands(false);
}
}
void MixerCurve::UpdateCurveUI()
{
// get the user settings
QString curveType = m_mixerUI->CurveType->currentText();
m_curve->activateCommand(curveType);
bool cmdsActive = m_curve->isCommandActive("Commands");
m_curve->showCommand("StepPlus", cmdsActive && curveType != "Linear");
m_curve->showCommand("StepMinus", cmdsActive && curveType != "Linear");
m_curve->showCommand("StepValue", cmdsActive && curveType != "Linear");
m_mixerUI->CurveStep->setMinimum(0.0);
m_mixerUI->CurveStep->setMaximum(100.0);
@ -170,8 +146,7 @@ void MixerCurve::UpdateCurveUI()
m_mixerUI->stepLabel->setVisible(false);
m_mixerUI->CurveStep->setVisible(false);
if ( curveType.compare("Flat")==0)
{
if (curveType.compare("Flat") == 0) {
m_mixerUI->minLabel->setVisible(false);
m_mixerUI->CurveMin->setVisible(false);
m_mixerUI->stepLabel->setVisible(true);
@ -181,13 +156,11 @@ void MixerCurve::UpdateCurveUI()
m_mixerUI->CurveStep->setSingleStep(0.01);
m_mixerUI->CurveStep->setValue(m_mixerUI->CurveMax->value() / 2);
}
if ( curveType.compare("Linear")==0)
{
if (curveType.compare("Linear") == 0) {
m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true);
}
if ( curveType.compare("Step")==0)
{
if (curveType.compare("Step") == 0) {
m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true);
m_mixerUI->stepLabel->setText("Step at");
@ -196,8 +169,7 @@ void MixerCurve::UpdateCurveUI()
m_mixerUI->CurveStep->setMinimum(1.0);
}
if ( curveType.compare("Exp")==0)
{
if (curveType.compare("Exp") == 0) {
m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true);
m_mixerUI->stepLabel->setText("Power");
@ -206,8 +178,7 @@ void MixerCurve::UpdateCurveUI()
m_mixerUI->CurveStep->setMinimum(1.0);
}
if ( curveType.compare("Log")==0)
{
if (curveType.compare("Log") == 0) {
m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true);
m_mixerUI->stepLabel->setText("Power");
@ -229,43 +200,32 @@ void MixerCurve::GenerateCurve()
double value2 = getCurveMax();
double value3 = getCurveStep();
m_curve->setCommandText("StepValue", QString("%0").arg(value3));
QString CurveType = m_mixerUI->CurveType->currentText();
QList<double> points;
for (int i=0; i<MixerCurveWidget::NODE_NUMELEM; i++)
{
for (int i = 0; i < MixerCurveWidget::NODE_NUMELEM; i++) {
scale = ((double)i / (double)(MixerCurveWidget::NODE_NUMELEM - 1));
if ( CurveType.compare("Flat")==0)
{
if (CurveType.compare("Flat") == 0) {
points.append(value3);
}
if ( CurveType.compare("Linear")==0)
{
if (CurveType.compare("Linear") == 0) {
newValue = value1 + (scale * (value2 - value1));
points.append(newValue);
}
if ( CurveType.compare("Step")==0)
{
if (scale*100<value3)
{
if (CurveType.compare("Step") == 0) {
if (scale * 100 < value3) {
points.append(value1);
}
else
{
} else {
points.append(value2);
}
}
if ( CurveType.compare("Exp")==0)
{
if (CurveType.compare("Exp") == 0) {
newValue = value1 + (((exp(scale * (value3 / 10)) - 1)) / (exp((value3 / 10)) - 1) * (value2 - value1));
points.append(newValue);
}
if ( CurveType.compare("Log")==0)
{
if (CurveType.compare("Log") == 0) {
newValue = value1 + (((log(scale * (value3 * 2) + 1)) / (log(1 + (value3 * 2)))) * (value2 - value1));
points.append(newValue);
}
@ -282,10 +242,12 @@ void MixerCurve::initCurve (const QList<double>* points)
m_curve->setCurve(points);
UpdateSettingsTable();
}
QList<double> MixerCurve::getCurve()
{
return m_curve->getCurve();
}
void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue)
{
setMin(minValue);
@ -293,42 +255,49 @@ void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue
m_curve->initLinearCurve(numPoints, maxValue, minValue);
if (m_spinDelegate)
if (m_spinDelegate) {
m_spinDelegate->setRange(minValue, maxValue);
}
}
void MixerCurve::setCurve(const QList<double> *points)
{
m_curve->setCurve(points);
UpdateSettingsTable();
}
void MixerCurve::setMin(double value)
{
// m_curve->setMin(value);
m_mixerUI->CurveMin->setMinimum(value);
}
double MixerCurve::getMin()
{
return m_curve->getMin();
}
void MixerCurve::setMax(double value)
{
// m_curve->setMax(value);
m_mixerUI->CurveMax->setMaximum(value);
}
double MixerCurve::getMax()
{
return m_curve->getMax();
}
double MixerCurve::setRange(double min, double max)
{
return m_curve->setRange(min, max);
}
double MixerCurve::getCurveMin()
{
return m_mixerUI->CurveMin->value();
}
double MixerCurve::getCurveMax()
{
return m_mixerUI->CurveMax->value();
@ -344,25 +313,25 @@ void MixerCurve::UpdateSettingsTable()
QList<double> points = m_curve->getCurve();
int ptCnt = points.count();
for (int i=0; i<ptCnt; i++)
{
for (int i = 0; i < ptCnt; i++) {
QTableWidgetItem *item = m_settings->item(i, 0);
if (item)
if (item) {
item->setText(QString().sprintf("%.2f", points.at((ptCnt - 1) - i)));
}
}
}
void MixerCurve::SettingsTableChanged()
{
QList<double> points;
for (int i=0; i < m_settings->rowCount(); i++)
{
for (int i = 0; i < m_settings->rowCount(); i++) {
QTableWidgetItem *item = m_settings->item(i, 0);
if (item)
if (item) {
points.push_front(item->text().toDouble());
}
}
m_mixerUI->CurveMin->setValue(points.first());
m_mixerUI->CurveMax->setValue(points.last());
@ -370,59 +339,6 @@ void MixerCurve::SettingsTableChanged()
m_curve->setCurve(&points);
}
void MixerCurve::CommandActivated(MixerNode* node)
{
QString name = (node) ? node->getName() : "Reset";
if (name == "Reset") {
ResetCurve();
m_curve->showCommands(false);
}
else if (name == "Commands") {
}
else if (name == "Popup" ) {
PopupCurve();
}
else if (name == "Linear") {
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear"));
}
else if (name == "Log") {
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Log"));
}
else if (name == "Exp") {
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Exp"));
}
else if (name == "Flat") {
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Flat"));
}
else if (name == "Step") {
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Step"));
}
else if (name == "MinPlus") {
m_mixerUI->CurveMin->stepUp();
}
else if (name == "MinMinus") {
m_mixerUI->CurveMin->stepDown();
}
else if (name == "MaxPlus") {
m_mixerUI->CurveMax->stepUp();
}
else if (name == "MaxMinus"){
m_mixerUI->CurveMax->stepDown();
}
else if (name == "StepPlus") {
m_mixerUI->CurveStep->stepUp();
m_curve->setCommandText("StepValue", QString("%0").arg(getCurveStep()));
}
else if (name == "StepMinus") {
m_mixerUI->CurveStep->stepDown();
m_curve->setCommandText("StepValue", QString("%0").arg(getCurveStep()));
}
GenerateCurve();
}
void MixerCurve::CurveTypeChanged()
{
// setup the ui for this curvetype
@ -455,8 +371,9 @@ void MixerCurve::showEvent(QShowEvent *event)
m_settings->setColumnWidth(0, (m_settings->width() - m_settings->verticalHeader()->width()));
int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount();
for (int i=0; i<m_settings->rowCount(); i++)
for (int i = 0; i < m_settings->rowCount(); i++) {
m_settings->setRowHeight(i, h);
}
m_curve->showEvent(event);
}
@ -467,8 +384,9 @@ void MixerCurve::resizeEvent(QResizeEvent* event)
m_settings->setColumnWidth(0, (m_settings->width() - m_settings->verticalHeader()->width()));
int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount();
for (int i=0; i<m_settings->rowCount(); i++)
for (int i = 0; i < m_settings->rowCount(); i++) {
m_settings->setRowHeight(i, h);
}
m_curve->resizeEvent(event);
}

View File

@ -84,7 +84,6 @@ public slots:
void UpdateSettingsTable();
private slots:
void CommandActivated(MixerNode* node = 0);
void SettingsTableChanged();
void CurveTypeChanged();
void CurveMinChanged(double value);

View File

@ -38,7 +38,7 @@ class OutputChannelForm : public ConfigTaskWidget
public:
explicit OutputChannelForm(const int index, QWidget *parent = NULL, const bool showLegend = false);
~OutputChannelForm();
friend class ConfigOnputWidget;
friend class ConfigOutputWidget;
void setAssignment(const QString &assignment);
int index() const;
@ -57,10 +57,10 @@ signals:
void channelChanged(int index, int value);
private:
Ui::outputChannelForm ui;
/// Channel index
int m_index;
bool m_inChannelTest;
Ui::outputChannelForm ui;
private slots:
void linkToggled(bool state);

View File

@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>720</width>
<height>567</height>
<width>643</width>
<height>531</height>
</rect>
</property>
<property name="windowTitle">
@ -16,10 +16,16 @@
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QTabWidget" name="tabWidget">
<property name="autoFillBackground">
<bool>true</bool>
</property>
<property name="currentIndex">
<number>0</number>
</property>
<widget class="QWidget" name="tab_2">
<property name="autoFillBackground">
<bool>true</bool>
</property>
<attribute name="title">
<string>Calibration</string>
</attribute>
@ -46,8 +52,8 @@
<widget class="QLabel" name="label_3">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
@ -132,8 +138,8 @@
<widget class="QLabel" name="label">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
@ -235,8 +241,8 @@ Hint: run this with engines at cruising speed.</string>
<widget class="QLabel" name="label_5">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
@ -288,173 +294,6 @@ Hint: run this with engines at cruising speed.</string>
</layout>
</widget>
</item>
<item>
<widget class="QFrame" name="frame_4">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_8">
<property name="margin">
<number>3</number>
</property>
<item>
<layout class="QVBoxLayout" name="gyroDriftLayout">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_11">
<item>
<widget class="QLabel" name="label_6">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>#4 Gyro temperature drift calibration</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>Temp:</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="gyroMinTemp">
<property name="font">
<font>
<pointsize>9</pointsize>
</font>
</property>
<property name="text">
<string>Min</string>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="gyroTempSlider">
<property name="toolTip">
<string>Currently measured temperature on the system. This is actually the
MB temperature, be careful if somehow you know that your INS
temperature is very different from your MB temp...</string>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="tickPosition">
<enum>QSlider::TicksBelow</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="gyroMaxTemp">
<property name="font">
<font>
<pointsize>9</pointsize>
</font>
</property>
<property name="text">
<string>Max</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_7">
<item>
<widget class="QLabel" name="label_14">
<property name="text">
<string>Current drift:</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_10">
<item>
<widget class="QLabel" name="label_17">
<property name="text">
<string>Saved drift:</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<item>
<widget class="QPushButton" name="startDriftCalib">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Start gathering data for temperature drift calibration.
Avoid sudden moves once you have started gathering!</string>
</property>
<property name="text">
<string>Start</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="gyroMeasureDrift">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Launch drift measurement based on gathered data.
TODO: is this necessary? Measurement could be auto updated every second or so, or done when we stop measuring...</string>
</property>
<property name="text">
<string>Measure</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="updateDrift">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Updates the XYZ drift values into the AHRS (saves to SD)</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
@ -473,54 +312,301 @@ p, li { white-space: pre-wrap; }
&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;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:11pt; font-weight:600;&quot;&gt;Help&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; font-weight:600;&quot;&gt;Step #1 and #2 are really necessary. Steps #3 and #4 will help you achieve the best possible results.&lt;/span&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; 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; font-weight:600;&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:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;#1: Multi-Point calibration:&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; font-weight:600;&quot;&gt;Help&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;Step #1 and #2 are really necessary. Step #3 will help you achieve the best possible results.&lt;/span&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; 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;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:'Ubuntu'; font-size:11pt;&quot;&gt;#1: Multi-Point calibration:&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;This calibration will compute the scale for all sensors on the INS. Press &amp;quot;Start&amp;quot; to begin calibration, and follow the instructions which will be displayed here. Note that your HomeLocation must be set first, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).&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;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:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;#2: Sensor noise calibration:&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;#2: Sensor noise calibration:&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;This calibration will compute sensor variance under standard conditions. You can leave your engines running at low to mid throttle to take their vibration into account before pressing &amp;quot;Start&amp;quot;.&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;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:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;#3: Accelerometer bias calibration:&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;This step will ensure that accelerometer bias is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.&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;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:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;#4 Gyro temp drift calibration:&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; font-weight:600;&quot;&gt;&lt;br /&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;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;#3: Accelerometer bias calibration:&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;This step will ensure that accelerometer bias is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.&lt;/span&gt;&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="tab">
<property name="autoFillBackground">
<bool>true</bool>
</property>
<attribute name="title">
<string>Settings</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_6">
<item>
<layout class="QHBoxLayout" name="ahrsSettingsLayout">
<item>
<widget class="QLabel" name="label_2">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
<property name="margin">
<number>6</number>
</property>
<property name="text">
<string>Attitude Algorithm:</string>
</property>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Attitude Estimation Algorithm</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="0" alignment="Qt::AlignTop">
<widget class="QComboBox" name="FusionAlgorithm">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Selects the sensor integration algorithm to be used by the Revolution board.</string>
</property>
</widget>
</item>
<item row="1" column="0">
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_2">
<widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Home Location</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum>
</property>
<item row="2" column="3">
<widget class="QLabel" name="label_10">
<property name="text">
<string>Gravity acceleration:</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Latitude:</string>
</property>
</widget>
</item>
<item row="2" column="5">
<widget class="QLineEdit" name="geBox">
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:HomeLocation</string>
<string>fieldname:g_e</string>
</stringlist>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="lattitudeBox">
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:HomeLocation</string>
<string>fieldname:Latitude</string>
</stringlist>
</property>
</widget>
</item>
<item row="1" column="5">
<widget class="QLineEdit" name="beBox">
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_8">
<property name="text">
<string>Altitude:</string>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QLineEdit" name="altitudeBox">
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:HomeLocation</string>
<string>fieldname:Altitude</string>
</stringlist>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="label_9">
<property name="text">
<string>Magnetic field vector:</string>
</property>
</widget>
</item>
<item row="0" column="0" colspan="6">
<widget class="QLabel" name="label_11">
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This information must be set to enable calibration the Revolution controllers sensors. &lt;br/&gt;Set home location using context menu in the map widget.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="longitudeBox">
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:HomeLocation</string>
<string>fieldname:Longitude</string>
</stringlist>
</property>
</widget>
</item>
<item row="3" column="5">
<widget class="QCheckBox" name="isSetCheckBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="text">
<string>Is Set</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:HomeLocation</string>
<string>fieldname:Set</string>
</stringlist>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_4">
<property name="text">
<string>Longitude:</string>
</property>
</widget>
</item>
<item row="5" column="5" alignment="Qt::AlignRight">
<widget class="QPushButton" name="hlClearButton">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Clear</string>
</property>
</widget>
</item>
<item row="4" column="5">
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QGroupBox" name="groupBox_3">
<property name="title">
<string>Rotate virtual attitude relative to board</string>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="0,1,0,1,0,1,0">
<item row="0" column="1">
<widget class="QLabel" name="label_12">
<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="QSpinBox" name="rollRotation">
<property name="minimum">
<number>-180</number>
</property>
<property name="maximum">
<number>180</number>
</property>
</widget>
</item>
<item row="1" column="4">
<spacer name="horizontalSpacer_9">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
@ -532,71 +618,114 @@ p, li { white-space: pre-wrap; }
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="label_4">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
<item row="1" column="5">
<widget class="QSpinBox" name="yawRotation">
<property name="minimum">
<number>-180</number>
</property>
<property name="text">
<string>Home Location:</string>
<property name="maximum">
<number>180</number>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="homeLocationSet">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Saves the Home Location. This is only enabled
if the Home Location is set, i.e. if the GPS fix is
successful.
Disabled if there is no GPS fix.</string>
<item row="0" column="5">
<widget class="QLabel" name="label_13">
<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>Set</string>
<string>Yaw</string>
</property>
<property name="checked">
<bool>true</bool>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<attribute name="buttonGroup">
<string notr="true">buttonGroup</string>
</attribute>
</widget>
</item>
<item>
<widget class="QRadioButton" name="homeLocationClear">
<property name="enabled">
<bool>true</bool>
<item row="1" column="2">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="toolTip">
<string>Clears the HomeLocation: only makes sense if you save
to SD. This will force the INS to use the next GPS fix as the
new home location unless it is in indoor mode.</string>
<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_15">
<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>Clear</string>
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<attribute name="buttonGroup">
<string notr="true">buttonGroup</string>
</attribute>
</widget>
</item>
<item row="1" column="3">
<widget class="QSpinBox" name="pitchRotation">
<property name="minimum">
<number>-90</number>
</property>
<property name="maximum">
<number>90</number>
</property>
</widget>
</item>
<item row="1" column="0">
<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 row="1" column="6">
<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>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
<height>100</height>
</size>
</property>
</spacer>
@ -716,7 +845,4 @@ specific calibration button on top of the screen.</string>
<include location="../coreplugin/core.qrc"/>
</resources>
<connections/>
<buttongroups>
<buttongroup name="buttonGroup"/>
</buttongroups>
</ui>

File diff suppressed because it is too large Load Diff

View File

@ -39,8 +39,6 @@
****************************************************************************/
import QtQuick 1.1
import QtWebKit 1.0
// This is a tabbed pane element. Add a nested Rectangle to add a tab.
TabWidget {

View File

@ -36,35 +36,30 @@ ScopeGadget::ScopeGadget(QString classId, ScopeGadgetWidget *widget, QWidget *pa
IUAVGadget(classId, parent),
m_widget(widget),
configLoaded(false)
{
}
{}
void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration *config)
{
ScopeGadgetConfiguration *sgConfig = qobject_cast<ScopeGadgetConfiguration *>(config);
ScopeGadgetWidget *widget = qobject_cast<ScopeGadgetWidget *>(m_widget);
widget->setXWindowSize(sgConfig->dataSize());
widget->setRefreshInterval(sgConfig->refreshInterval());
if(sgConfig->plotType() == SequentialPlot )
if (sgConfig->plotType() == SequentialPlot) {
widget->setupSequentialPlot();
else if(sgConfig->plotType() == ChronoPlot)
} else if (sgConfig->plotType() == ChronoPlot) {
widget->setupChronoPlot();
// else if(sgConfig->plotType() == UAVObjectPlot)
// widget->setupUAVObjectPlot();
}
foreach(PlotCurveConfiguration * plotCurveConfig, sgConfig->plotCurveConfigs()) {
QString uavObject = plotCurveConfig->uavObject;
QString uavField = plotCurveConfig->uavField;
int scale = plotCurveConfig->yScalePower;
int mean = plotCurveConfig->yMeanSamples;
QString mathFunction = plotCurveConfig->mathFunction;
QRgb color = plotCurveConfig->color;
bool antialiased = plotCurveConfig->drawAntialiased;
widget->addCurvePlot(
uavObject,
uavField,
@ -72,11 +67,11 @@ void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config)
mean,
mathFunction,
QPen(QBrush(QColor(color), Qt::SolidPattern),
// (qreal)2,
(qreal)1,
Qt::SolidLine,
Qt::SquareCap,
Qt::BevelJoin)
Qt::BevelJoin),
antialiased
);
}
@ -87,7 +82,6 @@ void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config)
widget->csvLoggingStop();
widget->csvLoggingSetName(sgConfig->name());
widget->csvLoggingStart();
}
/**

View File

@ -38,64 +38,52 @@ ScopeGadgetConfiguration::ScopeGadgetConfiguration(QString classId, QSettings* q
int plotCurveCount = 0;
//if a saved configuration exists load it
// If a saved configuration exists load it
if (qSettings != 0) {
currentStreamVersion = qSettings->value("configurationStreamVersion").toUInt();
if(currentStreamVersion != m_configurationStreamVersion)
if (currentStreamVersion != m_configurationStreamVersion) {
return;
}
m_plotType = qSettings->value("plotType").toInt();
m_dataSize = qSettings->value("dataSize").toInt();
m_refreshInterval = qSettings->value("refreshInterval").toInt();
plotCurveCount = qSettings->value("plotCurveCount").toInt();
for(int plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++)
{
QString uavObject;
QString uavField;
QRgb color;
for (int plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) {
qSettings->beginGroup(QString("plotCurve") + QString().number(plotDatasLoadIndex));
PlotCurveConfiguration *plotCurveConf = new PlotCurveConfiguration();
uavObject = qSettings->value("uavObject").toString();
plotCurveConf->uavObject = uavObject;
uavField = qSettings->value("uavField").toString();
plotCurveConf->uavField = uavField;
color = qSettings->value("color").value<QRgb>();
plotCurveConf->color = color;
plotCurveConf->uavObject = qSettings->value("uavObject").toString();
plotCurveConf->uavField = qSettings->value("uavField").toString();
plotCurveConf->color = qSettings->value("color").value<QRgb>();
plotCurveConf->yScalePower = qSettings->value("yScalePower").toInt();
plotCurveConf->mathFunction = qSettings->value("mathFunction").toString();
plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples").toInt();
if (!plotCurveConf->yMeanSamples) plotCurveConf->yMeanSamples = 1; // fallback for backward compatibility with earlier versions //IS THIS STILL NECESSARY?
plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples", 1).toInt();
plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples", 1).toInt();
plotCurveConf->drawAntialiased = qSettings->value("drawAntialiased", true).toBool();
plotCurveConf->yMinimum = qSettings->value("yMinimum").toDouble();
plotCurveConf->yMaximum = qSettings->value("yMaximum").toDouble();
m_PlotCurveConfigs.append(plotCurveConf);
m_plotCurveConfigs.append(plotCurveConf);
qSettings->endGroup();
}
m_LoggingEnabled = qSettings->value("LoggingEnabled").toBool();
m_LoggingNewFileOnConnect = qSettings->value("LoggingNewFileOnConnect").toBool();
m_LoggingPath = qSettings->value("LoggingPath").toString();
m_loggingEnabled = qSettings->value("LoggingEnabled").toBool();
m_loggingNewFileOnConnect = qSettings->value("LoggingNewFileOnConnect").toBool();
m_loggingPath = qSettings->value("LoggingPath").toString();
}
}
void ScopeGadgetConfiguration::clearPlotData()
{
PlotCurveConfiguration* poltCurveConfig;
PlotCurveConfiguration *plotCurveConfig;
while(m_PlotCurveConfigs.size() > 0)
{
poltCurveConfig = m_PlotCurveConfigs.first();
m_PlotCurveConfigs.pop_front();
delete poltCurveConfig;
while (m_plotCurveConfigs.size() > 0) {
plotCurveConfig = m_plotCurveConfigs.first();
m_plotCurveConfigs.pop_front();
delete plotCurveConfig;
}
}
@ -109,16 +97,16 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone()
int plotDatasLoadIndex = 0;
ScopeGadgetConfiguration *m = new ScopeGadgetConfiguration(this->classId());
m->setPlotType(m_plotType);
m->setDataSize(m_dataSize);
m->setMathFunctionType(m_mathFunctionType);
m->setRefreashInterval(m_refreshInterval);
plotCurveCount = m_PlotCurveConfigs.size();
plotCurveCount = m_plotCurveConfigs.size();
for(plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++)
{
PlotCurveConfiguration* currentPlotCurveConf = m_PlotCurveConfigs.at(plotDatasLoadIndex);
for (plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) {
PlotCurveConfiguration *currentPlotCurveConf = m_plotCurveConfigs.at(plotDatasLoadIndex);
PlotCurveConfiguration *newPlotCurveConf = new PlotCurveConfiguration();
newPlotCurveConf->uavObject = currentPlotCurveConf->uavObject;
@ -127,18 +115,16 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone()
newPlotCurveConf->yScalePower = currentPlotCurveConf->yScalePower;
newPlotCurveConf->yMeanSamples = currentPlotCurveConf->yMeanSamples;
newPlotCurveConf->mathFunction = currentPlotCurveConf->mathFunction;
newPlotCurveConf->drawAntialiased = currentPlotCurveConf->drawAntialiased;
newPlotCurveConf->yMinimum = currentPlotCurveConf->yMinimum;
newPlotCurveConf->yMaximum = currentPlotCurveConf->yMaximum;
m->addPlotCurveConfig(newPlotCurveConf);
}
m->setLoggingEnabled(m_LoggingEnabled);
m->setLoggingNewFileOnConnect(m_LoggingNewFileOnConnect);
m->setLoggingPath(m_LoggingPath);
m->setLoggingEnabled(m_loggingEnabled);
m->setLoggingNewFileOnConnect(m_loggingNewFileOnConnect);
m->setLoggingPath(m_loggingPath);
return m;
}
@ -148,9 +134,9 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone()
* Saves a configuration. //REDEFINES saveConfig CHILD BEHAVIOR?
*
*/
void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const {
int plotCurveCount = m_PlotCurveConfigs.size();
void ScopeGadgetConfiguration::saveConfig(QSettings *qSettings) const
{
int plotCurveCount = m_plotCurveConfigs.size();
int plotDatasLoadIndex = 0;
qSettings->setValue("configurationStreamVersion", m_configurationStreamVersion);
@ -159,11 +145,10 @@ void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const {
qSettings->setValue("refreshInterval", m_refreshInterval);
qSettings->setValue("plotCurveCount", plotCurveCount);
for(plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++)
{
for (plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) {
qSettings->beginGroup(QString("plotCurve") + QString().number(plotDatasLoadIndex));
PlotCurveConfiguration* plotCurveConf = m_PlotCurveConfigs.at(plotDatasLoadIndex);
PlotCurveConfiguration *plotCurveConf = m_plotCurveConfigs.at(plotDatasLoadIndex);
qSettings->setValue("uavObject", plotCurveConf->uavObject);
qSettings->setValue("uavField", plotCurveConf->uavField);
qSettings->setValue("color", plotCurveConf->color);
@ -172,22 +157,21 @@ void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const {
qSettings->setValue("yMeanSamples", plotCurveConf->yMeanSamples);
qSettings->setValue("yMinimum", plotCurveConf->yMinimum);
qSettings->setValue("yMaximum", plotCurveConf->yMaximum);
qSettings->setValue("drawAntialiased", plotCurveConf->drawAntialiased);
qSettings->endGroup();
}
qSettings->setValue("LoggingEnabled", m_LoggingEnabled);
qSettings->setValue("LoggingNewFileOnConnect", m_LoggingNewFileOnConnect);
qSettings->setValue("LoggingPath", m_LoggingPath);
qSettings->setValue("LoggingEnabled", m_loggingEnabled);
qSettings->setValue("LoggingNewFileOnConnect", m_loggingNewFileOnConnect);
qSettings->setValue("LoggingPath", m_loggingPath);
}
void ScopeGadgetConfiguration::replacePlotCurveConfig(QList<PlotCurveConfiguration *> newPlotCurveConfigs)
{
clearPlotData();
m_PlotCurveConfigs.append(newPlotCurveConfigs);
m_plotCurveConfigs.append(newPlotCurveConfigs);
}
ScopeGadgetConfiguration::~ScopeGadgetConfiguration()

View File

@ -35,8 +35,7 @@
using namespace Core;
struct PlotCurveConfiguration
{
struct PlotCurveConfiguration {
QString uavObject;
QString uavField;
int yScalePower; // This is the power to which each value must be raised
@ -45,10 +44,10 @@ struct PlotCurveConfiguration
QString mathFunction;
double yMinimum;
double yMaximum;
bool drawAntialiased;
};
class ScopeGadgetConfiguration : public IUAVGadgetConfiguration
{
class ScopeGadgetConfiguration : public IUAVGadgetConfiguration {
Q_OBJECT
public:
explicit ScopeGadgetConfiguration(QString classId, QSettings *qSettings = 0, QObject *parent = 0);
@ -56,45 +55,97 @@ public:
~ScopeGadgetConfiguration();
// configuration setter functions
void setPlotType(int value){m_plotType = value;}
void setMathFunctionType(int value){m_mathFunctionType = value;}
void setDataSize(int value){m_dataSize = value;}
void setRefreashInterval(int value){m_refreshInterval = value;}
void addPlotCurveConfig(PlotCurveConfiguration* value){m_PlotCurveConfigs.append(value);}
void replacePlotCurveConfig(QList<PlotCurveConfiguration*> m_PlotCurveConfigs);
void setPlotType(int value)
{
m_plotType = value;
}
void setMathFunctionType(int value)
{
m_mathFunctionType = value;
}
void setDataSize(int value)
{
m_dataSize = value;
}
void setRefreashInterval(int value)
{
m_refreshInterval = value;
}
void addPlotCurveConfig(PlotCurveConfiguration *value)
{
m_plotCurveConfigs.append(value);
}
void replacePlotCurveConfig(QList<PlotCurveConfiguration *> m_plotCurveConfigs);
//configurations getter functions
int plotType(){return m_plotType;}
int mathFunctionType(){return m_mathFunctionType;}
int dataSize(){return m_dataSize;}
int refreshInterval(){return m_refreshInterval;}
QList<PlotCurveConfiguration*> plotCurveConfigs(){return m_PlotCurveConfigs;}
// Configurations getter functions
int plotType()
{
return m_plotType;
}
int mathFunctionType()
{
return m_mathFunctionType;
}
int dataSize()
{
return m_dataSize;
}
int refreshInterval()
{
return m_refreshInterval;
}
QList<PlotCurveConfiguration *> plotCurveConfigs()
{
return m_plotCurveConfigs;
}
void saveConfig(QSettings *settings) const; // THIS SEEMS TO BE UNUSED
IUAVGadgetConfiguration *clone();
bool getLoggingEnabled(){return m_LoggingEnabled;};
bool getLoggingNewFileOnConnect(){return m_LoggingNewFileOnConnect;};
QString getLoggingPath(){return m_LoggingPath;};
void setLoggingEnabled(bool value){m_LoggingEnabled=value;};
void setLoggingNewFileOnConnect(bool value){m_LoggingNewFileOnConnect=value;};
void setLoggingPath(QString value){m_LoggingPath=value;};
bool getLoggingEnabled()
{
return m_loggingEnabled;
}
bool getLoggingNewFileOnConnect()
{
return m_loggingNewFileOnConnect;
}
QString getLoggingPath()
{
return m_loggingPath;
}
void setLoggingEnabled(bool value)
{
m_loggingEnabled = value;
}
void setLoggingNewFileOnConnect(bool value)
{
m_loggingNewFileOnConnect = value;
}
void setLoggingPath(QString value)
{
m_loggingPath = value;
}
private:
static const uint m_configurationStreamVersion = 1000;//Increment this if the stream format is not compatible with previous versions. This would cause existing configs to be discarded.
int m_plotType; //The type of the plot
int m_dataSize; //The size of the data buffer to render in the curve plot
int m_refreshInterval; //The interval to replot the curve widget. The data buffer is refresh as the data comes in.
int m_mathFunctionType; //The type of math function to be used in the scope analysis
QList<PlotCurveConfiguration*> m_PlotCurveConfigs;
// Increment this if the stream format is not compatible with previous versions. This would cause existing configs to be discarded.
static const uint m_configurationStreamVersion = 1000;
// The type of the plot
int m_plotType;
// The size of the data buffer to render in the curve plot
int m_dataSize;
// The interval to replot the curve widget. The data buffer is refresh as the data comes in.
int m_refreshInterval;
// The type of math function to be used in the scope analysis
int m_mathFunctionType;
QList<PlotCurveConfiguration *> m_plotCurveConfigs;
void clearPlotData();
bool m_LoggingEnabled;
bool m_LoggingNewFileOnConnect;
QString m_LoggingPath;
bool m_loggingEnabled;
bool m_loggingNewFileOnConnect;
QString m_loggingPath;
};
#endif // SCOPEGADGETCONFIGURATION_H

View File

@ -73,8 +73,9 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent)
options_page->mathFunctionComboBox->addItem("Boxcar average");
options_page->mathFunctionComboBox->addItem("Standard deviation");
if(options_page->cmbUAVObjects->currentIndex() >= 0)
if (options_page->cmbUAVObjects->currentIndex() >= 0) {
on_cmbUAVObjects_currentIndexChanged(options_page->cmbUAVObjects->currentText());
}
options_page->cmbScale->addItem("10^-9", -9);
options_page->cmbScale->addItem("10^-6", -6);
@ -102,19 +103,20 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent)
// add the configured curves
foreach(PlotCurveConfiguration * plotData, m_config->plotCurveConfigs()) {
QString uavObject = plotData->uavObject;
QString uavField = plotData->uavField;
int scale = plotData->yScalePower;
int mean = plotData->yMeanSamples;
QString mathFunction = plotData->mathFunction;
QVariant varColor = plotData->color;
bool antialiased = plotData->drawAntialiased;
addPlotCurveConfig(uavObject,uavField,scale,mean,mathFunction,varColor);
addPlotCurveConfig(uavObject, uavField, scale, mean, mathFunction, varColor, antialiased);
}
if(m_config->plotCurveConfigs().count() > 0)
if (m_config->plotCurveConfigs().count() > 0) {
options_page->lstCurves->setCurrentRow(0, QItemSelectionModel::ClearAndSelect);
}
connect(options_page->btnAddCurve, SIGNAL(clicked()), this, SLOT(on_btnAddCurve_clicked()));
connect(options_page->btnRemoveCurve, SIGNAL(clicked()), this, SLOT(on_btnRemoveCurve_clicked()));
@ -148,36 +150,35 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent)
sp->installEventFilter(this);
}
return optionsPageWidget;
}
bool ScopeGadgetOptionsPage::eventFilter( QObject * obj, QEvent * evt ) {
bool ScopeGadgetOptionsPage::eventFilter(QObject *obj, QEvent *evt)
{
// Filter all wheel events, and ignore them
if (evt->type() == QEvent::Wheel &&
(qobject_cast<QAbstractSpinBox *>(obj) ||
qobject_cast<QComboBox *>(obj) ||
qobject_cast<QAbstractSlider*>( obj ) ))
{
qobject_cast<QAbstractSlider *>(obj))) {
evt->ignore();
return true;
}
return ScopeGadgetOptionsPage::eventFilter(obj, evt);
}
void ScopeGadgetOptionsPage::on_mathFunctionComboBox_currentIndexChanged(int currentIndex){
void ScopeGadgetOptionsPage::on_mathFunctionComboBox_currentIndexChanged(int currentIndex)
{
if (currentIndex > 0) {
options_page->spnMeanSamples->setEnabled(true);
}
else{
} else {
options_page->spnMeanSamples->setEnabled(false);
}
}
void ScopeGadgetOptionsPage::on_btnColor_clicked()
{
QColor color = QColorDialog::getColor(QColor(options_page->btnColor->text()));
if (color.isValid()) {
setButtonColor(color);
}
@ -192,8 +193,9 @@ void ScopeGadgetOptionsPage::setYAxisWidgetFromPlotCurve()
bool parseOK = false;
QListWidgetItem *listItem = options_page->lstCurves->currentItem();
if(listItem == 0)
if (listItem == 0) {
return;
}
// WHAT IS UserRole DOING?
int currentIndex = options_page->cmbUAVObjects->findText(listItem->data(Qt::UserRole + 0).toString());
@ -211,12 +213,14 @@ void ScopeGadgetOptionsPage::setYAxisWidgetFromPlotCurve()
setButtonColor(QColor((QRgb)rgb));
int mean = listItem->data(Qt::UserRole + 4).toInt(&parseOK);
if(!parseOK) mean = 1;
if (!parseOK) {
mean = 1;
}
options_page->spnMeanSamples->setValue(mean);
currentIndex = options_page->mathFunctionComboBox->findText(listItem->data(Qt::UserRole + 5).toString());
options_page->mathFunctionComboBox->setCurrentIndex(currentIndex);
options_page->drawAntialiasedCheckBox->setChecked(listItem->data(Qt::UserRole + 6).toBool());
}
void ScopeGadgetOptionsPage::setButtonColor(const QColor &color)
@ -237,25 +241,24 @@ void ScopeGadgetOptionsPage::on_cmbUAVObjects_currentIndexChanged(QString val)
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(objManager->getObject(val));
if (obj == NULL)
if (obj == NULL) {
return; // Rare case: the config contained a UAVObject name which does not exist anymore.
}
QList<UAVObjectField *> fieldList = obj->getFields();
foreach(UAVObjectField * field, fieldList) {
if(field->getType() == UAVObjectField::STRING || field->getType() == UAVObjectField::ENUM )
if (field->getType() == UAVObjectField::STRING || field->getType() == UAVObjectField::ENUM) {
continue;
}
if(field->getElementNames().count() > 1)
{
foreach(QString elemName , field->getElementNames())
{
if (field->getElementNames().count() > 1) {
foreach(QString elemName, field->getElementNames()) {
options_page->cmbUAVField->addItem(field->getName() + "-" + elemName);
}
}
else
} else {
options_page->cmbUAVField->addItem(field->getName());
}
}
}
/**
* Called when the user presses apply or OK.
@ -281,22 +284,25 @@ void ScopeGadgetOptionsPage::apply()
newPlotCurveConfigs->uavObject = listItem->data(Qt::UserRole + 0).toString();
newPlotCurveConfigs->uavField = listItem->data(Qt::UserRole + 1).toString();
newPlotCurveConfigs->yScalePower = listItem->data(Qt::UserRole + 2).toInt(&parseOK);
if(!parseOK)
if (!parseOK) {
newPlotCurveConfigs->yScalePower = 0;
}
QVariant varColor = listItem->data(Qt::UserRole + 3);
int rgb = varColor.toInt(&parseOK);
if(!parseOK)
if (!parseOK) {
newPlotCurveConfigs->color = QColor(Qt::black).rgb();
else
} else {
newPlotCurveConfigs->color = (QRgb)rgb;
}
newPlotCurveConfigs->yMeanSamples = listItem->data(Qt::UserRole + 4).toInt(&parseOK);
if(!parseOK)
if (!parseOK) {
newPlotCurveConfigs->yMeanSamples = 1;
}
newPlotCurveConfigs->mathFunction = listItem->data(Qt::UserRole + 5).toString();
newPlotCurveConfigs->drawAntialiased = listItem->data(Qt::UserRole + 6).toBool();
plotCurveConfigs.append(newPlotCurveConfigs);
}
@ -307,7 +313,6 @@ void ScopeGadgetOptionsPage::apply()
m_config->setLoggingPath(options_page->LoggingPath->path());
m_config->setLoggingNewFileOnConnect(options_page->LoggingConnect->isChecked());
m_config->setLoggingEnabled(options_page->LoggingEnable->isChecked());
}
/*!
@ -320,8 +325,9 @@ void ScopeGadgetOptionsPage::on_btnAddCurve_clicked()
QString uavField = options_page->cmbUAVField->currentText();
int scale = options_page->cmbScale->itemData(options_page->cmbScale->currentIndex()).toInt(&parseOK);
if(!parseOK)
if (!parseOK) {
scale = 0;
}
int mean = options_page->spnMeanSamples->value();
QString mathFunction = options_page->mathFunctionComboBox->currentText();
@ -329,41 +335,40 @@ void ScopeGadgetOptionsPage::on_btnAddCurve_clicked()
QVariant varColor = (int)QColor(options_page->btnColor->text()).rgb();
bool antialiased = options_page->drawAntialiasedCheckBox->isChecked();
// Find an existing plot curve config based on the uavobject and uav field. If it
// exists, update it, else add a new one.
if (options_page->lstCurves->count() &&
options_page->lstCurves->currentItem()->text() == uavObject + "." + uavField)
{
options_page->lstCurves->currentItem()->text() == uavObject + "." + uavField) {
QListWidgetItem *listWidgetItem = options_page->lstCurves->currentItem();
setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,mean,mathFunction,varColor);
}else
{
addPlotCurveConfig(uavObject,uavField,scale,mean,mathFunction,varColor);
setCurvePlotProperties(listWidgetItem, uavObject, uavField, scale, mean, mathFunction, varColor, antialiased);
} else {
addPlotCurveConfig(uavObject, uavField, scale, mean, mathFunction, varColor, antialiased);
options_page->lstCurves->setCurrentRow(options_page->lstCurves->count() - 1);
}
}
void ScopeGadgetOptionsPage::addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor)
void ScopeGadgetOptionsPage::addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor, bool antialias)
{
// Add a new curve config to the list
QString listItemDisplayText = uavObject + "." + uavField;
options_page->lstCurves->addItem(listItemDisplayText);
QListWidgetItem *listWidgetItem = options_page->lstCurves->item(options_page->lstCurves->count() - 1);
setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,mean,mathFunction,varColor);
setCurvePlotProperties(listWidgetItem, uavObject, uavField, scale, mean, mathFunction, varColor, antialias);
}
void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetItem,QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor)
void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale,
int mean, QString mathFunction, QVariant varColor, bool antialias)
{
bool parseOK = false;
// Set the properties of the newly added list item
QString listItemDisplayText = uavObject + "." + uavField;
QRgb rgbColor = (QRgb)varColor.toInt(&parseOK);
QColor color = QColor(rgbColor);
//listWidgetItem->setText(listItemDisplayText);
listWidgetItem->setTextColor(color);
// Store some additional data for the plot curve on the list item
@ -373,6 +378,7 @@ void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetI
listWidgetItem->setData(Qt::UserRole + 3, varColor);
listWidgetItem->setData(Qt::UserRole + 4, QVariant(mean));
listWidgetItem->setData(Qt::UserRole + 5, QVariant(mathFunction));
listWidgetItem->setData(Qt::UserRole + 6, QVariant(antialias));
}
/*!
@ -384,9 +390,7 @@ void ScopeGadgetOptionsPage::on_btnRemoveCurve_clicked()
}
void ScopeGadgetOptionsPage::finish()
{
}
{}
/*!
When a different plot curve config is selected, populate its values into the widgets.
@ -400,10 +404,10 @@ void ScopeGadgetOptionsPage::on_lstCurves_currentRowChanged(int currentRow)
void ScopeGadgetOptionsPage::on_loggingEnable_clicked()
{
bool en = options_page->LoggingEnable->isChecked();
options_page->LoggingPath->setEnabled(en);
options_page->LoggingConnect->setEnabled(en);
options_page->LoggingLabel->setEnabled(en);
}
void ScopeGadgetOptionsPage::on_spnRefreshInterval_valueChanged(int)
@ -415,6 +419,7 @@ void ScopeGadgetOptionsPage::validateRefreshInterval()
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
for (int iIndex = 0; iIndex < options_page->lstCurves->count(); iIndex++) {
QListWidgetItem *listItem = options_page->lstCurves->item(iIndex);
@ -426,8 +431,7 @@ void ScopeGadgetOptionsPage::validateRefreshInterval()
continue;
}
if(options_page->spnRefreshInterval->value() < obj->getMetadata().flightTelemetryUpdatePeriod)
{
if (options_page->spnRefreshInterval->value() < obj->getMetadata().flightTelemetryUpdatePeriod) {
options_page->lblWarnings->setText("The refresh interval is faster than some or all telemetry objects.");
return;
}
@ -435,4 +439,3 @@ void ScopeGadgetOptionsPage::validateRefreshInterval()
options_page->lblWarnings->setText("");
}

View File

@ -38,22 +38,19 @@
#include <QDebug>
#include <QtGui/QColorDialog>
namespace Core
{
namespace Core {
class IUAVGadgetConfiguration;
}
class ScopeGadgetConfiguration;
namespace Ui
{
namespace Ui {
class ScopeGadgetOptionsPage;
}
using namespace Core;
class ScopeGadgetOptionsPage : public IOptionsPage
{
class ScopeGadgetOptionsPage : public IOptionsPage {
Q_OBJECT
public:
explicit ScopeGadgetOptionsPage(ScopeGadgetConfiguration *config, QObject *parent = 0);
@ -66,8 +63,9 @@ private:
Ui::ScopeGadgetOptionsPage *options_page;
ScopeGadgetConfiguration *m_config;
void addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor);
void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor);
void addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor, bool antialias);
void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, int mean,
QString mathFunction, QVariant varColor, bool antialias);
void setYAxisWidgetFromPlotCurve();
void setButtonColor(const QColor &color);
void validateRefreshInterval();
@ -82,7 +80,6 @@ private slots:
void on_btnColor_clicked();
void on_mathFunctionComboBox_currentIndexChanged(int currentIndex);
void on_loggingEnable_clicked();
};
#endif // SCOPEGADGETOPTIONSPAGE_H

View File

@ -176,38 +176,18 @@
</property>
</widget>
</item>
<item row="9" column="0">
<widget class="QLabel" name="label_3">
<item row="7" column="0">
<widget class="QLabel" name="mathFunctionLabel">
<property name="text">
<string>Color:</string>
<string>Math function:</string>
</property>
</widget>
</item>
<item row="9" column="1">
<widget class="QPushButton" name="btnColor">
<item row="7" column="1">
<widget class="QComboBox" name="mathFunctionComboBox">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="text">
<string>Choose</string>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QLabel" name="label_6">
<property name="text">
<string>Y-axis scale factor:</string>
</property>
</widget>
</item>
<item row="10" column="1">
<widget class="QComboBox" name="cmbScale">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="editable">
<bool>false</bool>
</property>
</widget>
</item>
<item row="8" column="0">
@ -248,18 +228,51 @@
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="mathFunctionLabel">
<item row="9" column="0">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Math function:</string>
<string>Color:</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QComboBox" name="mathFunctionComboBox">
<item row="9" column="1">
<widget class="QPushButton" name="btnColor">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="text">
<string>Choose</string>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QLabel" name="label_6">
<property name="text">
<string>Y-axis scale factor:</string>
</property>
</widget>
</item>
<item row="10" column="1">
<widget class="QComboBox" name="cmbScale">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="editable">
<bool>false</bool>
</property>
</widget>
</item>
<item row="11" column="1">
<widget class="QCheckBox" name="drawAntialiasedCheckBox">
<property name="toolTip">
<string>Check this to have the curve drawn antialiased.</string>
</property>
<property name="text">
<string>Draw Antialiased</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
@ -277,7 +290,7 @@
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>100</height>
<height>40</height>
</size>
</property>
</spacer>
@ -288,8 +301,7 @@
<string>Add a new curve to the scope, or update it if the UAVObject and UAVField is the same.</string>
</property>
<property name="text">
<string>Add
Update</string>
<string>Add / Update</string>
</property>
</widget>
</item>
@ -299,8 +311,7 @@ Update</string>
<string>Remove the curve from the scope.</string>
</property>
<property name="text">
<string>Remove
</string>
<string>Remove</string>
</property>
</widget>
</item>
@ -310,12 +321,12 @@ Update</string>
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>15</height>
<height>40</height>
</size>
</property>
</spacer>
@ -331,8 +342,8 @@ Update</string>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>200</height>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
@ -347,6 +358,19 @@ Update</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>

View File

@ -91,8 +91,7 @@ ScopeGadgetWidget::ScopeGadgetWidget(QWidget *parent) : QwtPlot(parent)
ScopeGadgetWidget::~ScopeGadgetWidget()
{
if (replotTimer)
{
if (replotTimer) {
replotTimer->stop();
delete replotTimer;
@ -102,9 +101,9 @@ ScopeGadgetWidget::~ScopeGadgetWidget()
// Get the object to de-monitor
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
foreach (QString uavObjName, m_connectedUAVObjects)
{
foreach(QString uavObjName, m_connectedUAVObjects) {
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(objManager->getObject(uavObjName));
disconnect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(uavObjectReceived(UAVObject *)));
}
@ -127,10 +126,11 @@ void ScopeGadgetWidget::mouseDoubleClickEvent(QMouseEvent *e)
{
// On double-click, toggle legend
mutex.lock();
if (legend())
if (legend()) {
deleteLegend();
else
} else {
addLegend();
}
mutex.unlock();
// On double-click, reset plot zoom
@ -150,8 +150,8 @@ void ScopeGadgetWidget::wheelEvent(QWheelEvent *e)
{
// Change zoom on scroll wheel event
QwtInterval yInterval = axisInterval(QwtPlot::yLeft);
if (yInterval.minValue() != yInterval.maxValue()) //Make sure that the two values are never the same. Sometimes axisInterval returns (0,0)
{
if (yInterval.minValue() != yInterval.maxValue()) { // Make sure that the two values are never the same. Sometimes axisInterval returns (0,0)
// Determine what y value to zoom about. NOTE, this approach has a bug that the in that
// the value returned by Qt includes the legend, whereas the value transformed by Qwt
// does *not*. Thus, when zooming with a legend, there will always be a small bias error.
@ -167,8 +167,7 @@ void ScopeGadgetWidget::wheelEvent(QWheelEvent *e)
setAxisScale(QwtPlot::yLeft,
(yInterval.minValue() - zoomLine) * zoomScale + zoomLine,
(yInterval.maxValue() - zoomLine) * zoomScale + zoomLine);
}
else{
} else {
setAxisScale(QwtPlot::yLeft,
(yInterval.minValue() - zoomLine) / zoomScale + zoomLine,
(yInterval.maxValue() - zoomLine) / zoomScale + zoomLine);
@ -178,30 +177,40 @@ void ScopeGadgetWidget::wheelEvent(QWheelEvent *e)
QwtPlot::wheelEvent(e);
}
void ScopeGadgetWidget::showEvent(QShowEvent *e)
{
replotNewData();
QwtPlot::showEvent(e);
}
/**
* Starts/stops telemetry
*/
void ScopeGadgetWidget::startPlotting()
{
if (!replotTimer)
if (!replotTimer) {
return;
}
if (!replotTimer->isActive())
if (!replotTimer->isActive()) {
replotTimer->start(m_refreshInterval);
}
}
void ScopeGadgetWidget::stopPlotting()
{
if (!replotTimer)
if (!replotTimer) {
return;
}
replotTimer->stop();
}
void ScopeGadgetWidget::deleteLegend()
{
if (!legend())
if (!legend()) {
return;
}
disconnect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, 0);
@ -211,8 +220,9 @@ void ScopeGadgetWidget::deleteLegend()
void ScopeGadgetWidget::addLegend()
{
if (legend())
if (legend()) {
return;
}
// Show a legend at the top
QwtLegend *legend = new QwtLegend();
@ -242,9 +252,11 @@ void ScopeGadgetWidget::addLegend()
foreach(QwtPlotItem * item, this->itemList()) {
bool on = item->isVisible();
QWidget *w = legend->find(item);
if ( w && w->inherits("QwtLegendItem") )
if (w && w->inherits("QwtLegendItem")) {
((QwtLegendItem *)w)->setChecked(!on);
}
}
connect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, SLOT(showCurve(QwtPlotItem *, bool)));
}
@ -281,21 +293,22 @@ void ScopeGadgetWidget::preparePlot(PlotType plotType)
// Only start the timer if we are already connected
Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager();
if (cm->getCurrentConnection() && replotTimer)
{
if (!replotTimer->isActive())
if (cm->getCurrentConnection() && replotTimer) {
if (!replotTimer->isActive()) {
replotTimer->start(m_refreshInterval);
else
} else {
replotTimer->setInterval(m_refreshInterval);
}
}
}
void ScopeGadgetWidget::showCurve(QwtPlotItem *item, bool on)
{
item->setVisible(!on);
QWidget *w = legend()->find(item);
if ( w && w->inherits("QwtLegendItem") )
if (w && w->inherits("QwtLegendItem")) {
((QwtLegendItem *)w)->setChecked(on);
}
mutex.lock();
replot();
@ -385,14 +398,15 @@ void ScopeGadgetWidget::setupChronoPlot()
// scaleWidget->setMinBorderDist(0, fmw);
}
void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor, int meanSamples, QString mathFunction, QPen pen)
void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor, int meanSamples, QString mathFunction, QPen pen, bool antialiased)
{
PlotData *plotData;
if (m_plotType == SequentialPlot)
if (m_plotType == SequentialPlot) {
plotData = new SequentialPlotData(uavObject, uavFieldSubField);
else if (m_plotType == ChronoPlot)
} else if (m_plotType == ChronoPlot) {
plotData = new ChronoPlotData(uavObject, uavFieldSubField);
}
// else if (m_plotType == UAVObjectPlot)
// plotData = new UAVObjectPlotData(uavObject, uavField);
@ -402,15 +416,15 @@ void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField
plotData->mathFunction = mathFunction;
// If the y-bounds are supplied, set them
if (plotData->yMinimum != plotData->yMaximum)
{
if (plotData->yMinimum != plotData->yMaximum) {
setAxisScale(QwtPlot::yLeft, plotData->yMinimum, plotData->yMaximum);
}
// Create the curve
QString curveName = (plotData->uavObject) + "." + (plotData->uavField);
if(plotData->haveSubField)
if (plotData->haveSubField) {
curveName = curveName.append("." + plotData->uavSubField);
}
// Get the uav object
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
@ -427,16 +441,23 @@ void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField
}
QString units = field->getUnits();
if(units == 0)
if (units == 0) {
units = QString();
}
QString curveNameScaled;
if(scaleOrderFactor == 0)
if (scaleOrderFactor == 0) {
curveNameScaled = curveName + " (" + units + ")";
else
} else {
curveNameScaled = curveName + " (x10^" + QString::number(scaleOrderFactor) + " " + units + ")";
}
QwtPlotCurve *plotCurve = new QwtPlotCurve(curveNameScaled);
if (antialiased) {
plotCurve->setRenderHint(QwtPlotCurve::RenderAntialiased);
}
plotCurve->setPen(pen);
plotCurve->setSamples(*plotData->xData, *plotData->yData);
plotCurve->attach(this);
@ -475,17 +496,21 @@ void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField
void ScopeGadgetWidget::uavObjectReceived(UAVObject *obj)
{
foreach(PlotData * plotData, m_curvesData.values()) {
if (plotData->append(obj)) m_csvLoggingDataUpdated=1;
if (plotData->append(obj)) {
m_csvLoggingDataUpdated = 1;
}
}
csvLoggingAddData();
}
void ScopeGadgetWidget::replotNewData()
{
QMutexLocker locker(&mutex);
if (!isVisible()) {
return;
}
foreach(PlotData* plotData, m_curvesData.values())
{
QMutexLocker locker(&mutex);
foreach(PlotData * plotData, m_curvesData.values()) {
plotData->removeStaleData();
plotData->curve->setSamples(*plotData->xData, *plotData->yData);
}
@ -493,8 +518,9 @@ void ScopeGadgetWidget::replotNewData()
QDateTime NOW = QDateTime::currentDateTime();
double toTime = NOW.toTime_t();
toTime += NOW.time().msec() / 1000.0;
if (m_plotType == ChronoPlot)
if (m_plotType == ChronoPlot) {
setAxisScale(QwtPlot::xBottom, toTime - m_xWindowSize, toTime);
}
// qDebug() << "replotNewData from " << NOW.addSecs(- m_xWindowSize) << " to " << NOW;
@ -503,53 +529,6 @@ void ScopeGadgetWidget::replotNewData()
replot();
}
/*
void ScopeGadgetWidget::setupExamplePlot()
{
preparePlot(SequentialPlot);
// Show the axes
setAxisTitle(xBottom, "x");
setAxisTitle(yLeft, "y");
// Calculate the data, 500 points each
const int points = 500;
double x[ points ];
double sn[ points ];
double cs[ points ];
double sg[ points ];
for (int i = 0; i < points; i++) {
x[i] = (3.0 * 3.14 / double(points)) * double(i);
sn[i] = 2.0 * sin(x[i]);
cs[i] = 3.0 * cos(x[i]);
sg[i] = (sn[i] > 0) ? 1 : ((sn[i] < 0) ? -1 : 0);
}
// add curves
QwtPlotCurve *curve1 = new QwtPlotCurve("Curve 1");
curve1->setPen(QPen(Qt::blue));
QwtPlotCurve *curve2 = new QwtPlotCurve("Curve 2");
curve2->setPen(QPen(Qt::red));
QwtPlotCurve *curve3 = new QwtPlotCurve("Curve 3");
curve3->setPen(QPen(Qt::green));
// copy the data into the curves
curve1->setSamples(x, sn, points);
curve2->setSamples(x, cs, points);
curve3->setSamples(x, sg, points);
curve1->attach(this);
curve2->attach(this);
curve3->attach(this);
// finally, refresh the plot
mutex.lock();
replot();
mutex.unlock();
}
*/
void ScopeGadgetWidget::clearCurvePlots()
{
foreach(PlotData * plotData, m_curvesData.values()) {
@ -572,41 +551,34 @@ QFile csvLoggingFile;
*/
int ScopeGadgetWidget::csvLoggingStart()
{
if (!m_csvLoggingStarted)
if (m_csvLoggingEnabled)
if ((!m_csvLoggingNewFileOnConnect)||(m_csvLoggingNewFileOnConnect && m_csvLoggingConnected))
{
if (!m_csvLoggingStarted) {
if (m_csvLoggingEnabled) {
if ((!m_csvLoggingNewFileOnConnect) || (m_csvLoggingNewFileOnConnect && m_csvLoggingConnected)) {
QDateTime NOW = QDateTime::currentDateTime();
m_csvLoggingStartTime = NOW;
m_csvLoggingHeaderSaved = 0;
m_csvLoggingDataSaved = 0;
m_csvLoggingBuffer.clear();
QDir PathCheck(m_csvLoggingPath);
if (!PathCheck.exists())
{
if (!PathCheck.exists()) {
PathCheck.mkpath("./");
}
if (m_csvLoggingNameSet)
{
if (m_csvLoggingNameSet) {
m_csvLoggingFile.setFileName(QString("%1/%2_%3_%4.csv").arg(m_csvLoggingPath).arg(m_csvLoggingName).arg(NOW.toString("yyyy-MM-dd")).arg(NOW.toString("hh-mm-ss")));
}
else
{
} else {
m_csvLoggingFile.setFileName(QString("%1/Log_%2_%3.csv").arg(m_csvLoggingPath).arg(NOW.toString("yyyy-MM-dd")).arg(NOW.toString("hh-mm-ss")));
}
QDir FileCheck(m_csvLoggingFile.fileName());
if (FileCheck.exists())
{
if (FileCheck.exists()) {
m_csvLoggingFile.setFileName("");
}
else
{
} else {
m_csvLoggingStarted = 1;
csvLoggingInsertHeader();
}
}
}
}
return 0;
@ -621,26 +593,30 @@ int ScopeGadgetWidget::csvLoggingStop()
int ScopeGadgetWidget::csvLoggingInsertHeader()
{
if (!m_csvLoggingStarted) return -1;
if (m_csvLoggingHeaderSaved) return -2;
if (m_csvLoggingDataSaved) return -3;
if (!m_csvLoggingStarted) {
return -1;
}
if (m_csvLoggingHeaderSaved) {
return -2;
}
if (m_csvLoggingDataSaved) {
return -3;
}
m_csvLoggingHeaderSaved = 1;
if(m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append)== FALSE)
{
if (m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append) == FALSE) {
qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Header";
}
else
{
} else {
QTextStream ts(&m_csvLoggingFile);
ts << "date" << ", " << "Time" << ", " << "Sec since start" << ", " << "Connected" << ", " << "Data changed";
foreach(PlotData* plotData2, m_curvesData.values())
{
foreach(PlotData * plotData2, m_curvesData.values()) {
ts << ", ";
ts << plotData2->uavObject;
ts << "." << plotData2->uavField;
if (plotData2->haveSubField) ts << "." << plotData2->uavSubField;
if (plotData2->haveSubField) {
ts << "." << plotData2->uavSubField;
}
}
ts << endl;
m_csvLoggingFile.close();
@ -650,7 +626,9 @@ int ScopeGadgetWidget::csvLoggingInsertHeader()
int ScopeGadgetWidget::csvLoggingAddData()
{
if (!m_csvLoggingStarted) return -1;
if (!m_csvLoggingStarted) {
return -1;
}
m_csvLoggingDataValid = 0;
QDateTime NOW = QDateTime::currentDateTime();
QString tempString;
@ -666,30 +644,21 @@ int ScopeGadgetWidget::csvLoggingAddData()
ss << ", " << m_csvLoggingConnected << ", " << m_csvLoggingDataUpdated;
m_csvLoggingDataUpdated = 0;
foreach(PlotData* plotData2, m_curvesData.values())
{
foreach(PlotData * plotData2, m_curvesData.values()) {
ss << ", ";
if (plotData2->xData->isEmpty ())
{
if (plotData2->xData->isEmpty()) {
ss << ", ";
if (plotData2->xData->isEmpty ())
{
}
else
{
if (plotData2->xData->isEmpty()) {} else {
ss << QString().sprintf("%3.10g", plotData2->yData->last());
m_csvLoggingDataValid = 1;
}
}
else
{
} else {
ss << QString().sprintf("%3.10g", plotData2->yData->last());
m_csvLoggingDataValid = 1;
}
}
ss << endl;
if (m_csvLoggingDataValid)
{
if (m_csvLoggingDataValid) {
QTextStream ts(&m_csvLoggingBuffer);
ts << tempString;
}
@ -699,15 +668,14 @@ int ScopeGadgetWidget::csvLoggingAddData()
int ScopeGadgetWidget::csvLoggingInsertData()
{
if (!m_csvLoggingStarted) return -1;
if (!m_csvLoggingStarted) {
return -1;
}
m_csvLoggingDataSaved = 1;
if(m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append)== FALSE)
{
if (m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append) == FALSE) {
qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Data";
}
else
{
} else {
QTextStream ts(&m_csvLoggingFile);
ts << m_csvLoggingBuffer;
m_csvLoggingFile.close();
@ -726,13 +694,15 @@ void ScopeGadgetWidget::csvLoggingSetName(QString newName)
void ScopeGadgetWidget::csvLoggingConnect()
{
m_csvLoggingConnected = 1;
if (m_csvLoggingNewFileOnConnect)csvLoggingStart();
return;
if (m_csvLoggingNewFileOnConnect) {
csvLoggingStart();
}
}
void ScopeGadgetWidget::csvLoggingDisconnect()
{
m_csvLoggingHeaderSaved = 0;
m_csvLoggingConnected = 0;
if (m_csvLoggingNewFileOnConnect)csvLoggingStop();
return;
if (m_csvLoggingNewFileOnConnect) {
csvLoggingStop();
}
}

View File

@ -49,7 +49,6 @@ class TimeScaleDraw : public QwtScaleDraw
{
public:
TimeScaleDraw() {
//baseTime = QDateTime::currentDateTime().toTime_t();
}
virtual QwtText label(double v) const {
uint seconds = (uint)(v);
@ -58,8 +57,6 @@ public:
upTime.setTime(timePart);
return upTime.toLocalTime().toString("hh:mm:ss");
}
private:
// double baseTime;
};
class ScopeGadgetWidget : public QwtPlot
@ -81,15 +78,15 @@ public:
int refreshInterval(){return m_refreshInterval;}
void addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, int meanSamples = 1, QString mathFunction= "None", QPen pen = QPen(Qt::black));
//void removeCurvePlot(QString uavObject, QString uavField);
void addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, int meanSamples = 1,
QString mathFunction= "None", QPen pen = QPen(Qt::black), bool antialiased = true);
void clearCurvePlots();
int csvLoggingStart();
int csvLoggingStop();
void csvLoggingSetName(QString);
void setLoggingEnabled(bool value){m_csvLoggingEnabled=value;};
void setLoggingNewFileOnConnect(bool value){m_csvLoggingNewFileOnConnect=value;};
void setLoggingPath(QString value){m_csvLoggingPath=value;};
void setLoggingEnabled(bool value){m_csvLoggingEnabled=value;}
void setLoggingNewFileOnConnect(bool value){m_csvLoggingNewFileOnConnect=value;}
void setLoggingPath(QString value){m_csvLoggingPath=value;}
protected:
void mousePressEvent(QMouseEvent *e);
@ -97,6 +94,7 @@ protected:
void mouseDoubleClickEvent(QMouseEvent *e);
void mouseMoveEvent(QMouseEvent *e);
void wheelEvent(QWheelEvent *e);
void showEvent(QShowEvent *e);
private slots:
void uavObjectReceived(UAVObject*);

View File

@ -66,10 +66,11 @@ void ConfigTaskWidget::addUAVObject(QString objectName,QList<int> * reloadGroups
void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList<int> *reloadGroups)
{
QString objstr;
if(objectName)
objstr=objectName->getName();
addUAVObject(objstr, reloadGroups);
if (objectName) {
objstr = objectName->getName();
}
addUAVObject(objstr, reloadGroups);
}
/**
* Add an UAVObject field to widget relation to the management system
@ -82,6 +83,7 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
{
UAVObject *obj = NULL;
UAVObjectField *_field = NULL;
obj = objManager->getObject(QString(object));
Q_ASSERT(obj);
_field = obj->getField(QString(field));
@ -93,10 +95,13 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
{
QString objstr;
QString fieldstr;
if(obj)
if (obj) {
objstr = obj->getName();
if(field)
}
if (field) {
fieldstr = field->getName();
}
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index);
}
/**
@ -113,15 +118,16 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
{
UAVObject *obj = objManager->getObject(QString(object), instID);
Q_ASSERT(obj);
UAVObjectField *_field;
int index = 0;
if(!field.isEmpty() && obj)
{
if (!field.isEmpty() && obj) {
_field = obj->getField(QString(field));
if(!element.isEmpty())
if (!element.isEmpty()) {
index = _field->getElementNames().indexOf(QString(element));
}
}
addUAVObjectToWidgetRelation(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID);
}
@ -129,20 +135,26 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
{
QString objstr;
QString fieldstr;
if(obj)
if (obj) {
objstr = obj->getName();
if(field)
}
if (field) {
fieldstr = field->getName();
}
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, element, scale, isLimited, defaultReloadGroups, instID);
}
void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
{
QString objstr;
QString fieldstr;
if(obj)
if (obj) {
objstr = obj->getName();
if(field)
}
if (field) {
fieldstr = field->getName();
}
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index, scale, isLimited, defaultReloadGroups, instID);
}
@ -159,21 +171,22 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject * obj,UAVObjectFie
*/
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
{
if(addShadowWidget(object,field,widget,index,scale,isLimited,defaultReloadGroups,instID))
if (addShadowWidget(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID)) {
return;
}
UAVObject *obj = NULL;
UAVObjectField *_field = NULL;
if(!object.isEmpty())
{
if (!object.isEmpty()) {
obj = objManager->getObject(QString(object), instID);
Q_ASSERT(obj);
objectUpdates.insert(obj, true);
connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(objectUpdated(UAVObject *)));
connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection);
}
if(!field.isEmpty() && obj)
if (!field.isEmpty() && obj) {
_field = obj->getField(QString(field));
}
objectToWidget *ow = new objectToWidget();
ow->field = _field;
ow->object = obj;
@ -182,36 +195,27 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
ow->scale = scale;
ow->isLimited = isLimited;
objOfInterest.append(ow);
if(obj)
{
if(smartsave)
{
if (obj) {
if (smartsave) {
smartsave->addObject((UAVDataObject *)obj);
}
}
if(widget==NULL)
{
if(defaultReloadGroups && obj)
{
foreach(int i,*defaultReloadGroups)
{
if(this->defaultReloadGroups.contains(i))
{
if (widget == NULL) {
if (defaultReloadGroups && obj) {
foreach(int i, *defaultReloadGroups) {
if (this->defaultReloadGroups.contains(i)) {
this->defaultReloadGroups.value(i)->append(ow);
}
else
{
} else {
this->defaultReloadGroups.insert(i, new QList<objectToWidget *>());
this->defaultReloadGroups.value(i)->append(ow);
}
}
}
}
else
{
} else {
connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged()));
if(defaultReloadGroups)
if (defaultReloadGroups) {
addWidgetToDefaultReloadGroups(widget, defaultReloadGroups);
}
shadowsList.insert(widget, ow);
loadWidgetLimits(widget, _field, index, isLimited, scale);
}
@ -221,20 +225,20 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
*/
ConfigTaskWidget::~ConfigTaskWidget()
{
if(smartsave)
if (smartsave) {
delete smartsave;
foreach(QList<objectToWidget*>* pointer,defaultReloadGroups.values())
{
if(pointer)
}
foreach(QList<objectToWidget *> *pointer, defaultReloadGroups.values()) {
if (pointer) {
delete pointer;
}
foreach (objectToWidget* oTw, objOfInterest)
{
if(oTw)
}
foreach(objectToWidget * oTw, objOfInterest) {
if (oTw) {
delete oTw;
}
if(timeOut)
{
}
if (timeOut) {
delete timeOut;
timeOut = NULL;
}
@ -246,6 +250,7 @@ void ConfigTaskWidget::saveObjectToSD(UAVObject *obj)
// central place (and one central queue)
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
utilMngr->saveObjectToSD(obj);
}
@ -253,9 +258,11 @@ void ConfigTaskWidget::saveObjectToSD(UAVObject *obj)
* Util function to get a pointer to the object manager
* @return pointer to the UAVObjectManager
*/
UAVObjectManager* ConfigTaskWidget::getObjectManager() {
UAVObjectManager *ConfigTaskWidget::getObjectManager()
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objMngr = pm->getObject<UAVObjectManager>();
Q_ASSERT(objMngr);
return objMngr;
}
@ -267,8 +274,10 @@ UAVObjectManager* ConfigTaskWidget::getObjectManager() {
double ConfigTaskWidget::listMean(QList<double> list)
{
double accum = 0;
for(int i = 0; i < list.size(); i++)
for (int i = 0; i < list.size(); i++) {
accum += list[i];
}
return accum / list.size();
}
@ -283,12 +292,14 @@ double ConfigTaskWidget::listVar(QList<double> list)
double var_accum = 0;
double mean;
for(int i = 0; i < list.size(); i++)
for (int i = 0; i < list.size(); i++) {
mean_accum += list[i];
}
mean = mean_accum / list.size();
for(int i = 0; i < list.size(); i++)
for (int i = 0; i < list.size(); i++) {
var_accum += (list[i] - mean) * (list[i] - mean);
}
// Use unbiased estimator
return var_accum / (list.size() - 1);
@ -312,12 +323,12 @@ void ConfigTaskWidget::forceConnectedState()//dynamic widgets don't recieve the
void ConfigTaskWidget::onAutopilotConnect()
{
if (utilMngr)
if (utilMngr) {
currentBoard = utilMngr->getBoardModel(); // TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE
}
invalidateObjects();
isConnected = true;
foreach(objectToWidget * ow,objOfInterest)
{
foreach(objectToWidget * ow, objOfInterest) {
loadWidgetLimits(ow->widget, ow->field, ow->index, ow->isLimited, ow->scale);
}
setDirty(false);
@ -332,15 +343,14 @@ void ConfigTaskWidget::populateWidgets()
{
bool dirtyBack = dirty;
emit populateWidgetsRequested();
foreach(objectToWidget * ow,objOfInterest)
{
if(ow->object==NULL || ow->field==NULL || ow->widget==NULL)
{
foreach(objectToWidget * ow, objOfInterest) {
if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) {
// do nothing
}
else
} else {
setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited);
}
}
setDirty(dirtyBack);
}
/**
@ -350,26 +360,22 @@ void ConfigTaskWidget::populateWidgets()
*/
void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj)
{
if (!allowWidgetUpdates)
if (!allowWidgetUpdates) {
return;
}
bool dirtyBack = dirty;
emit refreshWidgetsValuesRequested();
foreach(objectToWidget * ow,objOfInterest)
{
if(ow->object==NULL || ow->field==NULL || ow->widget==NULL)
{
foreach(objectToWidget * ow, objOfInterest) {
if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) {
// do nothing
}
else
{
if(ow->object==obj || obj==NULL)
} else {
if (ow->object == obj || obj == NULL) {
setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited);
}
}
}
setDirty(dirtyBack);
}
/**
* SLOT function used to update the uavobject fields from widgets with relation to
@ -379,15 +385,11 @@ void ConfigTaskWidget::refreshWidgetsValues(UAVObject * obj)
void ConfigTaskWidget::updateObjectsFromWidgets()
{
emit updateObjectsFromWidgetsRequested();
foreach(objectToWidget * ow,objOfInterest)
{
if(ow->object==NULL || ow->field==NULL)
{
}
else
foreach(objectToWidget * ow, objOfInterest) {
if (ow->object == NULL || ow->field == NULL) {} else {
setFieldFromWidget(ow->widget, ow->field, ow->index, ow->scale);
}
}
}
/**
@ -397,9 +399,11 @@ void ConfigTaskWidget::updateObjectsFromWidgets()
void ConfigTaskWidget::helpButtonPressed()
{
QString url = helpButtonList.value((QPushButton *)sender(), QString());
if(!url.isEmpty())
if (!url.isEmpty()) {
QDesktopServices::openUrl(QUrl(url, QUrl::StrictMode));
}
}
/**
* Add update and save buttons to the form
* multiple buttons can be added for the same function
@ -408,33 +412,28 @@ void ConfigTaskWidget::helpButtonPressed()
*/
void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save)
{
if(!smartsave)
{
if (!smartsave) {
smartsave = new smartSaveButton();
connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets()));
connect(smartsave, SIGNAL(saveSuccessfull()), this, SLOT(clearDirty()));
connect(smartsave, SIGNAL(beginOp()), this, SLOT(disableObjUpdates()));
connect(smartsave, SIGNAL(endOp()), this, SLOT(enableObjUpdates()));
}
if(update && save)
if (update && save) {
smartsave->addButtons(save, update);
else if (update)
} else if (update) {
smartsave->addApplyButton(update);
else if (save)
} else if (save) {
smartsave->addSaveButton(save);
if(objOfInterest.count()>0)
{
foreach(objectToWidget * oTw,objOfInterest)
{
}
if (objOfInterest.count() > 0) {
foreach(objectToWidget * oTw, objOfInterest) {
smartsave->addObject((UAVDataObject *)oTw->object);
}
}
TelemetryManager* telMngr = pm->getObject<TelemetryManager>();
if(telMngr->isConnected())
enableControls(true);
else
enableControls(false);
updateEnableControls();
}
/**
* SLOT function used the enable or disable the SAVE, UPLOAD and RELOAD buttons
* @param enable set to true to enable the buttons or false to disable them
@ -442,27 +441,36 @@ void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *sav
*/
void ConfigTaskWidget::enableControls(bool enable)
{
if(smartsave)
if (smartsave) {
smartsave->enableControls(enable);
}
foreach(QPushButton * button, reloadButtonList) {
button->setEnabled(enable);
}
foreach(objectToWidget * ow, objOfInterest) {
if (ow->widget) {
ow->widget->setEnabled(enable);
foreach(shadow * sh, ow->shadowsList) {
sh->widget->setEnabled(enable);
}
}
}
}
/**
* SLOT function called when on of the widgets contents added to the framework changes
*/
void ConfigTaskWidget::forceShadowUpdates()
{
foreach(objectToWidget * oTw,objOfInterest)
{
foreach (shadow * sh, oTw->shadowsList)
{
foreach(objectToWidget * oTw, objOfInterest) {
foreach(shadow * sh, oTw->shadowsList) {
disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged()));
checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale);
setWidgetFromVariant(sh->widget, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale);
emit widgetContentsChanged((QWidget *)sh->widget);
connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged()));
}
}
setDirty(true);
@ -475,36 +483,30 @@ void ConfigTaskWidget::widgetsContentsChanged()
emit widgetContentsChanged((QWidget *)sender());
double scale;
objectToWidget *oTw = shadowsList.value((QWidget *)sender(), NULL);
if(oTw)
{
if(oTw->widget==(QWidget*)sender())
{
if (oTw) {
if (oTw->widget == (QWidget *)sender()) {
scale = oTw->scale;
checkWidgetsLimits((QWidget*)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget*)sender(), oTw->scale, oTw->getUnits()), oTw->scale);
}
else
{
foreach (shadow * sh, oTw->shadowsList)
{
if(sh->widget==(QWidget*)sender())
{
checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(),
oTw->scale, oTw->getUnits()), oTw->scale);
} else {
foreach(shadow * sh, oTw->shadowsList) {
if (sh->widget == (QWidget *)sender()) {
scale = sh->scale;
checkWidgetsLimits((QWidget*)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), scale);
checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(),
scale, oTw->getUnits()), scale);
}
}
}
if(oTw->widget!=(QWidget *)sender())
{
if (oTw->widget != (QWidget *)sender()) {
disconnectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged()));
checkWidgetsLimits(oTw->widget, oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale);
setWidgetFromVariant(oTw->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale);
emit widgetContentsChanged((QWidget *)oTw->widget);
connectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged()));
}
foreach (shadow * sh, oTw->shadowsList)
{
if(sh->widget!=(QWidget*)sender())
{
foreach(shadow * sh, oTw->shadowsList) {
if (sh->widget != (QWidget *)sender()) {
disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged()));
checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale);
setWidgetFromVariant(sh->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale);
@ -513,8 +515,9 @@ void ConfigTaskWidget::widgetsContentsChanged()
}
}
}
if(smartsave)
if (smartsave) {
smartsave->resetIcons();
}
setDirty(true);
}
/**
@ -538,20 +541,22 @@ void ConfigTaskWidget::setDirty(bool value)
*/
bool ConfigTaskWidget::isDirty()
{
if(isConnected)
if (isConnected) {
return dirty;
else
} else {
return false;
}
}
/**
* SLOT function used to disable widget contents changes when related object field changes
*/
void ConfigTaskWidget::disableObjUpdates()
{
allowWidgetUpdates = false;
foreach(objectToWidget * obj,objOfInterest)
{
if(obj->object)disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*)));
foreach(objectToWidget * obj, objOfInterest) {
if (obj->object) {
disconnect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)));
}
}
}
/**
@ -560,12 +565,12 @@ void ConfigTaskWidget::disableObjUpdates()
void ConfigTaskWidget::enableObjUpdates()
{
allowWidgetUpdates = true;
foreach(objectToWidget * obj,objOfInterest)
{
if(obj->object)
foreach(objectToWidget * obj, objOfInterest) {
if (obj->object) {
connect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection);
}
}
}
/**
* Called when an uav object is updated
* @param obj pointer to the object whitch has just been updated
@ -582,8 +587,7 @@ bool ConfigTaskWidget::allObjectsUpdated()
{
qDebug() << "ConfigTaskWidge:allObjectsUpdated called";
bool ret = true;
foreach(UAVObject *obj, objectUpdates.keys())
{
foreach(UAVObject * obj, objectUpdates.keys()) {
ret = ret & objectUpdates[obj];
}
qDebug() << "Returned:" << ret;
@ -598,15 +602,13 @@ void ConfigTaskWidget::addHelpButton(QPushButton *button, QString url)
{
helpButtonList.insert(button, url);
connect(button, SIGNAL(clicked()), this, SLOT(helpButtonPressed()));
}
/**
* Invalidates all the uav objects "is updated" flag
*/
void ConfigTaskWidget::invalidateObjects()
{
foreach(UAVObject *obj, objectUpdates.keys())
{
foreach(UAVObject * obj, objectUpdates.keys()) {
objectUpdates[obj] = false;
}
}
@ -615,35 +617,36 @@ void ConfigTaskWidget::invalidateObjects()
*/
void ConfigTaskWidget::apply()
{
if(smartsave)
if (smartsave) {
smartsave->apply();
}
}
/**
* SLOT call this to save changes to uav objects
*/
void ConfigTaskWidget::save()
{
if(smartsave)
if (smartsave) {
smartsave->save();
}
}
/**
* Adds a new shadow widget
* shadow widgets are widgets whitch have a relation to an object already present on the framework pool i.e. already added trough addUAVObjectToWidgetRelation
* This function doesn't have to be used directly, addUAVObjectToWidgetRelation will call it if a previous relation exhists.
* @return returns false if the shadow widget relation failed to be added (no previous relation exhisted)
*/
bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited,QList<int>* defaultReloadGroups,quint32 instID)
bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited,
QList<int> *defaultReloadGroups, quint32 instID)
{
foreach(objectToWidget * oTw,objOfInterest)
{
if(!oTw->object || !oTw->widget || !oTw->field)
foreach(objectToWidget * oTw, objOfInterest) {
if (!oTw->object || !oTw->widget || !oTw->field) {
continue;
if(oTw->object->getName()==object && oTw->field->getName()==field && oTw->index==index && oTw->object->getInstID()==instID)
{
}
if (oTw->object->getName() == object && oTw->field->getName() == field && oTw->index == index && oTw->object->getInstID() == instID) {
shadow *sh = NULL;
// prefer anything else to QLabel
if(qobject_cast<QLabel *>(oTw->widget) && !qobject_cast<QLabel *>(widget))
{
if (qobject_cast<QLabel *>(oTw->widget) && !qobject_cast<QLabel *>(widget)) {
sh = new shadow;
sh->isLimited = oTw->isLimited;
sh->scale = oTw->scale;
@ -653,8 +656,7 @@ bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *w
oTw->widget = widget;
}
// prefer QDoubleSpinBox to anything else
else if(!qobject_cast<QDoubleSpinBox *>(oTw->widget) && qobject_cast<QDoubleSpinBox *>(widget))
{
else if (!qobject_cast<QDoubleSpinBox *>(oTw->widget) && qobject_cast<QDoubleSpinBox *>(widget)) {
sh = new shadow;
sh->isLimited = oTw->isLimited;
sh->scale = oTw->scale;
@ -662,9 +664,7 @@ bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *w
oTw->isLimited = isLimited;
oTw->scale = scale;
oTw->widget = widget;
}
else
{
} else {
sh = new shadow;
sh->isLimited = isLimited;
sh->scale = scale;
@ -673,8 +673,9 @@ bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *w
shadowsList.insert(widget, oTw);
oTw->shadowsList.append(sh);
connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged()));
if(defaultReloadGroups)
if (defaultReloadGroups) {
addWidgetToDefaultReloadGroups(widget, defaultReloadGroups);
}
loadWidgetLimits(widget, oTw->field, oTw->index, isLimited, scale);
return true;
}
@ -689,119 +690,116 @@ void ConfigTaskWidget::autoLoadWidgets()
{
QPushButton *saveButtonWidget = NULL;
QPushButton *applyButtonWidget = NULL;
foreach(QWidget * widget,this->findChildren<QWidget*>())
{
foreach(QWidget * widget, this->findChildren<QWidget *>()) {
QVariant info = widget->property("objrelation");
if(info.isValid())
{
if (info.isValid()) {
uiRelationAutomation uiRelation;
uiRelation.buttonType = none;
uiRelation.scale = 1;
uiRelation.element = QString();
uiRelation.haslimits = false;
foreach(QString str, info.toStringList())
{
foreach(QString str, info.toStringList()) {
QString prop = str.split(":").at(0);
QString value = str.split(":").at(1);
if(prop== "objname")
if (prop == "objname") {
uiRelation.objname = value;
else if(prop== "fieldname")
} else if (prop == "fieldname") {
uiRelation.fieldname = value;
else if(prop=="element")
} else if (prop == "element") {
uiRelation.element = value;
else if(prop== "scale")
{
if(value=="null")
} else if (prop == "scale") {
if (value == "null") {
uiRelation.scale = 1;
else
} else {
uiRelation.scale = value.toDouble();
}
else if(prop== "haslimits")
{
if(value=="yes")
} else if (prop == "haslimits") {
if (value == "yes") {
uiRelation.haslimits = true;
else
} else {
uiRelation.haslimits = false;
}
else if(prop== "button")
{
if(value=="save")
} else if (prop == "button") {
if (value == "save") {
uiRelation.buttonType = save_button;
else if(value=="apply")
} else if (value == "apply") {
uiRelation.buttonType = apply_button;
else if(value=="reload")
} else if (value == "reload") {
uiRelation.buttonType = reload_button;
else if(value=="default")
} else if (value == "default") {
uiRelation.buttonType = default_button;
else if(value=="help")
} else if (value == "help") {
uiRelation.buttonType = help_button;
}
else if(prop== "buttongroup")
{
foreach(QString s,value.split(","))
{
} else if (prop == "buttongroup") {
foreach(QString s, value.split(",")) {
uiRelation.buttonGroup.append(s.toInt());
}
}
else if(prop=="url")
} else if (prop == "url") {
uiRelation.url = str.mid(str.indexOf(":") + 1);
}
if(!uiRelation.buttonType==none)
{
}
if (!uiRelation.buttonType == none) {
QPushButton *button = NULL;
switch(uiRelation.buttonType)
{
switch (uiRelation.buttonType) {
case save_button:
saveButtonWidget = qobject_cast<QPushButton *>(widget);
if(saveButtonWidget)
if (saveButtonWidget) {
addApplySaveButtons(NULL, saveButtonWidget);
}
break;
case apply_button:
applyButtonWidget = qobject_cast<QPushButton *>(widget);
if(applyButtonWidget)
if (applyButtonWidget) {
addApplySaveButtons(applyButtonWidget, NULL);
}
break;
case default_button:
button = qobject_cast<QPushButton *>(widget);
if(button)
if (button) {
addDefaultButton(button, uiRelation.buttonGroup.at(0));
}
break;
case reload_button:
button = qobject_cast<QPushButton *>(widget);
if(button)
if (button) {
addReloadButton(button, uiRelation.buttonGroup.at(0));
}
break;
case help_button:
button = qobject_cast<QPushButton *>(widget);
if(button)
if (button) {
addHelpButton(button, uiRelation.url);
}
break;
default:
break;
}
}
else
{
} else {
QWidget *wid = qobject_cast<QWidget *>(widget);
if(wid)
if (wid) {
addUAVObjectToWidgetRelation(uiRelation.objname, uiRelation.fieldname, wid, uiRelation.element, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup);
}
}
}
}
refreshWidgetsValues();
forceShadowUpdates();
foreach(objectToWidget * ow,objOfInterest)
{
if(ow->widget)
foreach(objectToWidget * ow, objOfInterest) {
if (ow->widget) {
qDebug() << "Master:" << ow->widget->objectName();
foreach(shadow * sh,ow->shadowsList)
{
if(sh->widget)
}
foreach(shadow * sh, ow->shadowsList) {
if (sh->widget) {
qDebug() << "Child" << sh->widget->objectName();
}
}
}
}
/**
* Adds a widget to a list of default/reload groups
* default/reload groups are groups of widgets to be set with default or reloaded (values from persistent memory) when a defined button is pressed
@ -810,29 +808,23 @@ void ConfigTaskWidget::autoLoadWidgets()
*/
void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> *groups)
{
foreach(objectToWidget * oTw,objOfInterest)
{
foreach(objectToWidget * oTw, objOfInterest) {
bool addOTW = false;
if(oTw->widget==widget)
if (oTw->widget == widget) {
addOTW = true;
else
{
foreach(shadow * sh, oTw->shadowsList)
{
if(sh->widget==widget)
} else {
foreach(shadow * sh, oTw->shadowsList) {
if (sh->widget == widget) {
addOTW = true;
}
}
if(addOTW)
{
foreach(int i,*groups)
{
if(defaultReloadGroups.contains(i))
{
}
if (addOTW) {
foreach(int i, *groups) {
if (defaultReloadGroups.contains(i)) {
defaultReloadGroups.value(i)->append(oTw);
}
else
{
} else {
defaultReloadGroups.insert(i, new QList<objectToWidget *>());
defaultReloadGroups.value(i)->append(oTw);
}
@ -868,11 +860,12 @@ void ConfigTaskWidget::defaultButtonClicked()
{
int group = sender()->property("group").toInt();
emit defaultRequested(group);
QList<objectToWidget *> *list = defaultReloadGroups.value(group);
foreach(objectToWidget * oTw,*list)
{
if(!oTw->object || !oTw->field)
foreach(objectToWidget * oTw, *list) {
if (!oTw->object || !oTw->field) {
continue;
}
UAVDataObject *temp = ((UAVDataObject *)oTw->object)->dirtyClone();
setWidgetFromField(oTw->widget, temp->getField(oTw->field->getName()), oTw->index, oTw->scale, oTw->isLimited);
}
@ -882,12 +875,14 @@ void ConfigTaskWidget::defaultButtonClicked()
*/
void ConfigTaskWidget::reloadButtonClicked()
{
if(timeOut)
if (timeOut) {
return;
}
int group = sender()->property("group").toInt();
QList<objectToWidget *> *list = defaultReloadGroups.value(group, NULL);
if(!list)
if (!list) {
return;
}
ObjectPersistence *objper = dynamic_cast<ObjectPersistence *>(getObjectManager()->getObject(ObjectPersistence::NAME));
timeOut = new QTimer(this);
QEventLoop *eventLoop = new QEventLoop(this);
@ -895,17 +890,16 @@ void ConfigTaskWidget::reloadButtonClicked()
connect(objper, SIGNAL(objectUpdated(UAVObject *)), eventLoop, SLOT(quit()));
QList<temphelper> temp;
foreach(objectToWidget * oTw,*list)
{
if (oTw->object != NULL)
{
foreach(objectToWidget * oTw, *list) {
if (oTw->object != NULL) {
temphelper value;
value.objid = oTw->object->getObjID();
value.objinstid = oTw->object->getInstID();
if(temp.contains(value))
if (temp.contains(value)) {
continue;
else
} else {
temp.append(value);
}
ObjectPersistence::DataFields data;
data.Operation = ObjectPersistence::OPERATION_LOAD;
data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT;
@ -915,22 +909,20 @@ void ConfigTaskWidget::reloadButtonClicked()
objper->updated();
timeOut->start(500);
eventLoop->exec();
if(timeOut->isActive())
{
if (timeOut->isActive()) {
oTw->object->requestUpdate();
if(oTw->widget)
if (oTw->widget) {
setWidgetFromField(oTw->widget, oTw->field, oTw->index, oTw->scale, oTw->isLimited);
}
}
timeOut->stop();
}
}
if(eventLoop)
{
if (eventLoop) {
delete eventLoop;
eventLoop = NULL;
}
if(timeOut)
{
if (timeOut) {
delete timeOut;
timeOut = NULL;
}
@ -941,86 +933,56 @@ void ConfigTaskWidget::reloadButtonClicked()
*/
void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget *widget, const char *function)
{
if(!widget)
if (!widget) {
return;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
}
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
connect(cb, SIGNAL(currentIndexChanged(int)), this, function);
}
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
} else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
connect(cb, SIGNAL(valueChanged(int)), this, function);
}
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
{
} else if (MixerCurveWidget * cb = qobject_cast<MixerCurveWidget *>(widget)) {
connect(cb, SIGNAL(curveUpdated()), this, function);
}
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
{
} else if (QTableWidget * cb = qobject_cast<QTableWidget *>(widget)) {
connect(cb, SIGNAL(cellChanged(int, int)), this, function);
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
} else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
connect(cb, SIGNAL(valueChanged(int)), this, function);
}
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
} else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
connect(cb, SIGNAL(valueChanged(double)), this, function);
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
} else if (QCheckBox * cb = qobject_cast<QCheckBox *>(widget)) {
connect(cb, SIGNAL(stateChanged(int)), this, function);
}
else if(QPushButton * cb=qobject_cast<QPushButton *>(widget))
{
} else if (QPushButton * cb = qobject_cast<QPushButton *>(widget)) {
connect(cb, SIGNAL(clicked()), this, function);
}
else
} else {
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
}
}
/**
* Disconnects widgets "contents changed" signals to a slot
*/
void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function)
{
if(!widget)
if (!widget) {
return;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
}
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
disconnect(cb, SIGNAL(currentIndexChanged(int)), this, function);
}
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
} else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
disconnect(cb, SIGNAL(valueChanged(int)), this, function);
}
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
{
} else if (MixerCurveWidget * cb = qobject_cast<MixerCurveWidget *>(widget)) {
disconnect(cb, SIGNAL(curveUpdated()), this, function);
}
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
{
} else if (QTableWidget * cb = qobject_cast<QTableWidget *>(widget)) {
disconnect(cb, SIGNAL(cellChanged(int, int)), this, function);
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
} else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
disconnect(cb, SIGNAL(valueChanged(int)), this, function);
}
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
} else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
disconnect(cb, SIGNAL(valueChanged(double)), this, function);
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
} else if (QCheckBox * cb = qobject_cast<QCheckBox *>(widget)) {
disconnect(cb, SIGNAL(stateChanged(int)), this, function);
}
else if(QPushButton * cb=qobject_cast<QPushButton *>(widget))
{
} else if (QPushButton * cb = qobject_cast<QPushButton *>(widget)) {
disconnect(cb, SIGNAL(clicked()), this, function);
}
else
} else {
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
}
}
/**
* Sets a widget value from an UAVObject field
@ -1032,11 +994,11 @@ void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget * widget,const char
*/
bool ConfigTaskWidget::setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale)
{
if(!widget || !field)
if (!widget || !field) {
return false;
}
QVariant ret = getVariantFromWidget(widget, scale, field->getUnits());
if(ret.isValid())
{
if (ret.isValid()) {
field->setValue(ret, index);
return true;
}
@ -1053,28 +1015,17 @@ bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * fiel
*/
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, QString units)
{
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
return (QString)cb->currentText();
}
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
} else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
return (double)(cb->value() * scale);
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
} else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
return (double)(cb->value() * scale);
}
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
} else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
return (double)(cb->value() * scale);
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
} else if (QCheckBox * cb = qobject_cast<QCheckBox *>(widget)) {
return (QString)(cb->isChecked() ? "TRUE" : "FALSE");
}
else if(QLineEdit * cb=qobject_cast<QLineEdit *>(widget))
{
} else if (QLineEdit * cb = qobject_cast<QLineEdit *>(widget)) {
QString value = (QString)cb->displayText();
if (units == "hex") {
bool ok;
@ -1082,10 +1033,10 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, Q
} else {
return value;
}
}
else
} else {
return QVariant();
}
}
/**
* Sets a widget from a variant
* @param widget pointer for the widget to set
@ -1096,42 +1047,30 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, Q
*/
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units)
{
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
cb->setCurrentIndex(cb->findText(value.toString()));
return true;
}
else if(QLabel * cb=qobject_cast<QLabel *>(widget))
{
if(scale==0)
} else if (QLabel * cb = qobject_cast<QLabel *>(widget)) {
if (scale == 0) {
cb->setText(value.toString());
else
} else {
cb->setText(QString::number((value.toDouble() / scale)));
return true;
}
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
return true;
} else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
cb->setValue((double)(value.toDouble() / scale));
return true;
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
} else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
cb->setValue((int)qRound(value.toDouble() / scale));
return true;
}
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
} else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
cb->setValue((int)qRound(value.toDouble() / scale));
return true;
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
} else if (QCheckBox * cb = qobject_cast<QCheckBox *>(widget)) {
bool bvalue = value.toString() == "TRUE";
cb->setChecked(bvalue);
return true;
}
else if(QLineEdit * cb=qobject_cast<QLineEdit *>(widget))
{
} else if (QLineEdit * cb = qobject_cast<QLineEdit *>(widget)) {
if ((scale == 0) || (scale == 1)) {
if (units == "hex") {
cb->setText(QString::number(value.toUInt(), 16).toUpper());
@ -1142,10 +1081,10 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou
cb->setText(QString::number((value.toDouble() / scale)));
}
return true;
}
else
} else {
return false;
}
}
/**
* Sets a widget from a variant
@ -1170,82 +1109,62 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou
*/
bool ConfigTaskWidget::setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits)
{
if(!widget || !field)
if (!widget || !field) {
return false;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
if(cb->count()==0)
}
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
if (cb->count() == 0) {
loadWidgetLimits(cb, field, index, hasLimits, scale);
}
}
QVariant var = field->getValue(index);
checkWidgetsLimits(widget, field, index, hasLimits, var, scale);
bool ret = setWidgetFromVariant(widget, var, scale, field->getUnits());
if(ret)
if (ret) {
return true;
else
{
} else {
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
return false;
}
}
void ConfigTaskWidget::checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale)
{
if(!hasLimits)
if (!hasLimits) {
return;
if(!field->isWithinLimits(value,index,currentBoard))
{
if(!widget->property("styleBackup").isValid())
}
if (!field->isWithinLimits(value, index, currentBoard)) {
if (!widget->property("styleBackup").isValid()) {
widget->setProperty("styleBackup", widget->styleSheet());
}
widget->setStyleSheet(outOfLimitsStyle);
widget->setProperty("wasOverLimits", (bool)true);
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
if(cb->findText(value.toString())==-1)
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
if (cb->findText(value.toString()) == -1) {
cb->addItem(value.toString());
}
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
if((double)(value.toDouble()/scale)>cb->maximum())
{
} else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
if ((double)(value.toDouble() / scale) > cb->maximum()) {
cb->setMaximum((double)(value.toDouble() / scale));
}
else if((double)(value.toDouble()/scale)<cb->minimum())
{
} else if ((double)(value.toDouble() / scale) < cb->minimum()) {
cb->setMinimum((double)(value.toDouble() / scale));
}
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
if((int)qRound(value.toDouble()/scale)>cb->maximum())
{
} else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
if ((int)qRound(value.toDouble() / scale) > cb->maximum()) {
cb->setMaximum((int)qRound(value.toDouble() / scale));
} else if ((int)qRound(value.toDouble() / scale) < cb->minimum()) {
cb->setMinimum((int)qRound(value.toDouble() / scale));
}
else if((int)qRound(value.toDouble()/scale)<cb->minimum())
{
} else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
if ((int)qRound(value.toDouble() / scale) > cb->maximum()) {
cb->setMaximum((int)qRound(value.toDouble() / scale));
} else if ((int)qRound(value.toDouble() / scale) < cb->minimum()) {
cb->setMinimum((int)qRound(value.toDouble() / scale));
}
}
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
if((int)qRound(value.toDouble()/scale)>cb->maximum())
{
cb->setMaximum((int)qRound(value.toDouble()/scale));
}
else if((int)qRound(value.toDouble()/scale)<cb->minimum())
{
cb->setMinimum((int)qRound(value.toDouble()/scale));
}
}
}
else if(widget->property("wasOverLimits").isValid())
{
if(widget->property("wasOverLimits").toBool())
{
} else if (widget->property("wasOverLimits").isValid()) {
if (widget->property("wasOverLimits").toBool()) {
widget->setProperty("wasOverLimits", (bool)false);
if(widget->property("styleBackup").isValid())
{
if (widget->property("styleBackup").isValid()) {
QString style = widget->property("styleBackup").toString();
widget->setStyleSheet(style);
}
@ -1256,60 +1175,56 @@ void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * fiel
void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double scale)
{
if(!widget || !field)
if (!widget || !field) {
return;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
}
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
cb->clear();
QStringList option = field->getOptions();
if(hasLimits)
{
foreach(QString str,option)
{
if(field->isWithinLimits(str,index,currentBoard))
if (hasLimits) {
foreach(QString str, option) {
if (field->isWithinLimits(str, index, currentBoard)) {
cb->addItem(str);
}
}
else
} else {
cb->addItems(option);
}
if(!hasLimits)
}
if (!hasLimits) {
return;
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
if(field->getMaxLimit(index).isValid())
{
} else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
if (field->getMaxLimit(index).isValid()) {
cb->setMaximum((double)(field->getMaxLimit(index, currentBoard).toDouble() / scale));
}
if(field->getMinLimit(index,currentBoard).isValid())
{
if (field->getMinLimit(index, currentBoard).isValid()) {
cb->setMinimum((double)(field->getMinLimit(index, currentBoard).toDouble() / scale));
}
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
if(field->getMaxLimit(index,currentBoard).isValid())
{
} else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
if (field->getMaxLimit(index, currentBoard).isValid()) {
cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale));
}
if(field->getMinLimit(index,currentBoard).isValid())
{
if (field->getMinLimit(index, currentBoard).isValid()) {
cb->setMinimum((int)qRound(field->getMinLimit(index, currentBoard).toDouble() / scale));
}
}
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
if(field->getMaxLimit(index,currentBoard).isValid())
{
} else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
if (field->getMaxLimit(index, currentBoard).isValid()) {
cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale));
}
if(field->getMinLimit(index,currentBoard).isValid())
{
if (field->getMinLimit(index, currentBoard).isValid()) {
cb->setMinimum((int)(field->getMinLimit(index, currentBoard).toDouble() / scale));
}
}
}
void ConfigTaskWidget::updateEnableControls()
{
TelemetryManager *telMngr = pm->getObject<TelemetryManager>();
Q_ASSERT(telMngr);
enableControls(telMngr->isConnected());
}
void ConfigTaskWidget::disableMouseWheelEvents()
{
// Disable mouse wheel events
@ -1327,13 +1242,13 @@ void ConfigTaskWidget::disableMouseWheelEvents()
}
}
bool ConfigTaskWidget::eventFilter( QObject * obj, QEvent * evt ) {
bool ConfigTaskWidget::eventFilter(QObject *obj, QEvent *evt)
{
// Filter all wheel events, and ignore them
if (evt->type() == QEvent::Wheel &&
(qobject_cast<QAbstractSpinBox *>(obj) ||
qobject_cast<QComboBox *>(obj) ||
qobject_cast<QAbstractSlider*>( obj ) ))
{
qobject_cast<QAbstractSlider *>(obj))) {
evt->ignore();
return true;
}

View File

@ -48,19 +48,16 @@
#include <QUrl>
#include <QEvent>
class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget: public QWidget
{
class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget : public QWidget {
Q_OBJECT
public:
struct shadow
{
struct shadow {
QWidget *widget;
double scale;
bool isLimited;
};
struct objectToWidget
{
struct objectToWidget {
UAVObject *object;
UAVObjectField *field;
QWidget *widget;
@ -68,7 +65,8 @@ public:
double scale;
bool isLimited;
QList<shadow *> shadowsList;
QString getUnits() const {
QString getUnits() const
{
if (field) {
return field->getUnits();
}
@ -76,19 +74,17 @@ public:
}
};
struct temphelper
{
struct temphelper {
quint32 objid;
quint32 objinstid;
bool operator==(const temphelper & lhs)
{
return (lhs.objid==this->objid && lhs.objinstid==this->objinstid);
return lhs.objid == this->objid && lhs.objinstid == this->objinstid;
}
};
enum buttonTypeEnum { none, save_button, apply_button, reload_button, default_button, help_button };
struct uiRelationAutomation
{
struct uiRelationAutomation {
QString objname;
QString fieldname;
QString element;
@ -141,7 +137,10 @@ public:
void setDirty(bool value);
bool allObjectsUpdated();
void setOutOfLimitsStyle(QString style){outOfLimitsStyle=style;}
void setOutOfLimitsStyle(QString style)
{
outOfLimitsStyle = style;
}
void addHelpButton(QPushButton *button, QString url);
void forceShadowUpdates();
void forceConnectedState();
@ -195,6 +194,7 @@ private:
void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale);
QString outOfLimitsStyle;
QTimer *timeOut;
protected slots:
virtual void disableObjUpdates();
virtual void enableObjUpdates();
@ -207,6 +207,7 @@ protected slots:
protected:
virtual void enableControls(bool enable);
void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale);
void updateEnableControls();
};
#endif // CONFIGTASKWIDGET_H

View File

@ -43,17 +43,15 @@ MixerNode::MixerNode(MixerCurveWidget *graphWidget)
setFlag(ItemSendsGeometryChanges);
setCacheMode(DeviceCoordinateCache);
setZValue(-1);
cmdActive = false;
vertical = false;
cmdNode = false;
cmdToggle = true;
drawNode = true;
drawText = true;
posColor0 = "#1c870b"; //greenish?
posColor1 = "#116703"; //greenish?
negColor0 = "#aa0000"; //red
negColor1 = "#aa0000"; //red
positiveColor = "#609FF2"; //blueish?
neutralColor = "#14CE24"; //greenish?
negativeColor = "#EF5F5F"; //redish?
disabledColor = "#dddddd";
disabledTextColor = "#aaaaaa";
}
void MixerNode::addEdge(Edge *edge)
@ -70,7 +68,7 @@ QList<Edge *> MixerNode::edges() const
QRectF MixerNode::boundingRect() const
{
return cmdNode ? QRectF(-4, -4, 15, 10) : QRectF(-13, -13, 26, 26);
return QRectF(-13, -13, 26, 26);
}
QPainterPath MixerNode::shape() const
@ -82,48 +80,50 @@ QPainterPath MixerNode::shape() const
void MixerNode::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *)
{
QString text = cmdNode ? cmdText : QString().sprintf("%.2f", value());
QString text = QString().sprintf("%.2f", value());
painter->setFont(graph->font());
if (drawNode) {
QRadialGradient gradient(-3, -3, 10);
QColor color;
if (value() < 0) {
color = negativeColor;
}
else if (value() == 0) {
color = neutralColor;
}
else {
color = positiveColor;
}
if (option->state & QStyle::State_Sunken) {
gradient.setCenter(3, 3);
gradient.setFocalPoint(3, 3);
gradient.setColorAt(1, Qt::darkBlue);
gradient.setColorAt(0, Qt::darkBlue);
QColor selColor = color.darker();
gradient.setColorAt(1, selColor.darker());
gradient.setColorAt(0, selColor);
} else {
if (cmdNode) {
gradient.setColorAt(0, cmdActive ? posColor0 : negColor0);
gradient.setColorAt(1, cmdActive ? posColor1 : negColor1);
}
else {
if (value() < 0) {
gradient.setColorAt(0, negColor0);
gradient.setColorAt(1, negColor1);
}
else {
gradient.setColorAt(0, posColor0);
gradient.setColorAt(1, posColor1);
}
}
gradient.setColorAt(0, graph->isEnabled() ? color : disabledColor);
gradient.setColorAt(1, graph->isEnabled() ? color.darker() : disabledColor);
}
painter->setBrush(gradient);
painter->setPen(QPen(Qt::black, 0));
painter->setPen(graph->isEnabled() ? QPen(Qt::black, 0) : QPen(disabledTextColor));
painter->drawEllipse(boundingRect());
if (!image.isNull())
if (!image.isNull()) {
painter->drawImage(boundingRect().adjusted(1, 1, -1, -1), image);
}
}
if (drawText) {
if(graph->isEnabled()) {
painter->setPen(QPen(drawNode ? Qt::white : Qt::black, 0));
if (cmdNode) {
painter->drawText(0,4,text);
}
else {
painter->drawText( (value() < 0) ? -13 : -11, 4, text);
} else {
painter->setPen(QPen(disabledTextColor));
}
painter->drawText( (value() < 0) ? -10 : -8, 3, text);
}
}
@ -131,13 +131,6 @@ void MixerNode::verticalMove(bool flag){
vertical = flag;
}
void MixerNode::commandNode(bool enable){
cmdNode = enable;
}
void MixerNode::commandText(QString text){
cmdText = text;
}
double MixerNode::value() {
double h = graph->sceneRect().height();
double ratio = (h - pos().y()) / h;
@ -186,10 +179,6 @@ QVariant MixerNode::itemChange(GraphicsItemChange change, const QVariant &val)
void MixerNode::mousePressEvent(QGraphicsSceneMouseEvent *event)
{
if (cmdNode) {
graph->cmdActivated(this);
//return;
}
update();
QGraphicsItem::mousePressEvent(event);
}

View File

@ -39,8 +39,7 @@ QT_BEGIN_NAMESPACE
class QGraphicsSceneMouseEvent;
QT_END_NAMESPACE
class MixerNode : public QObject,public QGraphicsItem
{
class MixerNode : public QObject, public QGraphicsItem {
Q_OBJECT
public:
MixerNode(MixerCurveWidget *graphWidget);
@ -48,27 +47,37 @@ public:
QList<Edge *> edges() const;
enum { Type = UserType + 10 };
int type() const { return Type; }
void setName(QString name) { cmdName = name; }
const QString& getName() { return cmdName; }
int type() const
{
return Type;
}
void verticalMove(bool flag);
void commandNode(bool enable);
void commandText(QString text);
int getCommandIndex() { return index; }
void setCommandIndex(int idx) { index = idx; }
bool getCommandActive() { return cmdActive; }
void setCommandActive(bool enable) { cmdActive = enable; }
void setToggle(bool enable) { cmdToggle = enable; }
bool getToggle() { return cmdToggle; }
void setPositiveColor(QColor color = "#609FF2")
{
positiveColor = color;
}
void setPositiveColor(QString color0 = "#00ff00", QString color1 = "#00ff00") { posColor0 = color0; posColor1 = color1; }
void setNegativeColor(QString color0 = "#ff0000", QString color1 = "#ff0000") { negColor0 = color0; negColor1 = color1; }
void setImage(QImage img) { image = img; }
void setDrawNode(bool draw) { drawNode = draw; }
void setDrawText(bool draw) { drawText = draw; }
void setNegativeColor(QColor color = "#EF5F5F")
{
negativeColor = color;
}
void setImage(QImage img)
{
image = img;
}
void setDrawNode(bool draw)
{
drawNode = draw;
}
void setDrawText(bool draw)
{
drawText = draw;
}
QRectF boundingRect() const;
QPainterPath shape() const;
@ -76,9 +85,6 @@ public:
double value();
signals:
void commandActivated(QString text);
protected:
QVariant itemChange(GraphicsItemChange change, const QVariant &val);
@ -89,22 +95,19 @@ private:
QList<Edge *> edgeList;
QPointF newPos;
MixerCurveWidget *graph;
QString posColor0;
QString posColor1;
QString negColor0;
QString negColor1;
QColor positiveColor;
QColor neutralColor;
QColor negativeColor;
QColor disabledColor;
QColor disabledTextColor;
QImage image;
bool vertical;
QString cmdName;
bool cmdActive;
bool cmdNode;
bool cmdToggle;
QString cmdText;
bool drawNode;
bool drawText;
int index;
};
#endif // MIXERCURVEPOINT_H

View File

@ -66,286 +66,42 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent)
plot = new QGraphicsSvgItem();
renderer->load(QString(":/uavobjectwidgetutils/images/curve-bg.svg"));
plot->setSharedRenderer(renderer);
//plot->setElementId("map");
scene->addItem(plot);
plot->setZValue(-1);
scene->setSceneRect(plot->boundingRect());
setScene(scene);
posColor0 = "#1c870b"; //greenish?
posColor1 = "#116703"; //greenish?
negColor0 = "#ff0000"; //red
negColor1 = "#ff0000"; //red
// commmand nodes
// reset
MixerNode* node = getCommandNode(0);
node->setName("Reset");
node->setToolTip("Reset Curve to Defaults");
node->setToggle(false);
node->setPositiveColor("#ffffff", "#ffffff"); //white
node->setNegativeColor("#ffffff", "#ffffff");
scene->addItem(node);
// linear
node = getCommandNode(1);
node->setName("Linear");
node->setToolTip("Generate a Linear Curve");
QImage img = QImage(":/core/images/curve_linear.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText("/");
scene->addItem(node);
// log
node = getCommandNode(2);
node->setName("Log");
node->setToolTip("Generate a Logarithmic Curve");
img = QImage(":/core/images/curve_log.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText("(");
scene->addItem(node);
// exp
node = getCommandNode(3);
node->setName("Exp");
node->setToolTip("Generate an Exponential Curve");
img = QImage(":/core/images/curve_exp.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText(")");
scene->addItem(node);
// flat
node = getCommandNode(4);
node->setName("Flat");
node->setToolTip("Generate a Flat Curve");
img = QImage(":/core/images/curve_flat.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText("--");
scene->addItem(node);
// step
node = getCommandNode(5);
node->setName("Step");
node->setToolTip("Generate a Stepped Curve");
img = QImage(":/core/images/curve_step.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText("z");
scene->addItem(node);
// curve min/max nodes
node = getCommandNode(6);
node->setName("MinPlus");
node->setToolTip("Increase Curve Minimum");
img = QImage(":/core/images/curve_plus.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText("+");
node->setToggle(false);
node->setPositiveColor("#00aa00", "#00aa00"); //green
node->setNegativeColor("#00aa00", "#00aa00");
scene->addItem(node);
node = getCommandNode(7);
node->setName("MinMinus");
node->setToolTip("Decrease Curve Minimum");
img = QImage(":/core/images/curve_minus.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText("-");
node->setToggle(false);
node->setPositiveColor("#aa0000", "#aa0000"); //red
node->setNegativeColor("#aa0000", "#aa0000");
scene->addItem(node);
node = getCommandNode(8);
node->setName("MaxPlus");
node->setToolTip("Increase Curve Maximum");
img = QImage(":/core/images/curve_plus.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText("+");
node->setToggle(false);
node->setPositiveColor("#00aa00", "#00aa00"); //green
node->setNegativeColor("#00aa00", "#00aa00");
scene->addItem(node);
node = getCommandNode(9);
node->setName("MaxMinus");
node->setToolTip("Decrease Curve Maximum");
img = QImage(":/core/images/curve_plus.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText("-");
node->setToggle(false);
node->setPositiveColor("#aa0000", "#aa0000"); //red
node->setNegativeColor("#aa0000", "#aa0000");
scene->addItem(node);
node = getCommandNode(10);
node->setName("StepPlus");
node->setToolTip("Increase Step/Power Value");
img = QImage(":/core/images/curve_plus.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText("+");
node->setToggle(false);
node->setPositiveColor("#00aa00", "#00aa00"); //green
node->setNegativeColor("#00aa00", "#00aa00");
scene->addItem(node);
node = getCommandNode(11);
node->setName("StepMinus");
node->setToolTip("Decrease Step/Power Value");
img = QImage(":/core/images/curve_minus.png");
if (!img.isNull())
node->setImage(img);
else
node->commandText("-");
node->setToggle(false);
node->setPositiveColor("#aa0000", "#aa0000"); //red
node->setNegativeColor("#aa0000", "#aa0000");
scene->addItem(node);
node = getCommandNode(12);
node->setName("StepValue");
node->setDrawNode(false);
node->setToolTip("Current Step/Power Value");
node->setToggle(false);
node->setPositiveColor("#0000aa", "#0000aa"); //blue
node->setNegativeColor("#0000aa", "#0000aa");
scene->addItem(node);
// commands toggle
node = getCommandNode(13);
node->setName("Commands");
node->setToolTip("Toggle Command Buttons On/Off");
node->setToggle(true);
node->setPositiveColor("#00aa00", "#00aa00"); //greenish
node->setNegativeColor("#000000", "#000000");
scene->addItem(node);
// popup
node = getCommandNode(14);
node->setName("Popup");
node->setToolTip("Advanced Mode...");
node->commandText("");
node->setToggle(false);
node->setPositiveColor("#ff0000", "#ff0000"); //red
node->setNegativeColor("#ff0000", "#ff0000");
scene->addItem(node);
resizeCommands();
initNodes(MixerCurveWidget::NODE_NUMELEM);
}
MixerCurveWidget::~MixerCurveWidget()
{
while (!nodePool.isEmpty())
delete nodePool.takeFirst();
while (!edgePool.isEmpty())
delete edgePool.takeFirst();
while (!cmdNodePool.isEmpty())
delete cmdNodePool.takeFirst();
while (!nodeList.isEmpty()) {
delete nodeList.takeFirst();
}
MixerNode* MixerCurveWidget::getCommandNode(int index)
while (!edgeList.isEmpty()) {
delete edgeList.takeFirst();
}
}
void MixerCurveWidget::setPositiveColor(QString color)
{
MixerNode* node;
if (index >= 0 && index < cmdNodePool.count())
{
node = cmdNodePool.at(index);
}
else {
node = new MixerNode(this);
node->commandNode(true);
node->commandText("");
node->setCommandIndex(index);
node->setActive(false);
node->setPositiveColor("#aaaa00", "#aaaa00");
node->setNegativeColor("#1c870b", "#116703");
cmdNodePool.append(node);
}
return node;
}
MixerNode* MixerCurveWidget::getNode(int index)
{
MixerNode* node;
if (index >= 0 && index < nodePool.count())
{
node = nodePool.at(index);
}
else {
node = new MixerNode(this);
nodePool.append(node);
}
return node;
}
Edge* MixerCurveWidget::getEdge(int index, MixerNode* sourceNode, MixerNode* destNode)
{
Edge* edge;
if (index >= 0 && index < edgePool.count())
{
edge = edgePool.at(index);
edge->setSourceNode(sourceNode);
edge->setDestNode(destNode);
}
else {
edge = new Edge(sourceNode,destNode);
edgePool.append(edge);
}
return edge;
}
void MixerCurveWidget::setPositiveColor(QString color0, QString color1)
{
posColor0 = color0;
posColor1 = color1;
for (int i=0; i<nodePool.count(); i++) {
MixerNode* node = nodePool.at(i);
node->setPositiveColor(color0, color1);
}
}
void MixerCurveWidget::setNegativeColor(QString color0, QString color1)
{
negColor0 = color0;
negColor1 = color1;
for (int i=0; i<nodePool.count(); i++) {
MixerNode* node = nodePool.at(i);
node->setNegativeColor(color0, color1);
for (int i=0; i < nodeList.count(); i++) {
MixerNode* node = nodeList.at(i);
node->setPositiveColor(color);
}
}
void MixerCurveWidget::setNegativeColor(QString color)
{
for (int i=0; i < nodeList.count(); i++) {
MixerNode* node = nodeList.at(i);
node->setNegativeColor(color);
}
}
/**
Init curve: create a (flat) curve with a specified number of points.
@ -370,9 +126,11 @@ void MixerCurveWidget::initNodes(int numPoints)
foreach(Edge *edge, node->edges()) {
if (edge->sourceNode() == node) {
scene()->removeItem(edge);
delete edge;
}
}
scene()->removeItem(node);
delete node;
}
nodeList.clear();
@ -382,7 +140,7 @@ void MixerCurveWidget::initNodes(int numPoints)
MixerNode* prevNode = 0;
for (int i=0; i < numPoints; i++) {
MixerNode *node = getNode(i);
MixerNode *node = new MixerNode(this);
nodeList.append(node);
scene()->addItem(node);
@ -390,7 +148,7 @@ void MixerCurveWidget::initNodes(int numPoints)
node->setPos(0,0);
if (prevNode) {
scene()->addItem(getEdge(i, prevNode, node));
scene()->addItem(new Edge(prevNode, node));
}
prevNode = node;
@ -469,7 +227,6 @@ void MixerCurveWidget::showEvent(QShowEvent *event)
// the result is usually a ahrsbargraph that is way too small.
QRectF rect = plot->boundingRect();
resizeCommands();
fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio);
}
@ -478,61 +235,17 @@ void MixerCurveWidget::resizeEvent(QResizeEvent* event)
Q_UNUSED(event);
QRectF rect = plot->boundingRect();
resizeCommands();
fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio);
}
void MixerCurveWidget::resizeCommands()
void MixerCurveWidget::changeEvent(QEvent *event)
{
QRectF rect = plot->boundingRect();
MixerNode* node;
//popup
node = getCommandNode(14);
node->setPos((rect.left() + rect.width() / 2) - 20, rect.height() + 10);
//reset
node = getCommandNode(0);
node->setPos((rect.left() + rect.width() / 2) + 20, rect.height() + 10);
//commands on/off
node = getCommandNode(13);
node->setPos(rect.right() - 15, rect.bottomRight().x() - 14);
for (int i = 1; i<6; i++) {
node = getCommandNode(i);
//bottom right of widget
node->setPos(rect.right() - 130 + (i * 18), rect.bottomRight().x() - 14);
QGraphicsView::changeEvent(event);
if(event->type() == QEvent::EnabledChange) {
foreach (MixerNode *node, nodeList) {
node->update();
}
}
//curveminplus
node = getCommandNode(6);
node->setPos(rect.bottomLeft().x() + 15, rect.bottomLeft().y() - 10);
//curveminminus
node = getCommandNode(7);
node->setPos(rect.bottomLeft().x() + 15, rect.bottomLeft().y() + 5);
//curvemaxplus
node = getCommandNode(8);
node->setPos(rect.topRight().x() - 20, rect.topRight().y() - 7);
//curvemaxminus
node = getCommandNode(9);
node->setPos(rect.topRight().x() - 20, rect.topRight().y() + 8);
//stepplus
node = getCommandNode(10);
node->setPos(rect.bottomRight().x() - 40, rect.bottomRight().y() + 5);
//stepminus
node = getCommandNode(11);
node->setPos(rect.bottomRight().x() - 40, rect.bottomRight().y() + 15);
//step
node = getCommandNode(12);
node->setPos(rect.bottomRight().x() - 22, rect.bottomRight().y() + 9);
}
void MixerCurveWidget::itemMoved(double itemValue)
@ -575,87 +288,3 @@ double MixerCurveWidget::setRange(double min, double max)
return curveMax - curveMin;
}
MixerNode* MixerCurveWidget::getCmdNode(const QString& name)
{
MixerNode* node = 0;
for (int i=0; i<cmdNodePool.count(); i++) {
MixerNode* n = cmdNodePool.at(i);
if (n->getName() == name)
node = n;
}
return node;
}
void MixerCurveWidget::setCommandText(const QString& name, const QString& text)
{
for (int i=0; i<cmdNodePool.count(); i++) {
MixerNode* n = cmdNodePool.at(i);
if (n->getName() == name) {
n->commandText(text);
n->update();
}
}
}
void MixerCurveWidget::activateCommand(const QString& name)
{
for (int i=1; i<cmdNodePool.count()-2; i++) {
MixerNode* node = cmdNodePool.at(i);
node->setCommandActive(node->getName() == name);
node->update();
}
}
void MixerCurveWidget::showCommand(const QString& name, bool show)
{
MixerNode* node = getCmdNode(name);
if (node) {
if (show)
node->show();
else
node->hide();
}
}
void MixerCurveWidget::showCommands(bool show)
{
for (int i=1; i<cmdNodePool.count()-2; i++) {
MixerNode* node = cmdNodePool.at(i);
if (show)
node->show();
else
node->hide();
node->update();
}
}
bool MixerCurveWidget::isCommandActive(const QString& name)
{
bool active = false;
MixerNode* node = getCmdNode(name);
if (node) {
active = node->getCommandActive();
}
return active;
}
void MixerCurveWidget::cmdActivated(MixerNode* node)
{
if (node->getToggle()) {
if (node->getName() == "Commands") {
node->setCommandActive(!node->getCommandActive());
showCommands(node->getCommandActive());
}
else {
for (int i=1; i<cmdNodePool.count()-2; i++) {
MixerNode* n = cmdNodePool.at(i);
n->setCommandActive(false);
n->update();
}
node->setCommandActive(true);
}
}
node->update();
emit commandActivated(node);
}

View File

@ -37,8 +37,7 @@
#include "mixercurveline.h"
#include "uavobjectwidgetutils_global.h"
class UAVOBJECTWIDGETUTILS_EXPORT MixerCurveWidget : public QGraphicsView
{
class UAVOBJECTWIDGETUTILS_EXPORT MixerCurveWidget : public QGraphicsView {
Q_OBJECT
public:
@ -58,55 +57,34 @@ public:
double getMax();
double setRange(double min, double max);
void cmdActivated(MixerNode* node);
void activateCommand(const QString& name);
bool isCommandActive(const QString& name);
void showCommand(const QString& name, bool show);
void showCommands(bool show);
MixerNode* getCmdNode(const QString& name);
void setCommandText(const QString& name, const QString& text);
static const int NODE_NUMELEM = 5;
signals:
void curveUpdated();
void curveMinChanged(double value);
void curveMaxChanged(double value);
void commandActivated(MixerNode* node);
private slots:
private:
QGraphicsSvgItem *plot;
QList<MixerNode*> nodePool;
QList<MixerNode*> cmdNodePool;
QList<Edge*> edgePool;
QList<Edge *> edgeList;
QList<MixerNode *> nodeList;
double curveMin;
double curveMax;
bool curveUpdating;
QString posColor0;
QString posColor1;
QString negColor0;
QString negColor1;
void initNodes(int numPoints);
MixerNode* getNode(int index);
MixerNode* getCommandNode(int index);
Edge* getEdge(int index, MixerNode* sourceNode, MixerNode* destNode);
void setPositiveColor(QString color0 = "#00ff00", QString color1 = "#00ff00");
void setNegativeColor(QString color0 = "#ff0000", QString color1 = "#ff0000");
void setPositiveColor(QString color);
void setNegativeColor(QString color);
void resizeCommands();
protected:
void showEvent(QShowEvent *event);
void resizeEvent(QResizeEvent *event);
void changeEvent(QEvent *event);
};
#endif /* MIXERCURVEWIDGET_H_ */

View File

@ -12,18 +12,23 @@ namespace Ui {
class PopupWidget;
}
class UAVOBJECTWIDGETUTILS_EXPORT PopupWidget : public QDialog
{
class UAVOBJECTWIDGETUTILS_EXPORT PopupWidget : public QDialog {
Q_OBJECT
public:
explicit PopupWidget(QWidget *parent = 0);
void popUp(QWidget *widget = 0);
void setWidget(QWidget *widget);
QWidget* getWidget() { return m_widget; }
QHBoxLayout* getLayout() { return m_layout; }
signals:
QWidget *getWidget()
{
return m_widget;
}
QHBoxLayout *getLayout()
{
return m_layout;
}
public slots:
bool close();

View File

@ -37,11 +37,12 @@
#include "uavobjectutilmanager.h"
#include <QObject>
#include <QDebug>
class smartSaveButton:public QObject
{
class smartSaveButton : public QObject {
enum buttonTypeEnum { save_button, apply_button };
public:
Q_OBJECT
public:
smartSaveButton();
void addButtons(QPushButton *save, QPushButton *apply);
@ -53,14 +54,17 @@ public:
void addApplyButton(QPushButton *apply);
void addSaveButton(QPushButton *save);
void resetIcons();
signals:
void preProcessOperations();
void saveSuccessfull();
void beginOp();
void endOp();
public slots:
void apply();
void save();
private slots:
void processClick();
void processOperation(QPushButton *button, bool save);
@ -75,10 +79,9 @@ private:
QEventLoop loop;
QList<UAVDataObject *> objects;
QMap<QPushButton *, buttonTypeEnum> buttonList;
protected:
public slots:
void enableControls(bool value);
};

View File

@ -8,6 +8,8 @@
<field name="PressureNoise" units="m" type="float" elements="1" defaultvalue="0.4"/>
<field name="AccelNoise" units="m/s^2" type="float" elements="1" defaultvalue="5"/>
<field name="AccelDrift" units="m/s^2" type="float" elements="1" defaultvalue="0.001"/>
<field name="ThrottleExp" units="" type="uint8" elements="1" defaultvalue="128"/>
<field name="ThrottleRate" units="m/s" type="uint8" elements="1" defaultvalue="5"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>