1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-20 10:54:14 +01:00

Merge branch 'next' into ins

Conflicts:
	flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj
This commit is contained in:
James Cotton 2011-10-26 13:18:44 -05:00
commit 0f8ae1e076
70 changed files with 2032 additions and 1014 deletions

View File

@ -1,5 +1,20 @@
Short summary of changes. For a complete list see the git log.
2011-10-20
Inputs can be remapped to outputs to allow up to 10 channels of control. The
receiver inputs remap as follows:
Receiver 3 because output channel 7
Receiver 4 because output channel 8
Receiver 5 because output channel 9
Receiver 6 because output channel 10
2011-10-11
Fix for the Mac telemetry rates and specifically how long enumeration took.
2011-10-08
Make the flash chip need to be have bad magic for a full second before erasing
settings. Should avoid random lost settings.
2011-09-12
Max rate now ONLY applies to attitude and axis lock mode. Manual rate is the
only term that limits the rate mode now (and in axis lock when you push stick
@ -56,3 +71,4 @@ selected from ManualControlSettings.InputMode and the aircraft must be rebooted
after changing this. Also for CopterControl the HwSettings object must
indicate which modules are connected to which ports. PPM currently not
working.

View File

@ -353,7 +353,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin
# Add jtag targets (program and wipe)
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE)))
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG)))
.PHONY: elf lss sym hex bin bino
elf: $(OUTDIR)/$(TARGET).elf

View File

@ -413,7 +413,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin
# Add jtag targets (program and wipe)
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE)))
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG)))
.PHONY: elf lss sym hex bin bino
elf: $(OUTDIR)/$(TARGET).elf

View File

@ -419,7 +419,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin
# Add jtag targets (program and wipe)
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE)))
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG)))
.PHONY: elf lss sym hex bin bino
elf: $(OUTDIR)/$(TARGET).elf

View File

@ -414,7 +414,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin
# Add jtag targets (program and wipe)
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE)))
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG)))
.PHONY: elf lss sym hex bin bino
elf: $(OUTDIR)/$(TARGET).elf

View File

@ -410,6 +410,133 @@ static const struct pios_tim_channel pios_tim_servoport_all_pins[] = {
},
};
static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = {
{
.timer = TIM4,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM4,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM4,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM1,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM3,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_4,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.remap = GPIO_PartialRemap_TIM3,
},
{
.timer = TIM2,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_2,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
// Receiver port pins
// S3-S6 inputs are used as outputs in this case
{
.timer = TIM3,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM3,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM2,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM2,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
};
#if defined(PIOS_INCLUDE_USART)
#include "pios_usart_priv.h"
@ -674,7 +801,7 @@ static const struct pios_spektrum_cfg pios_spektrum_flexi_cfg = {
#if defined(PIOS_INCLUDE_SBUS)
/*
* SBUS USART
* S.Bus USART
*/
#include <pios_sbus_priv.h>
@ -795,6 +922,22 @@ const struct pios_servo_cfg pios_servo_cfg = {
.num_channels = NELEMENTS(pios_tim_servoport_all_pins),
};
const struct pios_servo_cfg pios_servo_rcvr_cfg = {
.tim_oc_init = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
.TIM_OCPolarity = TIM_OCPolarity_High,
.TIM_OCNPolarity = TIM_OCPolarity_High,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
},
.channels = pios_tim_servoport_rcvrport_pins,
.num_channels = NELEMENTS(pios_tim_servoport_rcvrport_pins),
};
/*
* PPM Inputs
*/
@ -1025,7 +1168,7 @@ void PIOS_Board_Init(void) {
}
uint32_t pios_sbus_id;
if (PIOS_SBUS_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
PIOS_Assert(0);
}
@ -1190,6 +1333,7 @@ void PIOS_Board_Init(void) {
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_CC_RCVRPORT_PPM:
case HWSETTINGS_CC_RCVRPORT_PPMSERVO:
#if defined(PIOS_INCLUDE_PPM)
{
uint32_t pios_ppm_id;
@ -1219,7 +1363,17 @@ void PIOS_Board_Init(void) {
GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS
PIOS_Servo_Init(&pios_servo_cfg);
switch (hwsettings_rcvrport) {
case HWSETTINGS_CC_RCVRPORT_DISABLED:
case HWSETTINGS_CC_RCVRPORT_PWM:
case HWSETTINGS_CC_RCVRPORT_PPM:
PIOS_Servo_Init(&pios_servo_cfg);
break;
case HWSETTINGS_CC_RCVRPORT_PPMSERVO:
case HWSETTINGS_CC_RCVRPORT_SERVO:
PIOS_Servo_Init(&pios_servo_rcvr_cfg);
break;
}
#else
PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels));
#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */

View File

@ -456,7 +456,7 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm
break;
}
ReceiverActivityActiveGroupSet(&group);
ReceiverActivityActiveGroupSet((uint8_t*)&group);
ReceiverActivityActiveChannelSet(&channel);
activity_updated = true;
}

View File

@ -48,7 +48,6 @@
#include "taskinfo.h"
#include "watchdogstatus.h"
#include "taskmonitor.h"
#include "pios_config.h"
// Private constants
@ -114,6 +113,7 @@ int32_t SystemModInitialize(void)
// Must registers objects here for system thread because ObjectManager started in OpenPilotInit
SystemSettingsInitialize();
SystemStatsInitialize();
FlightStatusInitialize();
ObjectPersistenceInitialize();
#if defined(DIAGNOSTICS)
TaskInfoInitialize();

View File

@ -62,6 +62,14 @@
/* Stabilization options */
#define PIOS_QUATERNION_STABILIZATION
/* Alarm Thresholds */
#define HEAP_LIMIT_WARNING 4000
#define HEAP_LIMIT_CRITICAL 1000
#define IRQSTACK_LIMIT_WARNING 150
#define IRQSTACK_LIMIT_CRITICAL 80
#define CPULOAD_LIMIT_WARNING 80
#define CPULOAD_LIMIT_CRITICAL 95
/* GPS options */
#define PIOS_GPS_SETS_HOMELOCATION

View File

@ -147,7 +147,7 @@ static void TaskTesting(void *pvParameters)
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_SPEKTRUM_Get(0), PIOS_SPEKTRUM_Get(1), PIOS_SPEKTRUM_Get(2), PIOS_SPEKTRUM_Get(3), PIOS_SPEKTRUM_Get(4), PIOS_SPEKTRUM_Get(5), PIOS_SPEKTRUM_Get(6), PIOS_SPEKTRUM_Get(7));
#endif
#if defined(PIOS_INCLUDE_SBUS)
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_SBUS_Get(0), PIOS_SBUS_Get(1), PIOS_SBUS_Get(2), PIOS_SBUS_Get(3), PIOS_SBUS_Get(4), PIOS_SBUS_Get(5), PIOS_SBUS_Get(6), PIOS_SBUS_Get(7));
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_SBus_Get(0), PIOS_SBus_Get(1), PIOS_SBus_Get(2), PIOS_SBus_Get(3), PIOS_SBus_Get(4), PIOS_SBus_Get(5), PIOS_SBus_Get(6), PIOS_SBus_Get(7));
#endif
#if defined(PIOS_INCLUDE_PWM)
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u uS\r", PIOS_PWM_Get(0), PIOS_PWM_Get(1), PIOS_PWM_Get(2), PIOS_PWM_Get(3), PIOS_PWM_Get(4), PIOS_PWM_Get(5), PIOS_PWM_Get(6), PIOS_PWM_Get(7));

View File

@ -33,11 +33,19 @@
#include "attitudeactual.h"
#include "positionactual.h"
#include "velocityactual.h"
#include "manualcontrolsettings.h"
#if defined(PIOS_INCLUDE_RCVR)
#include "pios_rcvr_priv.h"
struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS];
uint32_t pios_rcvr_max_channel;
/* One slot per selectable receiver group.
* eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS
* NOTE: No slot in this map for NONE.
*/
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
#endif /* PIOS_INCLUDE_RCVR */
void Stack_Change() {
}

View File

@ -31,21 +31,24 @@
#ifndef PIOS_RCVR_H
#define PIOS_RCVR_H
struct pios_rcvr_channel_map {
uint32_t id;
uint8_t channel;
};
extern struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[];
struct pios_rcvr_driver {
void (*init)(uint32_t id);
int32_t (*read)(uint32_t id, uint8_t channel);
void (*init)(uint32_t id);
int32_t (*read)(uint32_t id, uint8_t channel);
};
/* Public Functions */
extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel);
/*! Define error codes for PIOS_RCVR_Get */
enum PIOS_RCVR_errors {
/*! Indicates that a failsafe condition or missing receiver detected for that channel */
PIOS_RCVR_TIMEOUT = 0,
/*! Channel is invalid for this driver (usually out of range supported) */
PIOS_RCVR_INVALID = -1,
/*! Indicates that the driver for this channel has not been initialized */
PIOS_RCVR_NODRIVER = -2
};
#endif /* PIOS_RCVR_H */
/**

View File

@ -21,32 +21,39 @@ static bool PIOS_RCVR_validate(struct pios_rcvr_dev * rcvr_dev)
}
#if defined(PIOS_INCLUDE_FREERTOS) && 0
static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
{
struct pios_rcvr_dev * rcvr_dev;
rcvr_dev = (struct pios_rcvr_dev *)malloc(sizeof(*rcvr_dev));
if (!rcvr_dev) return (NULL);
rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
return(rcvr_dev);
}
//static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
//{
// struct pios_rcvr_dev * rcvr_dev;
//
// rcvr_dev = (struct pios_rcvr_dev *)pvPortMalloc(sizeof(*rcvr_dev));
// if (!rcvr_dev) return (NULL);
//
// rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
// return(rcvr_dev);
//}
#else
static struct pios_rcvr_dev pios_rcvr_devs[PIOS_RCVR_MAX_DEVS];
static uint8_t pios_rcvr_num_devs;
static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
static uint32_t PIOS_RCVR_alloc(void)
{
struct pios_rcvr_dev * rcvr_dev;
if (pios_rcvr_num_devs >= PIOS_RCVR_MAX_DEVS) {
return (NULL);
return (PIOS_RCVR_MAX_DEVS+1);
}
rcvr_dev = &pios_rcvr_devs[pios_rcvr_num_devs++];
rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
return (rcvr_dev);
return (pios_rcvr_num_devs);
}
static struct pios_rcvr_dev * PIOS_RCVR_find_dev(uint32_t rcvr_dev_id)
{
if (!rcvr_dev_id) return NULL;
if (rcvr_dev_id>pios_rcvr_num_devs+1) return NULL;
return &pios_rcvr_devs[rcvr_dev_id-1];
}
#endif
/**
@ -56,35 +63,53 @@ static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
* \param[in] id
* \return < 0 if initialisation failed
*/
int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id)
int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, uint32_t lower_id)
{
PIOS_DEBUG_Assert(rcvr_id);
PIOS_DEBUG_Assert(driver);
uint32_t rcvr_dev_id;
struct pios_rcvr_dev * rcvr_dev;
rcvr_dev = (struct pios_rcvr_dev *) PIOS_RCVR_alloc();
rcvr_dev_id = PIOS_RCVR_alloc();
rcvr_dev = PIOS_RCVR_find_dev(rcvr_dev_id);
if (!rcvr_dev) goto out_fail;
rcvr_dev->driver = driver;
rcvr_dev->lower_id = lower_id;
*rcvr_id = pios_rcvr_num_devs - 1;
*rcvr_id = rcvr_dev_id;
return(0);
out_fail:
return(-1);
}
/**
* @brief Reads an input channel from the appropriate driver
* @param[in] rcvr_id driver to read from
* @param[in] channel channel to read
* @returns Unitless input value
* @retval PIOS_RCVR_TIMEOUT indicates a failsafe or timeout from that channel
* @retval PIOS_RCVR_INVALID invalid channel for this driver (usually out of range supported)
* @retval PIOS_RCVR_NODRIVER driver was not initialized
*/
int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel)
{
struct pios_rcvr_dev * rcvr_dev = &pios_rcvr_devs[rcvr_id];
// Publicly facing API uses channel 1 for first channel
if(channel == 0)
return PIOS_RCVR_INVALID;
else
channel--;
if (rcvr_id == 0)
return PIOS_RCVR_NODRIVER;
struct pios_rcvr_dev * rcvr_dev = PIOS_RCVR_find_dev(rcvr_id);
if (!PIOS_RCVR_validate(rcvr_dev)) {
/* Undefined RCVR port for this board (see pios_board.c) */
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
PIOS_DEBUG_Assert(rcvr_dev->driver->read);

View File

@ -194,7 +194,7 @@ static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail)
length = (udp_dev->tx_out_cb)(udp_dev->tx_out_context, udp_dev->tx_buffer, PIOS_UDP_RX_BUFFER_SIZE, NULL, &tx_need_yield);
rem = length;
while (rem>0) {
len = sendto(udp_dev->socket, udp_dev->tx_buffer, length, 0,
len = sendto(udp_dev->socket, udp_dev->tx_buffer+length-rem, rem, 0,
(struct sockaddr *) &udp_dev->client,
sizeof(udp_dev->client));
if (len<=0) {

View File

@ -227,6 +227,12 @@ extern uint32_t pios_com_telem_usb_id;
#define PIOS_SPEKTRUM_MAX_DEVS 2
#define PIOS_SPEKTRUM_NUM_INPUTS 12
//-------------------------
// Receiver S.Bus input
//-------------------------
#define PIOS_SBUS_MAX_DEVS 1
#define PIOS_SBUS_NUM_INPUTS (16+2)
//-------------------------
// Servo outputs
//-------------------------

View File

@ -200,6 +200,12 @@ extern uint32_t pios_com_aux_id;
#define PIOS_SPEKTRUM_MAX_DEVS 1
#define PIOS_SPEKTRUM_NUM_INPUTS 12
//-------------------------
// Receiver S.Bus input
//-------------------------
#define PIOS_SBUS_MAX_DEVS 0
#define PIOS_SBUS_NUM_INPUTS (16+2)
//-------------------------
// Servo outputs
//-------------------------

View File

@ -61,7 +61,7 @@ struct fileHeader {
#define OBJECT_TABLE_START 0x00000010
#define OBJECT_TABLE_END 0x00001000
#define SECTOR_SIZE 0x00001000
#define MAX_BADMAGIC 4
#define MAX_BADMAGIC 1000
/**
* @brief Initialize the flash object setting FS
@ -72,7 +72,7 @@ int32_t PIOS_FLASHFS_Init()
// Check for valid object table or create one
uint32_t object_table_magic;
uint8_t magic_fail_count = 0;
uint32_t magic_fail_count = 0;
bool magic_good = false;
while(!magic_good) {
@ -85,7 +85,7 @@ int32_t PIOS_FLASHFS_Init()
magic_fail_count = 0;
magic_good = true;
} else {
PIOS_DELAY_WaituS(100);
PIOS_DELAY_WaituS(1000);
}
}

View File

@ -2,13 +2,13 @@
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_SBUS Futaba S.Bus receiver functions
* @brief Code to read Futaba S.Bus input
* @addtogroup PIOS_SBus Futaba S.Bus receiver functions
* @brief Code to read Futaba S.Bus receiver serial stream
* @{
*
* @file pios_sbus.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief USART commands. Inits USARTs, controls USARTs & Interrupt handlers. (STM32 dependent)
* @brief Code to read Futaba S.Bus receiver serial stream
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
@ -34,44 +34,166 @@
#if defined(PIOS_INCLUDE_SBUS)
/* Provide a RCVR driver */
static int32_t PIOS_SBUS_Get(uint32_t rcvr_id, uint8_t channel);
/* Forward Declarations */
static int32_t PIOS_SBus_Get(uint32_t rcvr_id, uint8_t channel);
static uint16_t PIOS_SBus_RxInCallback(uint32_t context,
uint8_t *buf,
uint16_t buf_len,
uint16_t *headroom,
bool *need_yield);
static void PIOS_SBus_Supervisor(uint32_t sbus_id);
const struct pios_rcvr_driver pios_sbus_rcvr_driver = {
.read = PIOS_SBUS_Get,
};
/* Local Variables */
static uint16_t channel_data[SBUS_NUMBER_OF_CHANNELS];
static uint8_t received_data[SBUS_FRAME_LENGTH - 2];
static uint8_t receive_timer;
static uint8_t failsafe_timer;
static uint8_t frame_found;
const struct pios_rcvr_driver pios_sbus_rcvr_driver = {
.read = PIOS_SBus_Get,
};
static void PIOS_SBUS_Supervisor(uint32_t sbus_id);
enum pios_sbus_dev_magic {
PIOS_SBUS_DEV_MAGIC = 0x53427573,
};
/**
* reset_channels() function clears all channel data in case of
* lost signal or explicit failsafe flag from the S.Bus data stream
*/
static void reset_channels(void)
struct pios_sbus_state {
uint16_t channel_data[PIOS_SBUS_NUM_INPUTS];
uint8_t received_data[SBUS_FRAME_LENGTH - 2];
uint8_t receive_timer;
uint8_t failsafe_timer;
uint8_t frame_found;
uint8_t byte_count;
};
struct pios_sbus_dev {
enum pios_sbus_dev_magic magic;
const struct pios_sbus_cfg *cfg;
struct pios_sbus_state state;
};
/* Allocate S.Bus device descriptor */
#if defined(PIOS_INCLUDE_FREERTOS)
static struct pios_sbus_dev *PIOS_SBus_Alloc(void)
{
for (int i = 0; i < SBUS_NUMBER_OF_CHANNELS; i++) {
channel_data[i] = PIOS_RCVR_TIMEOUT;
struct pios_sbus_dev *sbus_dev;
sbus_dev = (struct pios_sbus_dev *)pvPortMalloc(sizeof(*sbus_dev));
if (!sbus_dev) return(NULL);
sbus_dev->magic = PIOS_SBUS_DEV_MAGIC;
return(sbus_dev);
}
#else
static struct pios_sbus_dev pios_sbus_devs[PIOS_SBUS_MAX_DEVS];
static uint8_t pios_sbus_num_devs;
static struct pios_sbus_dev *PIOS_SBus_Alloc(void)
{
struct pios_sbus_dev *sbus_dev;
if (pios_sbus_num_devs >= PIOS_SBUS_MAX_DEVS) {
return (NULL);
}
sbus_dev = &pios_sbus_devs[pios_sbus_num_devs++];
sbus_dev->magic = PIOS_SBUS_DEV_MAGIC;
return (sbus_dev);
}
#endif
/* Validate S.Bus device descriptor */
static bool PIOS_SBus_Validate(struct pios_sbus_dev *sbus_dev)
{
return (sbus_dev->magic == PIOS_SBUS_DEV_MAGIC);
}
/* Reset channels in case of lost signal or explicit failsafe receiver flag */
static void PIOS_SBus_ResetChannels(struct pios_sbus_state *state)
{
for (int i = 0; i < PIOS_SBUS_NUM_INPUTS; i++) {
state->channel_data[i] = PIOS_RCVR_TIMEOUT;
}
}
/* Reset S.Bus receiver state */
static void PIOS_SBus_ResetState(struct pios_sbus_state *state)
{
state->receive_timer = 0;
state->failsafe_timer = 0;
state->frame_found = 0;
PIOS_SBus_ResetChannels(state);
}
/* Initialise S.Bus receiver interface */
int32_t PIOS_SBus_Init(uint32_t *sbus_id,
const struct pios_sbus_cfg *cfg,
const struct pios_com_driver *driver,
uint32_t lower_id)
{
PIOS_DEBUG_Assert(sbus_id);
PIOS_DEBUG_Assert(cfg);
PIOS_DEBUG_Assert(driver);
struct pios_sbus_dev *sbus_dev;
sbus_dev = (struct pios_sbus_dev *)PIOS_SBus_Alloc();
if (!sbus_dev) goto out_fail;
/* Bind the configuration to the device instance */
sbus_dev->cfg = cfg;
PIOS_SBus_ResetState(&(sbus_dev->state));
*sbus_id = (uint32_t)sbus_dev;
/* Enable inverter clock and enable the inverter */
(*cfg->gpio_clk_func)(cfg->gpio_clk_periph, ENABLE);
GPIO_Init(cfg->inv.gpio, &cfg->inv.init);
GPIO_WriteBit(cfg->inv.gpio, cfg->inv.init.GPIO_Pin, cfg->gpio_inv_enable);
/* Set comm driver callback */
(driver->bind_rx_cb)(lower_id, PIOS_SBus_RxInCallback, *sbus_id);
if (!PIOS_RTC_RegisterTickCallback(PIOS_SBus_Supervisor, *sbus_id)) {
PIOS_DEBUG_Assert(0);
}
return 0;
out_fail:
return -1;
}
/**
* unroll_channels() function computes channel_data[] from received_data[]
* Get the value of an input channel
* \param[in] channel Number of the channel desired (zero based)
* \output PIOS_RCVR_INVALID channel not available
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
* \output >0 channel value
*/
static int32_t PIOS_SBus_Get(uint32_t rcvr_id, uint8_t channel)
{
struct pios_sbus_dev *sbus_dev = (struct pios_sbus_dev *)rcvr_id;
if (!PIOS_SBus_Validate(sbus_dev))
return PIOS_RCVR_INVALID;
/* return error if channel is not available */
if (channel >= PIOS_SBUS_NUM_INPUTS) {
return PIOS_RCVR_INVALID;
}
return sbus_dev->state.channel_data[channel];
}
/**
* Compute channel_data[] from received_data[].
* For efficiency it unrolls first 8 channels without loops and does the
* same for other 8 channels. Also 2 discrete channels will be set.
*/
static void unroll_channels(void)
static void PIOS_SBus_UnrollChannels(struct pios_sbus_state *state)
{
uint8_t *s = received_data;
uint16_t *d = channel_data;
uint8_t *s = state->received_data;
uint16_t *d = state->channel_data;
#define F(v,s) ((v) >> s) & 0x7ff
#define F(v,s) (((v) >> (s)) & 0x7ff)
/* unroll channels 1-8 */
*d++ = F(s[0] | s[1] << 8, 0);
@ -98,132 +220,119 @@ static void unroll_channels(void)
*d++ = (s[22] & SBUS_FLAG_DC2) ? SBUS_VALUE_MAX : SBUS_VALUE_MIN;
}
/**
* process_byte() function processes incoming byte from S.Bus stream
*/
static void process_byte(uint8_t b)
/* Update decoder state processing input byte from the S.Bus stream */
static void PIOS_SBus_UpdateState(struct pios_sbus_state *state, uint8_t b)
{
static uint8_t byte_count;
/* should not process any data until new frame is found */
if (!state->frame_found)
return;
if (frame_found == 0) {
/* no frame found yet, waiting for start byte */
if (b == SBUS_SOF_BYTE) {
byte_count = 0;
frame_found = 1;
}
} else {
/* do not store start and end of frame bytes */
if (byte_count < SBUS_FRAME_LENGTH - 2) {
/* store next byte */
received_data[byte_count++] = b;
if (state->byte_count == 0) {
if (b != SBUS_SOF_BYTE) {
/* discard the whole frame if the 1st byte is not correct */
state->frame_found = 0;
} else {
if (b == SBUS_EOF_BYTE) {
/* full frame received */
uint8_t flags = received_data[SBUS_FRAME_LENGTH - 3];
if (flags & SBUS_FLAG_FL) {
/* frame lost, do not update */
} else if (flags & SBUS_FLAG_FS) {
/* failsafe flag active */
reset_channels();
} else {
/* data looking good */
unroll_channels();
failsafe_timer = 0;
}
} else {
/* discard whole frame */
}
/* prepare for the next frame */
frame_found = 0;
/* do not store the SOF byte */
state->byte_count++;
}
return;
}
/* do not store last frame byte as well */
if (state->byte_count < SBUS_FRAME_LENGTH - 1) {
/* store next byte */
state->received_data[state->byte_count - 1] = b;
state->byte_count++;
} else {
if (b == SBUS_EOF_BYTE) {
/* full frame received */
uint8_t flags = state->received_data[SBUS_FRAME_LENGTH - 3];
if (flags & SBUS_FLAG_FL) {
/* frame lost, do not update */
} else if (flags & SBUS_FLAG_FS) {
/* failsafe flag active */
PIOS_SBus_ResetChannels(state);
} else {
/* data looking good */
PIOS_SBus_UnrollChannels(state);
state->failsafe_timer = 0;
}
} else {
/* discard whole frame */
}
/* prepare for the next frame */
state->frame_found = 0;
}
}
static uint16_t PIOS_SBUS_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
/* Comm byte received callback */
static uint16_t PIOS_SBus_RxInCallback(uint32_t context,
uint8_t *buf,
uint16_t buf_len,
uint16_t *headroom,
bool *need_yield)
{
struct pios_sbus_dev *sbus_dev = (struct pios_sbus_dev *)context;
bool valid = PIOS_SBus_Validate(sbus_dev);
PIOS_Assert(valid);
struct pios_sbus_state *state = &(sbus_dev->state);
/* process byte(s) and clear receive timer */
for (uint8_t i = 0; i < buf_len; i++) {
process_byte(buf[i]);
receive_timer = 0;
PIOS_SBus_UpdateState(state, buf[i]);
state->receive_timer = 0;
}
/* Always signal that we can accept another byte */
if (headroom) {
if (headroom)
*headroom = SBUS_FRAME_LENGTH;
}
/* We never need a yield */
*need_yield = false;
/* Always indicate that all bytes were consumed */
return (buf_len);
}
/**
* Initialise S.Bus receiver interface
*/
int32_t PIOS_SBUS_Init(uint32_t * sbus_id, const struct pios_sbus_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id)
{
/* Enable inverter clock and enable the inverter */
(*cfg->gpio_clk_func)(cfg->gpio_clk_periph, ENABLE);
GPIO_Init(cfg->inv.gpio, &cfg->inv.init);
GPIO_WriteBit(cfg->inv.gpio,
cfg->inv.init.GPIO_Pin,
cfg->gpio_inv_enable);
(driver->bind_rx_cb)(lower_id, PIOS_SBUS_RxInCallback, 0);
if (!PIOS_RTC_RegisterTickCallback(PIOS_SBUS_Supervisor, 0)) {
PIOS_Assert(0);
}
return (0);
}
/**
* Get the value of an input channel
* \param[in] channel Number of the channel desired (zero based)
* \output -1 channel not available
* \output >0 channel value
*/
static int32_t PIOS_SBUS_Get(uint32_t rcvr_id, uint8_t channel)
{
/* return error if channel is not available */
if (channel >= SBUS_NUMBER_OF_CHANNELS) {
return PIOS_RCVR_INVALID;
}
return channel_data[channel];
return buf_len;
}
/**
* Input data supervisor is called periodically and provides
* two functions: frame syncing and failsafe triggering.
*
* S.Bus frames come at 7ms (HS) or 14ms (FS) rate at 100000bps. RTC
* timer is running at 625Hz (1.6ms). So with divider 2 it gives
* 3.2ms pause between frames which is good for both S.Bus data rates.
* S.Bus frames come at 7ms (HS) or 14ms (FS) rate at 100000bps.
* RTC timer is running at 625Hz (1.6ms). So with divider 2 it gives
* 3.2ms pause between frames which is good for both S.Bus frame rates.
*
* Data receive function must clear the receive_timer to confirm new
* data reception. If no new data received in 100ms, we must call the
* failsafe function which clears all channels.
*/
static void PIOS_SBUS_Supervisor(uint32_t sbus_id)
static void PIOS_SBus_Supervisor(uint32_t sbus_id)
{
struct pios_sbus_dev *sbus_dev = (struct pios_sbus_dev *)sbus_id;
bool valid = PIOS_SBus_Validate(sbus_dev);
PIOS_Assert(valid);
struct pios_sbus_state *state = &(sbus_dev->state);
/* waiting for new frame if no bytes were received in 3.2ms */
if (++receive_timer > 2) {
receive_timer = 0;
frame_found = 0;
if (++state->receive_timer > 2) {
state->frame_found = 1;
state->byte_count = 0;
state->receive_timer = 0;
}
/* activate failsafe if no frames have arrived in 102.4ms */
if (++failsafe_timer > 64) {
reset_channels();
failsafe_timer = 0;
if (++state->failsafe_timer > 64) {
PIOS_SBus_ResetChannels(state);
state->failsafe_timer = 0;
}
}
#endif
#endif /* PIOS_INCLUDE_SBUS */
/**
* @}

View File

@ -2,7 +2,7 @@
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_SBUS Futaba S.Bus receiver functions
* @addtogroup PIOS_SBus Futaba S.Bus receiver functions
* @{
*
* @file pios_sbus.h

View File

@ -2,7 +2,7 @@
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_SBUS S.Bus Functions
* @addtogroup PIOS_SBus S.Bus Functions
* @brief PIOS interface to read and write from Futaba S.Bus port
* @{
*
@ -63,7 +63,9 @@
* S.Bus protocol provides 16 proportional and 2 discrete channels.
* Do not change unless driver code is updated accordingly.
*/
#define SBUS_NUMBER_OF_CHANNELS (16 + 2)
#if (PIOS_SBUS_NUM_INPUTS != (16+2))
#error "S.Bus protocol provides 16 proportional and 2 discrete channels"
#endif
/* Discrete channels represented as bits, provide values for them */
#define SBUS_VALUE_MIN 352
@ -81,7 +83,10 @@ struct pios_sbus_cfg {
extern const struct pios_rcvr_driver pios_sbus_rcvr_driver;
extern int32_t PIOS_SBUS_Init(uint32_t * sbus_id, const struct pios_sbus_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id);
extern int32_t PIOS_SBus_Init(uint32_t *sbus_id,
const struct pios_sbus_cfg *cfg,
const struct pios_com_driver *driver,
uint32_t lower_id);
#endif /* PIOS_SBUS_PRIV_H */

View File

@ -263,8 +263,6 @@
65643CB01413322000A32F59 /* pios_spektrum_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_spektrum_priv.h; sourceTree = "<group>"; };
65643CB91413456D00A32F59 /* pios_tim.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_tim.c; sourceTree = "<group>"; };
65643CBA141350C200A32F59 /* pios_sbus.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_sbus.c; sourceTree = "<group>"; };
65643CEC141429A100A32F59 /* NMEA.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = NMEA.c; sourceTree = "<group>"; };
65643CEE141429AF00A32F59 /* NMEA.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = NMEA.h; sourceTree = "<group>"; };
6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_memory.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_memory.ld; sourceTree = SOURCE_ROOT; };
6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_sections.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld; sourceTree = SOURCE_ROOT; };
657CEEAD121DB6C8007A1FBE /* homelocation.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = homelocation.xml; sourceTree = "<group>"; };
@ -2822,7 +2820,6 @@
65C35E5612EFB2F3004811C2 /* attitudeactual.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitudeactual.xml; sourceTree = "<group>"; };
65C35E5812EFB2F3004811C2 /* attituderaw.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attituderaw.xml; sourceTree = "<group>"; };
65C35E5912EFB2F3004811C2 /* baroaltitude.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = baroaltitude.xml; sourceTree = "<group>"; };
65C35E5A12EFB2F3004811C2 /* batterysettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = batterysettings.xml; sourceTree = "<group>"; };
65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightbatterystate.xml; sourceTree = "<group>"; };
65C35E5D12EFB2F3004811C2 /* flightplancontrol.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightplancontrol.xml; sourceTree = "<group>"; };
65C35E5E12EFB2F3004811C2 /* flightplansettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightplansettings.xml; sourceTree = "<group>"; };
@ -7963,6 +7960,7 @@
65E410AE12F65AEA00725888 /* attitudesettings.xml */,
65C35E5912EFB2F3004811C2 /* baroaltitude.xml */,
65C35E5A12EFB2F3004811C2 /* batterysettings.xml */,
655B1A8E13B2FC0900B0E48D /* camerastabsettings.xml */,
652C8568132B632A00BFCC70 /* firmwareiapobj.xml */,
65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */,
65C35E5D12EFB2F3004811C2 /* flightplancontrol.xml */,
@ -7976,6 +7974,7 @@
65C35E6412EFB2F3004811C2 /* gpstime.xml */,
65C35E6512EFB2F3004811C2 /* guidancesettings.xml */,
65C35E6612EFB2F3004811C2 /* homelocation.xml */,
65E6D80713E3A4D0002A557A /* hwsettings.xml */,
65C35E6712EFB2F3004811C2 /* i2cstats.xml */,
65C35E6812EFB2F3004811C2 /* manualcontrolcommand.xml */,
65C35E6912EFB2F3004811C2 /* manualcontrolsettings.xml */,
@ -8267,24 +8266,8 @@
65E8F05811EFF25C00BBF654 /* STM32F10x */ = {
isa = PBXGroup;
children = (
65D1FBD813F51865006374A6 /* pios_bmp085.c */,
6560A39D13EE277E00105DA5 /* pios_iap.c */,
6560A39E13EE277E00105DA5 /* pios_sbus.c */,
6560A38E13EE270C00105DA5 /* link_STM3210E_INS_BL_sections.ld */,
6560A38F13EE270C00105DA5 /* link_STM3210E_INS_memory.ld */,
6560A39013EE270C00105DA5 /* link_STM3210E_INS_sections.ld */,
6560A39113EE270C00105DA5 /* link_STM3210E_OP_BL_sections.ld */,
6560A39213EE270C00105DA5 /* link_STM3210E_OP_memory.ld */,
6560A39313EE270C00105DA5 /* link_STM3210E_OP_sections.ld */,
6560A39413EE270C00105DA5 /* link_STM32103CB_AHRS_BL_sections.ld */,
6560A39513EE270C00105DA5 /* link_STM32103CB_AHRS_memory.ld */,
6560A39613EE270C00105DA5 /* link_STM32103CB_AHRS_sections.ld */,
6560A39713EE270C00105DA5 /* link_STM32103CB_CC_Rev1_BL_sections.ld */,
6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */,
6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */,
6560A39813EE270C00105DA5 /* link_STM32103CB_PIPXTREME_BL_sections.ld */,
6560A39913EE270C00105DA5 /* link_STM32103CB_PIPXTREME_memory.ld */,
6560A39A13EE270C00105DA5 /* link_STM32103CB_PIPXTREME_sections.ld */,
65E8F05911EFF25C00BBF654 /* Libraries */,
65E8F0D811EFF25C00BBF654 /* link_stm32f10x_HD.ld */,
65E8F0DB11EFF25C00BBF654 /* link_stm32f10x_MD.ld */,

View File

@ -64,6 +64,7 @@ typedef struct {
uint32_t objId;
uint16_t instId;
uint32_t length;
uint8_t instanceLength;
uint8_t cs;
int32_t rxCount;
UAVTalkRxState state;

View File

@ -351,9 +351,15 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx
// Determine data length
if (iproc->type == UAVTALK_TYPE_OBJ_REQ || iproc->type == UAVTALK_TYPE_ACK || iproc->type == UAVTALK_TYPE_NACK)
{
iproc->length = 0;
iproc->instanceLength = 0;
}
else
{
iproc->length = UAVObjGetNumBytes(iproc->obj);
iproc->instanceLength = (UAVObjIsSingleInstance(iproc->obj) ? 0 : 2);
}
// Check length and determine next state
if (iproc->length >= UAVTALK_MAX_PAYLOAD_LENGTH)
@ -364,7 +370,7 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx
}
// Check the lengths match
if ((iproc->rxPacketLength + iproc->length) != iproc->packet_size)
if ((iproc->rxPacketLength + iproc->instanceLength + iproc->length) != iproc->packet_size)
{ // packet error - mismatched packet size
connection->stats.rxErrors++;
iproc->state = UAVTALK_STATE_SYNC;

View File

@ -9,5 +9,6 @@
<dependency name="UAVObjects" version="1.0.0"/>
<dependency name="UAVTalk" version="1.0.0"/>
<dependency name="UAVObjectUtil" version="1.0.0"/>
<dependency name="UAVSettingsImportExport" version="1.0.0"/>
</dependencyList>
</plugin>

View File

@ -138,46 +138,6 @@
<string>None</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 1</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 2</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 3</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 4</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 5</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 6</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 7</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 8</string>
</property>
</item>
</widget>
</item>
<item row="4" column="1">
@ -187,46 +147,6 @@
<string>None</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 1</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 2</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 3</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 4</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 5</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 6</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 7</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 8</string>
</property>
</item>
</widget>
</item>
<item row="3" column="0">
@ -243,46 +163,6 @@
<string>None</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 1</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 2</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 3</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 4</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 5</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 6</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 7</string>
</property>
</item>
<item>
<property name="text">
<string>Channel 8</string>
</property>
</item>
</widget>
</item>
<item row="4" column="0">

View File

@ -8,7 +8,7 @@ include(../../plugins/uavtalk/uavtalk.pri)
include(../../plugins/coreplugin/coreplugin.pri)
include(../../plugins/uavobjects/uavobjects.pri)
include(../../plugins/uavobjectutil/uavobjectutil.pri)
include(../../plugins/uavsettingsimportexport/uavsettingsimportexport.pri)
INCLUDEPATH += ../../libs/eigen
OTHER_FILES += Config.pluginspec

View File

@ -36,6 +36,10 @@
#include <math.h>
#include <QDesktopServices>
#include <QUrl>
#include "systemsettings.h"
#include "mixersettings.h"
#include "actuatorsettings.h"
#include <QEventLoop>
/**
Helper delegate for the custom mixer editor table.
@ -101,10 +105,13 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
ffTuningInProgress = false;
ffTuningPhase = false;
mixerTypes << "Mixer1Type" << "Mixer2Type" << "Mixer3Type"
<< "Mixer4Type" << "Mixer5Type" << "Mixer6Type" << "Mixer7Type" << "Mixer8Type";
mixerVectors << "Mixer1Vector" << "Mixer2Vector" << "Mixer3Vector"
<< "Mixer4Vector" << "Mixer5Vector" << "Mixer6Vector" << "Mixer7Vector" << "Mixer8Vector";
QStringList channels;
channels << "None";
for (int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) {
mixerTypes << QString("Mixer%1Type").arg(i+1);
mixerVectors << QString("Mixer%1Vector").arg(i+1);
channels << QString("Channel%1").arg(i+1);
}
QStringList airframeTypes;
airframeTypes << "Fixed Wing" << "Multirotor" << "Helicopter" << "Custom";
@ -120,11 +127,6 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
<< "Octo Coax X" << "Hexacopter Y6" << "Tricopter Y";
m_aircraft->multirotorFrameType->addItems(multiRotorTypes);
QStringList channels;
channels << "None" << "Channel1" << "Channel2" << "Channel3" <<
"Channel4" << "Channel5" << "Channel6" << "Channel7" << "Channel8";
// Now load all the channel assignements for fixed wing
m_aircraft->fwElevator1Channel->addItems(channels);
m_aircraft->fwElevator2Channel->addItems(channels);
@ -443,6 +445,8 @@ void ConfigAirframeWidget::updateCustomThrottle2CurveValue(QList<double> list, d
*/
void ConfigAirframeWidget::refreshWidgetsValues()
{
if(!allObjectsUpdated())
return;
bool dirty=isDirty();
// Get the Airframe type from the system settings:
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
@ -1516,6 +1520,16 @@ bool ConfigAirframeWidget::setupFrameVtail()
*/
bool ConfigAirframeWidget::setupMixer(double mixerFactors[8][3])
{
qDebug()<<"Mixer factors";
qDebug()<<mixerFactors[0][0]<<" "<<mixerFactors[0][1]<<" "<<mixerFactors[0][2];
qDebug()<<mixerFactors[1][0]<<" "<<mixerFactors[1][1]<<" "<<mixerFactors[1][2];
qDebug()<<mixerFactors[2][0]<<" "<<mixerFactors[2][1]<<" "<<mixerFactors[2][2];
qDebug()<<mixerFactors[3][0]<<" "<<mixerFactors[3][1]<<" "<<mixerFactors[3][2];
qDebug()<<mixerFactors[4][0]<<" "<<mixerFactors[4][1]<<" "<<mixerFactors[4][2];
qDebug()<<mixerFactors[5][0]<<" "<<mixerFactors[5][1]<<" "<<mixerFactors[5][2];
qDebug()<<mixerFactors[6][0]<<" "<<mixerFactors[6][1]<<" "<<mixerFactors[6][2];
qDebug()<<mixerFactors[7][0]<<" "<<mixerFactors[7][1]<<" "<<mixerFactors[7][2];
UAVObjectField *field;
QList<QComboBox*> mmList;
mmList << m_aircraft->multiMotor1 << m_aircraft->multiMotor2 << m_aircraft->multiMotor3
@ -1533,11 +1547,15 @@ bool ConfigAirframeWidget::setupMixer(double mixerFactors[8][3])
double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100;
double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100;
double yFactor = (double)m_aircraft->mrYawMixLevel->value()/100;
qDebug()<<QString("pFactor=%0 rFactor=%1 yFactor=%2").arg(pFactor).arg(rFactor).arg(yFactor);
for (int i=0 ; i<8; i++) {
int channel = mmList.at(i)->currentIndex()-1;
if (channel > -1)
setupQuadMotor(channel, mixerFactors[i][0]*pFactor,
rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]);
if(mmList.at(i)->isEnabled())
{
int channel = mmList.at(i)->currentIndex()-1;
if (channel > -1)
setupQuadMotor(channel, mixerFactors[i][0]*pFactor,
rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]);
}
}
// obj->updated();
return true;
@ -1549,6 +1567,7 @@ bool ConfigAirframeWidget::setupMixer(double mixerFactors[8][3])
*/
void ConfigAirframeWidget::setupQuadMotor(int channel, double pitch, double roll, double yaw)
{
qDebug()<<QString("Setup quad motor channel=%0 pitch=%1 roll=%2 yaw=%3").arg(channel).arg(pitch).arg(roll).arg(yaw);
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
UAVObjectField *field = obj->getField(mixerTypes.at(channel));
@ -1560,10 +1579,13 @@ void ConfigAirframeWidget::setupQuadMotor(int channel, double pitch, double roll
field->setValue(127, ti);
ti = field->getElementNames().indexOf("Roll");
field->setValue(roll*127,ti);
qDebug()<<"Set roll="<<roll*127;
ti = field->getElementNames().indexOf("Pitch");
field->setValue(pitch*127,ti);
qDebug()<<"Set pitch="<<pitch*127;
ti = field->getElementNames().indexOf("Yaw");
field->setValue(yaw*127,ti);
qDebug()<<"Set yaw="<<yaw*127;
}
/**

View File

@ -41,12 +41,26 @@
#include "camerastabsettings.h"
#include "hwsettings.h"
#include "mixersettings.h"
#include "actuatorcommand.h"
ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_camerastabilization = new Ui_CameraStabilizationWidget();
m_camerastabilization->setupUi(this);
QComboBox * selectors[3] = {
m_camerastabilization->rollChannel,
m_camerastabilization->pitchChannel,
m_camerastabilization->yawChannel
};
for (int i = 0; i < 3; i++) {
selectors[i]->clear();
selectors[i]->addItem("None");
for (int j = 0; j < ActuatorCommand::CHANNEL_NUMELEM; j++)
selectors[i]->addItem(QString("Channel %1").arg(j+1));
}
connectUpdates();
// Connect buttons

View File

@ -98,7 +98,7 @@ void ConfigCCAttitudeWidget::attitudeRawUpdated(UAVObject * obj) {
attitudeSettingsData.GyroBias[0] = -x_gyro_bias;
attitudeSettingsData.GyroBias[1] = -y_gyro_bias;
attitudeSettingsData.GyroBias[2] = -z_gyro_bias;
attitudeSettingsData.BiasCorrectGyro = initialBiasCorrected;
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE;
AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData);
} else {
@ -134,7 +134,6 @@ void ConfigCCAttitudeWidget::startAccelCalibration() {
// Disable gyro bias correction to see raw data
AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData();
initialBiasCorrected = attitudeSettingsData.BiasCorrectGyro;
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE;
AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData);

View File

@ -57,7 +57,6 @@ private:
Ui_ccattitude *ui;
QTimer timer;
UAVObject::Metadata initialMdata;
quint8 initialBiasCorrected;
int updates;

View File

@ -618,224 +618,6 @@ void ConfigInputWidget::restoreMdata()
manualCommandObj->setMetadata(manualControlMdata);
}
//void ConfigInputWidget::setupWizardWidget(int step)
//{
// if(step==wizardWelcome)
// {
// m_config->graphicsView->setVisible(false);
// setTxMovement(nothing);
// if(wizardStep==wizardChooseMode)
// {
// delete extraWidgets.at(0);
// delete extraWidgets.at(1);
// extraWidgets.clear();
// }
// manualSettingsData=manualSettingsObj->getData();
// manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED;
// manualSettingsObj->setData(manualSettingsData);
// m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\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"
// "At any time you can press 'back' to return to the previous screeen or 'Cancel' to cancel the wizard.\n"));
// m_config->stackedWidget->setCurrentIndex(1);
// m_config->wzBack->setEnabled(false);
// wizardStep=wizardWelcome;
// }
// else if(step==wizardChooseMode)
// {
// m_config->graphicsView->setVisible(true);
// setTxMovement(nothing);
// if(wizardStep==wizardIdentifySticks)
// {
// disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
// m_config->wzNext->setEnabled(true);
// }
// m_config->wzText->setText(tr("Please choose your transmiter type.\n"
// "Mode 1 means your throttle stick is on the right\n"
// "Mode 2 means your throttle stick is on the left\n"));
// m_config->wzBack->setEnabled(true);
// QRadioButton * mode1=new QRadioButton(tr("Mode 1"),this);
// QRadioButton * mode2=new QRadioButton(tr("Mode 2"),this);
// mode2->setChecked(true);
// extraWidgets.clear();
// extraWidgets.append(mode1);
// extraWidgets.append(mode2);
// m_config->checkBoxesLayout->layout()->addWidget(mode1);
// m_config->checkBoxesLayout->layout()->addWidget(mode2);
// wizardStep=wizardChooseMode;
// }
// else if(step==wizardChooseType)
// {
// if(wizardStep==wizardChooseMode)
// {
// QRadioButton * mode=qobject_cast<QRadioButton *>(extraWidgets.at(0));
// if(mode->isChecked())
// transmitterMode=mode1;
// else
// transmitterMode=mode2;
// delete extraWidgets.at(0);
// delete extraWidgets.at(1);
// extraWidgets.clear();
// }
// m_config->wzText->setText(tr("Please choose your transmiter mode.\n"
// "Acro means normal transmitter\n"
// "Heli means there is a collective pitch and throttle input\n"));
// m_config->wzBack->setEnabled(true);
// QRadioButton * typeAcro=new QRadioButton(tr("Acro"),this);
// QRadioButton * typeHeli=new QRadioButton(tr("Heli"),this);
// typeAcro->setChecked(true);
// typeHeli->setChecked(false);
// extraWidgets.clear();
// extraWidgets.append(typeAcro);
// extraWidgets.append(typeHeli);
// m_config->checkBoxesLayout->layout()->addWidget(typeAcro);
// m_config->checkBoxesLayout->layout()->addWidget(typeHeli);
// wizardStep=wizardChooseType;
// } else if(step==wizardIdentifySticks && !isSimple) {
// usedChannels.clear();
// if(wizardStep==wizardChooseType)
// {
// qDebug() << "Chosing type";
// QRadioButton * type=qobject_cast<QRadioButton *>(extraWidgets.at(0));
// if(type->isChecked())
// transmitterType=acro;
// else
// transmitterType=heli;
// qDebug() << "Checked: " << type->isChecked() << " " << "type is" << transmitterType;
// delete extraWidgets.at(0);
// delete extraWidgets.at(1);
// extraWidgets.clear();
// }
// wizardStep=wizardIdentifySticks;
// currentCommand=0;
// getChannelFromStep(currentCommand);
// manualSettingsData=manualSettingsObj->getData();
// connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
// m_config->wzNext->setEnabled(false);
// }
// else if(step==wizardIdentifyCenter || (isSimple && step==wizardIdentifySticks))
// {
// setTxMovement(centerAll);
// if(wizardStep==wizardIdentifySticks)
// disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
// else
// {
// disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
// manualSettingsObj->setData(manualSettingsData);
// manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata());
// }
// wizardStep=wizardIdentifyCenter;
// m_config->wzText->setText(QString(tr("Please center all control controls and press next when ready (if your FlightMode switch has only two positions, leave it on either position)")));
// }
// else if(step==wizardIdentifyLimits)
// {
// dimOtherControls(false);
// setTxMovement(moveAll);
// if(wizardStep==wizardIdentifyCenter)
// {
// wizardStep=wizardIdentifyLimits;
// manualCommandData=manualCommandObj->getData();
// manualSettingsData=manualSettingsObj->getData();
// for(unsigned int i=0;i<ManualControlCommand::CHANNEL_NUMELEM;++i)
// {
// manualSettingsData.ChannelNeutral[i]=manualCommandData.Channel[i];
// }
// manualSettingsObj->setData(manualSettingsData);
// }
// if(wizardStep==wizardIdentifyInverted)
// {
// foreach(QWidget * wd,extraWidgets)
// {
// QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
// if(cb)
// {
// disconnect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
// delete cb;
// }
// }
// }
// extraWidgets.clear();
// disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
// wizardStep=wizardIdentifyLimits;
// m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready")));
// UAVObject::Metadata mdata= manualCommandObj->getMetadata();
// mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC;
// mdata.flightTelemetryUpdatePeriod = 150;
// manualCommandObj->setMetadata(mdata);
// manualSettingsData=manualSettingsObj->getData();
// for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
// {
// manualSettingsData.ChannelMin[i]=manualSettingsData.ChannelNeutral[i];
// manualSettingsData.ChannelMax[i]=manualSettingsData.ChannelNeutral[i];
// }
// connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
// }
// else if(step==wizardIdentifyInverted)
// {
// dimOtherControls(true);
// setTxMovement(nothing);
// if(wizardStep==wizardIdentifyLimits)
// {
// disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
// manualSettingsObj->setData(manualSettingsData);
// }
// extraWidgets.clear();
// foreach(QString name,manualSettingsObj->getFields().at(0)->getElementNames())
// {
// if(!name.contains("Access") && !name.contains("Flight"))
// {
// QCheckBox * cb=new QCheckBox(name,this);
// extraWidgets.append(cb);
// m_config->checkBoxesLayout->layout()->addWidget(cb);
// connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
// }
// }
// connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
// wizardStep=wizardIdentifyInverted;
// m_config->wzText->setText(QString(tr("Please check the picture below and check all the sticks which show an inverted movement and press next when ready")));
// }
// else if(step==wizardFinish)
// {
// foreach(QWidget * wd,extraWidgets)
// {
// QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
// if(cb)
// {
// disconnect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
// delete cb;
// }
// }
// wizardStep=wizardFinish;
// extraWidgets.clear();
// m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture below mimics your sticks movement.\n"
// "This new settings aren't saved to the board yet, after pressing next you will go to the initial screen where you can do that.")));
// }
// else if(step==wizardFinish+1)
// {
// setTxMovement(nothing);
// manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata());
// disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
// manualSettingsData=manualSettingsObj->getData();
// manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]=
// manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+
// ((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]-
// manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02);
// if((abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100) ||
// (abs(manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100))
// {
// manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]=manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]+
// (manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE])/2;
// }
// manualSettingsObj->setData(manualSettingsData);
// m_config->stackedWidget->setCurrentIndex(0);
// wizardStep=wizardWelcome;
// }
//}
/**
* Set the display to indicate which channel the person should move
*/
@ -849,12 +631,16 @@ void ConfigInputWidget::setChannel(int newChan)
m_config->wzText->setText(QString(tr("Please move each control once 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"))
if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory")) {
m_config->wzNext->setEnabled(true);
m_config->wzText->setText(m_config->wzText->text() + tr(" or click next to skip this channel."));
} else
m_config->wzNext->setEnabled(false);
setMoveFromCommand(newChan);
currentChannelNum = newChan;
channelDetected = false;
}
/**
@ -907,6 +693,8 @@ void ConfigInputWidget::identifyControls()
receiverActivityData=receiverActivityObj->getData();
if(receiverActivityData.ActiveChannel==255)
return;
if(channelDetected)
return;
else
{
receiverActivityData=receiverActivityObj->getData();
@ -918,6 +706,7 @@ void ConfigInputWidget::identifyControls()
lastChannel.number=currentChannel.number;
if(!usedChannels.contains(lastChannel) && debounce>1)
{
channelDetected = true;
debounce=0;
usedChannels.append(lastChannel);
manualSettingsData=manualSettingsObj->getData();
@ -932,7 +721,7 @@ void ConfigInputWidget::identifyControls()
m_config->wzText->clear();
setTxMovement(nothing);
QTimer::singleShot(300, this, SLOT(wzNext()));
QTimer::singleShot(500, this, SLOT(wzNext()));
}
void ConfigInputWidget::identifyLimits()
@ -1368,6 +1157,8 @@ void ConfigInputWidget::updateCalibration()
void ConfigInputWidget::simpleCalibration(bool enable)
{
if (enable) {
m_config->configurationWizard->setEnabled(false);
QMessageBox msgBox;
msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety."));
msgBox.setDetailedText(tr("You will have to reconfigure arming settings yourself afterwards."));
@ -1392,6 +1183,8 @@ void ConfigInputWidget::simpleCalibration(bool enable)
connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration()));
} else {
m_config->configurationWizard->setEnabled(true);
manualCommandData = manualCommandObj->getData();
manualSettingsData = manualSettingsObj->getData();

View File

@ -81,6 +81,7 @@ private:
}lastChannel;
channelsStruct currentChannel;
QList<channelsStruct> usedChannels;
bool channelDetected;
QEventLoop * loop;
bool skipflag;

View File

@ -38,28 +38,32 @@
#include <QMessageBox>
#include <QDesktopServices>
#include <QUrl>
#include "actuatorcommand.h"
#include "systemalarms.h"
ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_config = new Ui_OutputWidget();
m_config->setupUi(this);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
addUAVObject("ActuatorSettings");
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
addUAVObject("ActuatorSettings");
// First of all, put all the channel widgets into lists, so that we can
// First of all, put all the channel widgets into lists, so that we can
// manipulate those:
// NOTE: for historical reasons, we have objects below called ch0 to ch7, but the convention for OP is Channel 1 to Channel 8.
// NOTE: for historical reasons, we have objects below called ch0 to ch7, but the convention for OP is Channel 1 to Channel 8.
outLabels << m_config->ch0OutValue
<< m_config->ch1OutValue
<< m_config->ch2OutValue
<< m_config->ch3OutValue
<< m_config->ch4OutValue
<< m_config->ch5OutValue
<< m_config->ch6OutValue
<< m_config->ch7OutValue;
<< m_config->ch1OutValue
<< m_config->ch2OutValue
<< m_config->ch3OutValue
<< m_config->ch4OutValue
<< m_config->ch5OutValue
<< m_config->ch6OutValue
<< m_config->ch7OutValue
<< m_config->ch8OutValue
<< m_config->ch9OutValue;
outSliders << m_config->ch0OutSlider
<< m_config->ch1OutSlider
@ -68,7 +72,9 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
<< m_config->ch4OutSlider
<< m_config->ch5OutSlider
<< m_config->ch6OutSlider
<< m_config->ch7OutSlider;
<< m_config->ch7OutSlider
<< m_config->ch8OutSlider
<< m_config->ch9OutSlider;
outMin << m_config->ch0OutMin
<< m_config->ch1OutMin
@ -77,7 +83,9 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
<< m_config->ch4OutMin
<< m_config->ch5OutMin
<< m_config->ch6OutMin
<< m_config->ch7OutMin;
<< m_config->ch7OutMin
<< m_config->ch8OutMin
<< m_config->ch9OutMin;
outMax << m_config->ch0OutMax
<< m_config->ch1OutMax
@ -86,7 +94,9 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
<< m_config->ch4OutMax
<< m_config->ch5OutMax
<< m_config->ch6OutMax
<< m_config->ch7OutMax;
<< m_config->ch7OutMax
<< m_config->ch8OutMax
<< m_config->ch9OutMax;
reversals << m_config->ch0Rev
<< m_config->ch1Rev
@ -95,7 +105,9 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
<< m_config->ch4Rev
<< m_config->ch5Rev
<< m_config->ch6Rev
<< m_config->ch7Rev;
<< m_config->ch7Rev
<< m_config->ch8Rev
<< m_config->ch9Rev;
links << m_config->ch0Link
<< m_config->ch1Link
@ -104,15 +116,23 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
<< m_config->ch4Link
<< m_config->ch5Link
<< m_config->ch6Link
<< m_config->ch7Link;
<< m_config->ch7Link
<< m_config->ch8Link
<< m_config->ch9Link;
// Register for ActuatorSettings changes:
for (int i = 0; i < 8; i++) {
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
connect(outMin[i], SIGNAL(editingFinished()), this, SLOT(setChOutRange()));
connect(outMax[i], SIGNAL(editingFinished()), this, SLOT(setChOutRange()));
connect(reversals[i], SIGNAL(toggled(bool)), this, SLOT(reverseChannel(bool)));
// Now connect the channel out sliders to our signal to send updates in test mode
connect(outSliders[i], SIGNAL(valueChanged(int)), this, SLOT(sendChannelTest(int)));
addWidget(outMin[i]);
addWidget(outMax[i]);
addWidget(reversals[i]);
addWidget(outSliders[i]);
addWidget(links[i]);
}
connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool)));
@ -134,39 +154,7 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
addWidget(m_config->outputRate3);
addWidget(m_config->outputRate2);
addWidget(m_config->outputRate1);
addWidget(m_config->ch0OutMin);
addWidget(m_config->ch0OutSlider);
addWidget(m_config->ch0OutMax);
addWidget(m_config->ch0Rev);
addWidget(m_config->ch0Link);
addWidget(m_config->ch1OutMin);
addWidget(m_config->ch1OutSlider);
addWidget(m_config->ch1OutMax);
addWidget(m_config->ch1Rev);
addWidget(m_config->ch2OutMin);
addWidget(m_config->ch2OutSlider);
addWidget(m_config->ch2OutMax);
addWidget(m_config->ch2Rev);
addWidget(m_config->ch3OutMin);
addWidget(m_config->ch3OutSlider);
addWidget(m_config->ch3OutMax);
addWidget(m_config->ch3Rev);
addWidget(m_config->ch4OutMin);
addWidget(m_config->ch4OutSlider);
addWidget(m_config->ch4OutMax);
addWidget(m_config->ch4Rev);
addWidget(m_config->ch5OutMin);
addWidget(m_config->ch5OutSlider);
addWidget(m_config->ch5OutMax);
addWidget(m_config->ch5Rev);
addWidget(m_config->ch6OutMin);
addWidget(m_config->ch6OutSlider);
addWidget(m_config->ch6OutMax);
addWidget(m_config->ch6Rev);
addWidget(m_config->ch7OutMin);
addWidget(m_config->ch7OutSlider);
addWidget(m_config->ch7OutMax);
addWidget(m_config->ch7Rev);
addWidget(m_config->spinningArmed);
}
@ -215,6 +203,22 @@ void ConfigOutputWidget::linkToggled(bool state)
*/
void ConfigOutputWidget::runChannelTests(bool state)
{
SystemAlarms * systemAlarmsObj = SystemAlarms::GetInstance(getObjectManager());
SystemAlarms::DataFields systemAlarms = systemAlarmsObj->getData();
if(state && systemAlarms.Alarm[SystemAlarms::ALARM_ACTUATOR] != SystemAlarms::ALARM_OK) {
QMessageBox mbox;
mbox.setText(QString(tr("The actuator module is in an error state. This can also occur because there are no inputs. Please fix these before testing outputs.")));
mbox.setStandardButtons(QMessageBox::Ok);
mbox.exec();
// Unfortunately must cache this since callback will reoccur
accInitialData = ActuatorCommand::GetInstance(getObjectManager())->getMetadata();
m_config->channelOutTest->setChecked(false);
return;
}
// Confirm this is definitely what they want
if(state) {
QMessageBox mbox;
@ -229,11 +233,7 @@ void ConfigOutputWidget::runChannelTests(bool state)
}
}
qDebug() << "Running with state " << state;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("ActuatorCommand")));
ActuatorCommand * obj = ActuatorCommand::GetInstance(getObjectManager());
UAVObject::Metadata mdata = obj->getMetadata();
if (state)
{
@ -252,6 +252,9 @@ void ConfigOutputWidget::runChannelTests(bool state)
foreach (QSpinBox* box, outMax) {
box->setEnabled(false);
}
foreach (QCheckBox* box, reversals) {
box->setEnabled(false);
}
}
else
@ -263,6 +266,9 @@ void ConfigOutputWidget::runChannelTests(bool state)
foreach (QSpinBox* box, outMax) {
box->setEnabled(true);
}
foreach (QCheckBox* box, reversals) {
box->setEnabled(true);
}
}
obj->setMetadata(mdata);
@ -301,6 +307,12 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str)
case 7:
m_config->ch7Output->setText(str);
break;
case 8:
m_config->ch8Output->setText(str);
break;
case 9:
m_config->ch9Output->setText(str);
break;
}
}
@ -384,14 +396,8 @@ void ConfigOutputWidget::refreshWidgetsValues()
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
// Reset all channel assignements:
m_config->ch0Output->setText("-");
m_config->ch1Output->setText("-");
m_config->ch2Output->setText("-");
m_config->ch3Output->setText("-");
m_config->ch4Output->setText("-");
m_config->ch5Output->setText("-");
m_config->ch6Output->setText("-");
m_config->ch7Output->setText("-");
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++)
outLabels[i]->setText("-");
// Get the channel assignements:
UAVDataObject * obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("ActuatorSettings")));
@ -418,8 +424,8 @@ void ConfigOutputWidget::refreshWidgetsValues()
// CopterControl family
m_config->chBank1->setText("1-3");
m_config->chBank2->setText("4");
m_config->chBank3->setText("5");
m_config->chBank4->setText("6");
m_config->chBank3->setText("5,7-8");
m_config->chBank4->setText("6,9-10");
m_config->outputRate1->setEnabled(true);
m_config->outputRate2->setEnabled(true);
m_config->outputRate3->setEnabled(true);
@ -443,7 +449,7 @@ void ConfigOutputWidget::refreshWidgetsValues()
// Get Channel ranges:
for (int i=0;i<8;i++) {
for (int i=0;i<ActuatorCommand::CHANNEL_NUMELEM;i++) {
field = obj->getField(QString("ChannelMin"));
int minValue = field->getValue(i).toInt();
outMin[i]->setValue(minValue);
@ -462,7 +468,7 @@ void ConfigOutputWidget::refreshWidgetsValues()
}
field = obj->getField(QString("ChannelNeutral"));
for (int i=0; i<8; i++) {
for (int i=0; i<ActuatorCommand::CHANNEL_NUMELEM; i++) {
int value = field->getValue(i).toInt();
outSliders[i]->setValue(value);
outLabels[i]->setText(QString::number(value));
@ -483,17 +489,17 @@ void ConfigOutputWidget::updateObjectsFromWidgets()
// Now send channel ranges:
UAVObjectField * field = obj->getField(QString("ChannelMax"));
for (int i = 0; i < 8; i++) {
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
field->setValue(outMax[i]->value(),i);
}
field = obj->getField(QString("ChannelMin"));
for (int i = 0; i < 8; i++) {
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
field->setValue(outMin[i]->value(),i);
}
field = obj->getField(QString("ChannelNeutral"));
for (int i = 0; i < 8; i++) {
for (int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
field->setValue(outSliders[i]->value(),i);
}

View File

@ -26,14 +26,17 @@
*/
#include "configtaskwidget.h"
#include <QtGui/QWidget>
#include "uavsettingsimportexport/uavsettingsimportexportfactory.h"
#include "configgadgetwidget.h"
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false)
{
pm = ExtensionSystem::PluginManager::instance();
objManager = pm->getObject<UAVObjectManager>();
connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect()));
connect(parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect()));
connect((ConfigGadgetWidget*)parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect()));
connect((ConfigGadgetWidget*)parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect()));
UAVSettingsImportExportFactory * importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(invalidateObjects()));
}
void ConfigTaskWidget::addWidget(QWidget * widget)
{
@ -62,6 +65,8 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
{
obj = objManager->getObject(QString(object));
Q_ASSERT(obj);
objectUpdates.insert(obj,true);
connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*)));
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
}
//smartsave->addObject(obj);
@ -123,6 +128,7 @@ ConfigTaskWidget::~ConfigTaskWidget()
void ConfigTaskWidget::saveObjectToSD(UAVObject *obj)
{
qDebug()<<"ConfigTaskWidget::saveObjectToSD";
// saveObjectToSD is now handled by the UAVUtils plugin in one
// central place (and one central queue)
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
@ -153,10 +159,12 @@ void ConfigTaskWidget::onAutopilotDisconnect()
{
isConnected=false;
enableControls(false);
invalidateObjects();
}
void ConfigTaskWidget::onAutopilotConnect()
{
invalidateObjects();
dirty=false;
isConnected=true;
enableControls(true);
@ -189,6 +197,10 @@ void ConfigTaskWidget::populateWidgets()
{
cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale);
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(ow->widget))
{
cb->setChecked(ow->field->getValue(ow->index).toBool());
}
}
setDirty(dirtyBack);
}
@ -218,6 +230,10 @@ void ConfigTaskWidget::refreshWidgetsValues()
{
cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale);
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(ow->widget))
{
cb->setChecked(ow->field->getValue(ow->index).toBool());
}
}
setDirty(dirtyBack);
}
@ -246,6 +262,10 @@ void ConfigTaskWidget::updateObjectsFromWidgets()
{
ow->field->setValue(cb->value()* ow->scale,ow->index);
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(ow->widget))
{
ow->field->setValue((cb->isChecked()?"TRUE":"FALSE"),ow->index);
}
}
}
@ -308,6 +328,30 @@ void ConfigTaskWidget::enableObjUpdates()
}
}
void ConfigTaskWidget::objectUpdated(UAVObject *obj)
{
objectUpdates[obj]=true;
}
bool ConfigTaskWidget::allObjectsUpdated()
{
bool ret=true;
foreach(UAVObject *obj, objectUpdates.keys())
{
ret=ret & objectUpdates[obj];
}
qDebug()<<"ALL OBJECTS UPDATE:"<<ret;
return ret;
}
void ConfigTaskWidget::invalidateObjects()
{
foreach(UAVObject *obj, objectUpdates.keys())
{
objectUpdates[obj]=false;
}
}

View File

@ -71,13 +71,16 @@ public:
bool isDirty();
void setDirty(bool value);
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index);
bool allObjectsUpdated();
public slots:
void onAutopilotDisconnect();
void onAutopilotConnect();
void invalidateObjects();
private slots:
virtual void refreshValues();
virtual void updateObjectsFromWidgets();
void objectUpdated(UAVObject*);
private:
bool isConnected;
QStringList objectsList;
@ -85,6 +88,7 @@ private:
ExtensionSystem::PluginManager *pm;
UAVObjectManager *objManager;
smartSaveButton *smartsave;
QMap<UAVObject *,bool> objectUpdates;
bool dirty;
protected slots:
virtual void disableObjUpdates();

Binary file not shown.

Before

Width:  |  Height:  |  Size: 2.8 KiB

After

Width:  |  Height:  |  Size: 8.4 KiB

View File

@ -970,6 +970,172 @@ p, li { white-space: pre-wrap; }
</property>
</widget>
</item>
<item row="9" column="0">
<widget class="QLabel" name="actuator8Label">
<property name="text">
<string>Channel 9:</string>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QLabel" name="actuator9Label">
<property name="text">
<string>Channel 10:</string>
</property>
</widget>
</item>
<item row="9" column="1">
<widget class="QLabel" name="ch8Output">
<property name="font">
<font>
<pointsize>9</pointsize>
</font>
</property>
<property name="text">
<string>-</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="10" column="1">
<widget class="QLabel" name="ch9Output">
<property name="font">
<font>
<pointsize>9</pointsize>
</font>
</property>
<property name="text">
<string>-</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="9" column="2">
<widget class="QSpinBox" name="ch8OutMin">
<property name="maximum">
<number>9999</number>
</property>
</widget>
</item>
<item row="10" column="2">
<widget class="QSpinBox" name="ch9OutMin">
<property name="maximum">
<number>9999</number>
</property>
</widget>
</item>
<item row="9" column="3">
<widget class="QSlider" name="ch8OutSlider">
<property name="maximum">
<number>9999</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="10" column="3">
<widget class="QSlider" name="ch9OutSlider">
<property name="maximum">
<number>9999</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="9" column="4">
<widget class="QSpinBox" name="ch8OutMax">
<property name="maximum">
<number>9999</number>
</property>
</widget>
</item>
<item row="10" column="4">
<widget class="QSpinBox" name="ch9OutMax">
<property name="maximum">
<number>9999</number>
</property>
</widget>
</item>
<item row="9" column="5">
<widget class="QLabel" name="ch8OutValue">
<property name="text">
<string>0000</string>
</property>
</widget>
</item>
<item row="10" column="5">
<widget class="QLabel" name="ch9OutValue">
<property name="text">
<string>0000</string>
</property>
</widget>
</item>
<item row="9" column="6">
<widget class="QCheckBox" name="ch8Rev">
<property name="font">
<font>
<family>FreeSans</family>
<pointsize>8</pointsize>
</font>
</property>
<property name="toolTip">
<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:'FreeSans'; font-size:8pt; 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;Check to invert the channel.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="10" column="6">
<widget class="QCheckBox" name="ch9Rev">
<property name="font">
<font>
<family>FreeSans</family>
<pointsize>8</pointsize>
</font>
</property>
<property name="toolTip">
<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:'FreeSans'; font-size:8pt; 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;Check to invert the channel.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="9" column="7">
<widget class="QCheckBox" name="ch8Link">
<property name="toolTip">
<string>Only used with Test Output mode</string>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="10" column="7">
<widget class="QCheckBox" name="ch9Link">
<property name="toolTip">
<string>Only used with Test Output mode</string>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
</layout>
</item>
<item>

View File

@ -49,7 +49,7 @@ void smartSaveButton::processClick()
}
if(up_result==false)
{
//qDebug()<<"Object upload error:"<<obj->getName();
qDebug()<<"Object upload error:"<<obj->getName();
error=true;
continue;
}
@ -59,7 +59,7 @@ void smartSaveButton::processClick()
{
for(int i=0;i<3;++i)
{
//qDebug()<<"try to save:"<<obj->getName();
qDebug()<<"try to save:"<<obj->getName();
connect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool)));
connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit()));
utilMngr->saveObjectToSD(obj);
@ -73,6 +73,7 @@ void smartSaveButton::processClick()
}
if(sv_result==false)
{
qDebug()<<"failed to save:"<<obj->getName();
error=true;
}
}

View File

@ -0,0 +1,10 @@
<plugin name="DebugGadget" version="1.0.0" compatVersion="1.0.0">
<vendor>The OpenPilot Project</vendor>
<copyright>(C) 2010 OpenPilot Project</copyright>
<license>The GNU Public License (GPL) Version 3</license>
<description>An debug gadget</description>
<url>http://www.openpilot.org</url>
<dependencyList>
<dependency name="Core" version="1.0.0"/>
</dependencyList>
</plugin>

View File

@ -0,0 +1,31 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>Form</class>
<widget class="QWidget" name="Form">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QPushButton" name="pushButton">
<property name="text">
<string>Save to file</string>
</property>
</widget>
</item>
<item>
<widget class="QTextBrowser" name="plainTextEdit"/>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>

View File

@ -0,0 +1,13 @@
#include "debugengine.h"
debugengine::debugengine()
{
}
void debugengine::writeToStdErr(const QString &level, const QList<QVariant> &msgs)
{
emit dbgMsgError(level,msgs);
}
void debugengine::writeToStdOut(const QString &level, const QList<QVariant> &msgs)
{
emit dbgMsg(level,msgs);
}

View File

@ -0,0 +1,18 @@
#ifndef DEBUGENGINE_H
#define DEBUGENGINE_H
#include "qxtbasicstdloggerengine.h"
#include <QObject>
class debugengine:public QObject,public QxtBasicSTDLoggerEngine
{
Q_OBJECT
public:
debugengine();
protected:
void writeToStdErr ( const QString & level, const QList<QVariant> & msgs );
void writeToStdOut ( const QString & level, const QList<QVariant> & msgs );
signals:
void dbgMsgError( const QString & level, const QList<QVariant> & msgs );
void dbgMsg( const QString & level, const QList<QVariant> & msgs );
};
#endif // DEBUGENGINE_H

View File

@ -0,0 +1,39 @@
/**
******************************************************************************
*
* @file debuggadget.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup DebugGadgetPlugin Debug Gadget Plugin
* @{
* @brief A place holder gadget plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "debuggadget.h"
#include "debuggadgetwidget.h"
DebugGadget::DebugGadget(QString classId, DebugGadgetWidget *widget, QWidget *parent) :
IUAVGadget(classId, parent),
m_widget(widget)
{
}
DebugGadget::~DebugGadget()
{
delete m_widget;
}

View File

@ -0,0 +1,59 @@
/**
******************************************************************************
*
* @file debuggadget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup DebugGadgetPlugin Debug Gadget Plugin
* @{
* @brief A place holder gadget plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef DEBUGGADGET_H_
#define DEBUGGADGET_H_
#include <coreplugin/iuavgadget.h>
namespace Core {
class IUAVGadget;
}
//class QWidget;
//class QString;
class DebugGadgetWidget;
using namespace Core;
class DebugGadget : public Core::IUAVGadget
{
Q_OBJECT
public:
DebugGadget(QString classId, DebugGadgetWidget *widget, QWidget *parent = 0);
~DebugGadget();
QList<int> context() const { return m_context; }
QWidget *widget() { return m_widget; }
QString contextHelpId() const { return QString(); }
private:
QWidget *m_widget;
QList<int> m_context;
};
#endif // DEBUGGADGET_H_

View File

@ -0,0 +1,21 @@
TEMPLATE = lib
TARGET = DebugGadget
include(../../openpilotgcsplugin.pri)
include(../../plugins/coreplugin/coreplugin.pri)
include(../../libs/libqxt/core/logengines.pri)
HEADERS += debugplugin.h \
debugengine.h
HEADERS += debuggadget.h
HEADERS += debuggadgetwidget.h
HEADERS += debuggadgetfactory.h
SOURCES += debugplugin.cpp \
debugengine.cpp
SOURCES += debuggadget.cpp
SOURCES += debuggadgetfactory.cpp
SOURCES += debuggadgetwidget.cpp
OTHER_FILES += DebugGadget.pluginspec
FORMS += \
debug.ui

View File

@ -0,0 +1,47 @@
/**
******************************************************************************
*
* @file debuggadgetfactory.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup DebugGadgetPlugin Debug Gadget Plugin
* @{
* @brief A place holder gadget plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "debuggadgetfactory.h"
#include "debuggadgetwidget.h"
#include "debuggadget.h"
#include <coreplugin/iuavgadget.h>
DebugGadgetFactory::DebugGadgetFactory(QObject *parent) :
IUAVGadgetFactory(QString("DebugGadget"),
tr("DebugGadget"),
parent)
{
}
DebugGadgetFactory::~DebugGadgetFactory()
{
}
IUAVGadget* DebugGadgetFactory::createGadget(QWidget *parent) {
DebugGadgetWidget* gadgetWidget = new DebugGadgetWidget(parent);
return new DebugGadget(QString("DebugGadget"), gadgetWidget, parent);
}

View File

@ -0,0 +1,50 @@
/**
******************************************************************************
*
* @file debuggadgetfactory.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup DebugGadgetPlugin Debug Gadget Plugin
* @{
* @brief A place holder gadget plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef DEBUGGADGETFACTORY_H_
#define DEBUGGADGETFACTORY_H_
#include <coreplugin/iuavgadgetfactory.h>
namespace Core {
class IUAVGadget;
class IUAVGadgetFactory;
}
using namespace Core;
class DebugGadgetFactory : public IUAVGadgetFactory
{
Q_OBJECT
public:
DebugGadgetFactory(QObject *parent = 0);
~DebugGadgetFactory();
IUAVGadget *createGadget(QWidget *parent);
};
#endif // DEBUGGADGETFACTORY_H_

View File

@ -0,0 +1,96 @@
/**
******************************************************************************
*
* @file debuggadgetwidget.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup DebugGadgetPlugin Debug Gadget Plugin
* @{
* @brief A place holder gadget plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "debuggadgetwidget.h"
#include <QDebug>
#include <QStringList>
#include <QtGui/QWidget>
#include <QtGui/QTextEdit>
#include <QtGui/QVBoxLayout>
#include <QtGui/QPushButton>
#include "qxtlogger.h"
#include "debugengine.h"
#include <QFile>
#include <QFileDialog>
#include <QMessageBox>
#include <QScrollBar>
#include <QTime>
DebugGadgetWidget::DebugGadgetWidget(QWidget *parent) : QLabel(parent)
{
m_config = new Ui_Form();
m_config->setupUi(this);
debugengine * de=new debugengine();
QxtLogger::getInstance()->addLoggerEngine("debugplugin", de);
connect(de,SIGNAL(dbgMsg(QString,QList<QVariant>)),this,SLOT(dbgMsg(QString,QList<QVariant>)));
connect(de,SIGNAL(dbgMsgError(QString,QList<QVariant>)),this,SLOT(dbgMsgError(QString,QList<QVariant>)));
connect(m_config->pushButton,SIGNAL(clicked()),this,SLOT(saveLog()));
}
DebugGadgetWidget::~DebugGadgetWidget()
{
// Do nothing
}
void DebugGadgetWidget::dbgMsg(const QString &level, const QList<QVariant> &msgs)
{
m_config->plainTextEdit->setTextColor(Qt::red);
m_config->plainTextEdit->append(QString("%2[%0]%1").arg(level).arg(msgs[0].toString()).arg(QTime::currentTime().toString()));
QScrollBar *sb = m_config->plainTextEdit->verticalScrollBar();
sb->setValue(sb->maximum());
}
void DebugGadgetWidget::dbgMsgError(const QString &level, const QList<QVariant> &msgs)
{
m_config->plainTextEdit->setTextColor(Qt::black);
m_config->plainTextEdit->append(QString("%2[%0]%1").arg(level).arg(msgs[0].toString()).arg(QTime::currentTime().toString()));
QScrollBar *sb = m_config->plainTextEdit->verticalScrollBar();
sb->setValue(sb->maximum());
}
void DebugGadgetWidget::saveLog()
{
QString fileName = QFileDialog::getSaveFileName(0, tr("Save log File As"), "");
if (fileName.isEmpty()) {
return;
}
QFile file(fileName);
if (file.open(QIODevice::WriteOnly) &&
(file.write(m_config->plainTextEdit->toHtml().toAscii()) != -1)) {
file.close();
} else {
QMessageBox::critical(0,
tr("Log Save"),
tr("Unable to save log: ") + fileName,
QMessageBox::Ok);
return;
}
}

View File

@ -0,0 +1,49 @@
/**
******************************************************************************
*
* @file debuggadgetwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup DebugGadgetPlugin Debug Gadget Plugin
* @{
* @brief A place holder gadget plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef DEBUGGADGETWIDGET_H_
#define DEBUGGADGETWIDGET_H_
#include <QtGui/QLabel>
#include "ui_debug.h"
class DebugGadgetWidget : public QLabel
{
Q_OBJECT
public:
DebugGadgetWidget(QWidget *parent = 0);
~DebugGadgetWidget();
private:
Ui_Form *m_config;
private slots:
void saveLog();
void dbgMsgError( const QString & level, const QList<QVariant> & msgs );
void dbgMsg( const QString & level, const QList<QVariant> & msgs );
};
#endif /* DEBUGGADGETWIDGET_H_ */

View File

@ -0,0 +1,65 @@
/**
******************************************************************************
*
* @file debugplugin.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup DebugGadgetPlugin Debug Gadget Plugin
* @{
* @brief A place holder gadget plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "debugplugin.h"
#include "debuggadgetfactory.h"
#include <QDebug>
#include <QtPlugin>
#include <QStringList>
#include <extensionsystem/pluginmanager.h>
DebugPlugin::DebugPlugin()
{
// Do nothing
}
DebugPlugin::~DebugPlugin()
{
// Do nothing
}
bool DebugPlugin::initialize(const QStringList& args, QString *errMsg)
{
Q_UNUSED(args);
Q_UNUSED(errMsg);
mf = new DebugGadgetFactory(this);
addAutoReleasedObject(mf);
return true;
}
void DebugPlugin::extensionsInitialized()
{
// Do nothing
}
void DebugPlugin::shutdown()
{
// Do nothing
}
Q_EXPORT_PLUGIN(DebugPlugin)

View File

@ -0,0 +1,47 @@
/**
******************************************************************************
*
* @file debugplugin.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup DebugGadgetPlugin Debug Gadget Plugin
* @{
* @brief A place holder gadget plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef DEBUGPLUGIN_H_
#define DEBUGPLUGIN_H_
#include <extensionsystem/iplugin.h>
class DebugGadgetFactory;
class DebugPlugin : public ExtensionSystem::IPlugin
{
public:
DebugPlugin();
~DebugPlugin();
void extensionsInitialized();
bool initialize(const QStringList & arguments, QString * errorString);
void shutdown();
private:
DebugGadgetFactory *mf;
};
#endif /* DEBUGPLUGIN_H_ */

View File

@ -19,6 +19,12 @@ plugin_emptygadget.subdir = emptygadget
plugin_emptygadget.depends = plugin_coreplugin
SUBDIRS += plugin_emptygadget
# UAV Settings Import/Export plugin
plugin_debuggadget.subdir = debuggadget
#plugin_debughelper.depends = plugin_coreplugin
#plugin_debughelper.depends += plugin_uavobjects
SUBDIRS += plugin_debuggadget
# Welcome plugin
plugin_welcome.subdir = welcome
plugin_welcome.depends = plugin_coreplugin
@ -107,6 +113,7 @@ SUBDIRS += plugin_systemhealth
plugin_config.subdir = config
plugin_config.depends = plugin_coreplugin
plugin_config.depends += plugin_uavobjects
plugin_config.depends += plugin_uavsettingsimportexport
SUBDIRS += plugin_config
#GPS Display gadget

View File

@ -37,7 +37,6 @@
#if defined( Q_OS_MAC)
// todo:
#elif defined(Q_OS_UNIX)
//#elif defined(Q_OS_LINUX)
@ -104,10 +103,12 @@ public:
void mytest(int num);
signals:
void deviceUnplugged(int);//just to make pips changes compile
private:
#if defined( Q_OS_MAC)
// todo:
#endif
private:
#if defined( Q_OS_MAC)
#elif defined(Q_OS_UNIX)
//#elif defined(Q_OS_LINUX)

View File

@ -44,6 +44,18 @@
#include <IOKit/hid/IOHIDLib.h>
#include <CoreFoundation/CFString.h>
#include <QString>
#include <QThread>
#include <QTimer>
#include <QCoreApplication>
class delay : public QThread
{
public:
static void msleep(unsigned long msecs)
{
QThread::msleep(msecs);
}
};
#define BUFFER_SIZE 64
@ -54,6 +66,8 @@ typedef struct hid_struct hid_t;
typedef struct buffer_struct buffer_t;
static hid_t *first_hid = NULL;
static hid_t *last_hid = NULL;
// Make sure we use the correct runloop
CFRunLoopRef the_correct_runloop = NULL;
struct hid_struct {
IOHIDDeviceRef ref;
int open;
@ -75,9 +89,10 @@ static void free_all_hid(void);
static void hid_close(hid_t *);
static void attach_callback(void *, IOReturn, void *, IOHIDDeviceRef);
static void detach_callback(void *, IOReturn, void *hid_mgr, IOHIDDeviceRef dev);
static void timeout_callback(CFRunLoopTimerRef, void *);
static void input_callback(void *, IOReturn, void *, IOHIDReportType, uint32_t, uint8_t *, CFIndex);
static void output_callback(hid_t *context, IOReturn ret, void *sender, IOHIDReportType type, uint32_t id, uint8_t *data, CFIndex len);
static void timeout_callback(CFRunLoopTimerRef, void *);
pjrc_rawhid::pjrc_rawhid()
{
@ -164,6 +179,8 @@ int pjrc_rawhid::open(int max, int vid, int pid, int usage_page, int usage)
CFRelease(hid_manager);
return 0;
}
// Set the run loop reference:
the_correct_runloop = CFRunLoopGetCurrent();
printf("run loop\n");
// let it do the callback for all devices
while (CFRunLoopRunInMode(kCFRunLoopDefaultMode, 0, true) == kCFRunLoopRunHandledSource) ;
@ -183,47 +200,56 @@ int pjrc_rawhid::open(int max, int vid, int pid, int usage_page, int usage)
//
int pjrc_rawhid::receive(int num, void *buf, int len, int timeout)
{
hid_t *hid;
buffer_t *b;
CFRunLoopTimerRef timer=NULL;
CFRunLoopTimerContext context;
int ret=0, timeout_occurred=0;
hid_t *hid;
buffer_t *b;
CFRunLoopTimerRef timer=NULL;
CFRunLoopTimerContext context;
int ret=0, timeout_occurred=0;
if (len < 1) return 0;
hid = get_hid(num);
if (!hid || !hid->open) return -1;
if ((b = hid->first_buffer) != NULL) {
if (len > b->len) len = b->len;
memcpy(buf, b->buf, len);
hid->first_buffer = b->next;
free(b);
return len;
}
memset(&context, 0, sizeof(context));
context.info = &timeout_occurred;
timer = CFRunLoopTimerCreate(NULL, CFAbsoluteTimeGetCurrent() +
(double)timeout / 1000.0, 0, 0, 0, timeout_callback, &context);
CFRunLoopAddTimer(CFRunLoopGetCurrent(), timer, kCFRunLoopDefaultMode);
while (1) {
CFRunLoopRun();
if ((b = hid->first_buffer) != NULL) {
if (len > b->len) len = b->len;
memcpy(buf, b->buf, len);
hid->first_buffer = b->next;
free(b);
ret = len;
if (len < 1) return 0;
hid = get_hid(num);
if (!hid || !hid->open) return -1;
if ((b = hid->first_buffer) != NULL) {
if (len > b->len) len = b->len;
memcpy(buf, b->buf, len);
hid->first_buffer = b->next;
free(b);
return len;
}
memset(&context, 0, sizeof(context));
context.info = &timeout_occurred;
timer = CFRunLoopTimerCreate(NULL, CFAbsoluteTimeGetCurrent() +
(double)timeout / 1000.0, 0, 0, 0, timeout_callback, &context);
CFRunLoopAddTimer(CFRunLoopGetCurrent(), timer, kCFRunLoopDefaultMode);
the_correct_runloop = CFRunLoopGetCurrent();
//qDebug("--");
while (1) {
//qDebug(".");
CFRunLoopRun(); // Found the problem: somehow the input_callback does not
// stop this CFRunLoopRun because it is hooked to a different run loop !!!
// Hence the use of the "correct_runloop" variable above.
//qDebug(" ..");
if ((b = hid->first_buffer) != NULL) {
if (len > b->len) len = b->len;
memcpy(buf, b->buf, len);
hid->first_buffer = b->next;
free(b);
ret = len;
//qDebug("*************");
break;
}
if (!hid->open) {
printf("pjrc_rawhid_recv, device not open\n");
ret = -1;
break;
}
if (timeout_occurred)
break;
}
if (!hid->open) {
printf("pjrc_rawhid_recv, device not open\n");
ret = -1;
break;
}
if (timeout_occurred) break;
}
CFRunLoopTimerInvalidate(timer);
CFRelease(timer);
return ret;
}
CFRunLoopTimerInvalidate(timer);
CFRelease(timer);
return ret;
}
// send - send a packet
@ -335,10 +361,11 @@ static void input_callback(void *context, IOReturn ret, void *sender, IOHIDRepor
buffer_t *n;
hid_t *hid;
printf("input_callback, report id: %i buf: %x %x, len: %d\n", id, data[0], data[1], len);
//qDebug("input_callback, ret: %i - report id: %i buf: %x %x, len: %d\n", ret, id, data[0], data[1], len);
if (ret != kIOReturnSuccess || len < 1) return;
hid = (hid_t*)context;
if (!hid || hid->ref != sender) return;
printf("Processing packet");
n = (buffer_t *)malloc(sizeof(buffer_t));
if (!n) return;
if (len > BUFFER_SIZE) len = BUFFER_SIZE;
@ -352,14 +379,16 @@ static void input_callback(void *context, IOReturn ret, void *sender, IOHIDRepor
hid->last_buffer->next = n;
hid->last_buffer = n;
}
CFRunLoopStop(CFRunLoopGetCurrent());
//qDebug() << "Stop CFRunLoop from input_callback" << CFRunLoopGetCurrent();
CFRunLoopStop(the_correct_runloop);
}
static void timeout_callback(CFRunLoopTimerRef timer, void *info)
{
printf("timeout_callback\n");
*(int *)info = 1;
CFRunLoopStop(CFRunLoopGetCurrent());
//qDebug("timeout_callback\n");
*(int *)info = 1;
//qDebug() << "Stop CFRunLoop from timeout_callback" << CFRunLoopGetCurrent();
CFRunLoopStop(CFRunLoopGetCurrent());
}
static void add_hid(hid_t *h)

View File

@ -31,7 +31,7 @@
#include <QStringList>
#include <QDebug>
#include <QCheckBox>
#include "importsummary.h"
// for menu item
#include <coreplugin/coreconstants.h>
#include <coreplugin/actionmanager/actionmanager.h>
@ -62,321 +62,20 @@ UAVSettingsImportExportPlugin::~UAVSettingsImportExportPlugin()
bool UAVSettingsImportExportPlugin::initialize(const QStringList& args, QString *errMsg)
{
Q_UNUSED(args);
Q_UNUSED(errMsg);
// Add Menu entry
Core::ActionManager* am = Core::ICore::instance()->actionManager();
Core::ActionContainer* ac = am->actionContainer(Core::Constants::M_FILE);
Core::Command* cmd = am->registerAction(new QAction(this),
"UAVSettingsImportExportPlugin.UAVSettingsExport",
QList<int>() <<
Core::Constants::C_GLOBAL_ID);
cmd->setDefaultKeySequence(QKeySequence("Ctrl+E"));
cmd->action()->setText(tr("Export UAV Settings..."));
ac->addAction(cmd, Core::Constants::G_FILE_SAVE);
connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVSettings()));
cmd = am->registerAction(new QAction(this),
"UAVSettingsImportExportPlugin.UAVSettingsImport",
QList<int>() <<
Core::Constants::C_GLOBAL_ID);
cmd->setDefaultKeySequence(QKeySequence("Ctrl+I"));
cmd->action()->setText(tr("Import UAV Settings..."));
ac->addAction(cmd, Core::Constants::G_FILE_SAVE);
connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(importUAVSettings()));
cmd = am->registerAction(new QAction(this),
"UAVSettingsImportExportPlugin.UAVDataExport",
QList<int>() <<
Core::Constants::C_GLOBAL_ID);
cmd->action()->setText(tr("Export UAV Data..."));
ac->addAction(cmd, Core::Constants::G_FILE_SAVE);
connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVData()));
Q_UNUSED(args);
Q_UNUSED(errMsg);
mf = new UAVSettingsImportExportFactory(this);
addAutoReleasedObject(mf);
return true;
}
void UAVSettingsImportExportPlugin::extensionsInitialized()
{
// Do nothing
}
// Slot called by the menu manager on user action
void UAVSettingsImportExportPlugin::importUAVSettings()
{
// ask for file name
QString fileName;
QString filters = tr("UAVSettings XML files (*.uav);; XML files (*.xml)");
fileName = QFileDialog::getOpenFileName(0, tr("Import UAV Settings"), "", filters);
if (fileName.isEmpty()) {
return;
}
// Now open the file
QFile file(fileName);
QDomDocument doc("UAVSettings");
file.open(QFile::ReadOnly|QFile::Text);
if (!doc.setContent(file.readAll())) {
QMessageBox msgBox;
msgBox.setText(tr("File Parsing Failed."));
msgBox.setInformativeText(tr("This file is not a correct XML file"));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.exec();
return;
}
file.close();
QDomElement root = doc.documentElement();
if (root.tagName() != "settings") {
QMessageBox msgBox;
msgBox.setText(tr("Wrong file contents."));
msgBox.setInformativeText(tr("This file is not a correct UAVSettings file"));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.exec();
return;
}
// We are now ok: setup the import summary dialog & update it as we
// go along.
ImportSummaryDialog swui;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
swui.show();
QDomNode node = root.firstChild();
while (!node.isNull()) {
QDomElement e = node.toElement();
if (e.tagName() == "object") {
// - Read each object
QString uavObjectName = e.attribute("name");
uint uavObjectID = e.attribute("id").toUInt(NULL,16);
// Sanity Check:
UAVObject* obj = objManager->getObject(uavObjectName);
if (obj == NULL) {
// This object is unknown!
qDebug() << "Object unknown:" << uavObjectName << uavObjectID;
swui.addLine(uavObjectName, "Error (Object unknown)", false);
} else {
// - Update each field
// - Issue and "updated" command
bool error=false;
QDomNode field = node.firstChild();
while(!field.isNull()) {
QDomElement f = field.toElement();
if (f.tagName() == "field") {
UAVObjectField *uavfield = obj->getField(f.attribute("name"));
if (uavfield) {
QStringList list = f.attribute("values").split(",");
if (list.length() == 1) {
uavfield->setValue(f.attribute("values"));
} else {
// This is an enum:
int i=0;
QStringList list = f.attribute("values").split(",");
foreach (QString element, list) {
uavfield->setValue(element,i++);
}
}
error = false;
} else {
error = true;
}
}
field = field.nextSibling();
}
obj->updated();
if (error) {
swui.addLine(uavObjectName, "Warning (Object field unknown)", true);
} else if (uavObjectID != obj->getObjID()) {
qDebug() << "Mismatch for Object " << uavObjectName << uavObjectID << " - " << obj->getObjID();
swui.addLine(uavObjectName, "Warning (ObjectID mismatch)", true);
} else
swui.addLine(uavObjectName, "OK", true);
}
}
node = node.nextSibling();
}
swui.exec();
}
// Create an XML document from UAVObject database
QString UAVSettingsImportExportPlugin::createXMLDocument(
const QString docName, const bool isSettings, const bool fullExport)
{
// generate an XML first (used for all export formats as a formatted data source)
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
QDomDocument doc(docName);
QDomElement root = doc.createElement(isSettings ? "settings" : "data");
doc.appendChild(root);
QDomElement versionInfo =doc.createElement("versionInfo");
root.appendChild(versionInfo);
QDomElement fw=doc.createElement("Embedded");
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
fw.setAttribute("gitcommittag",utilMngr->getBoardDescriptionStruct().gitTag);
fw.setAttribute("fwtag",utilMngr->getBoardDescriptionStruct().description);
fw.setAttribute("cpuSerial",QString(utilMngr->getBoardCPUSerial().toHex()));
versionInfo.appendChild(fw);
QDomElement gcs=doc.createElement("GCS");
gcs.setAttribute("revision",QString::fromLatin1(Core::Constants::GCS_REVISION_STR));
versionInfo.appendChild(gcs);
// iterate over settings objects
QList< QList<UAVDataObject*> > objList = objManager->getDataObjects();
foreach (QList<UAVDataObject*> list, objList) {
foreach (UAVDataObject* obj, list) {
if (obj->isSettings() == isSettings) {
// add each object to the XML
QDomElement o = doc.createElement("object");
o.setAttribute("name", obj->getName());
o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper());
if (fullExport) {
QDomElement d = doc.createElement("description");
QDomText t = doc.createTextNode(obj->getDescription().remove("@Ref ", Qt::CaseInsensitive));
d.appendChild(t);
o.appendChild(d);
}
// iterate over fields
QList<UAVObjectField*> fieldList = obj->getFields();
foreach (UAVObjectField* field, fieldList) {
QDomElement f = doc.createElement("field");
// iterate over values
QString vals;
quint32 nelem = field->getNumElements();
for (unsigned int n = 0; n < nelem; ++n) {
vals.append(QString("%1,").arg(field->getValue(n).toString()));
}
vals.chop(1);
f.setAttribute("name", field->getName());
f.setAttribute("values", vals);
if (fullExport) {
f.setAttribute("type", field->getTypeAsString());
f.setAttribute("units", field->getUnits());
f.setAttribute("elements", nelem);
if (field->getType() == UAVObjectField::ENUM) {
f.setAttribute("options", field->getOptions().join(","));
}
}
o.appendChild(f);
}
root.appendChild(o);
}
}
}
return doc.toString(4);
}
// Slot called by the menu manager on user action
void UAVSettingsImportExportPlugin::exportUAVSettings()
{
// ask for file name
QString fileName;
QString filters = tr("UAVSettings XML files (*.uav)");
fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Settings File As"), "", filters);
if (fileName.isEmpty()) {
return;
}
bool fullExport = false;
// If the filename ends with .xml, we will do a full export, otherwise, a simple export
if (fileName.endsWith(".xml")) {
fullExport = true;
} else if (!fileName.endsWith(".uav")) {
fileName.append(".uav");
}
// generate an XML first (used for all export formats as a formatted data source)
QString xml = createXMLDocument("UAVSettings", true, fullExport);
// save file
QFile file(fileName);
if (file.open(QIODevice::WriteOnly) &&
(file.write(xml.toAscii()) != -1)) {
file.close();
} else {
QMessageBox::critical(0,
tr("UAV Settings Export"),
tr("Unable to save settings: ") + fileName,
QMessageBox::Ok);
return;
}
QMessageBox msgBox;
msgBox.setText(tr("Settings saved."));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.exec();
}
// Slot called by the menu manager on user action
void UAVSettingsImportExportPlugin::exportUAVData()
{
if (QMessageBox::question(0, tr("Are you sure?"),
tr("This option is only useful for passing your current "
"system data to the technical support staff. "
"Do you really want to export?"),
QMessageBox::Ok | QMessageBox::Cancel,
QMessageBox::Ok) != QMessageBox::Ok) {
return;
}
// ask for file name
QString fileName;
QString filters = tr("UAVData XML files (*.uav)");
fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Data File As"), "", filters);
if (fileName.isEmpty()) {
return;
}
bool fullExport = false;
// If the filename ends with .xml, we will do a full export, otherwise, a simple export
if (fileName.endsWith(".xml")) {
fullExport = true;
} else if (!fileName.endsWith(".uav")) {
fileName.append(".uav");
}
// generate an XML first (used for all export formats as a formatted data source)
QString xml = createXMLDocument("UAVData", false, fullExport);
// save file
QFile file(fileName);
if (file.open(QIODevice::WriteOnly) &&
(file.write(xml.toAscii()) != -1)) {
file.close();
} else {
QMessageBox::critical(0,
tr("UAV Data Export"),
tr("Unable to save data: ") + fileName,
QMessageBox::Ok);
return;
}
QMessageBox msgBox;
msgBox.setText(tr("Data saved."));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.exec();
}
void UAVSettingsImportExportPlugin::shutdown()
{
// Do nothing
}
void UAVSettingsImportExportPlugin::extensionsInitialized()
{
}
Q_EXPORT_PLUGIN(UAVSettingsImportExportPlugin)

View File

@ -29,9 +29,10 @@
#include <extensionsystem/iplugin.h>
#include "uavobjectutil/uavobjectutilmanager.h"
#include "importsummary.h"
#include "uavsettingsimportexport_global.h"
#include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h"
class UAVSettingsImportExportPlugin : public ExtensionSystem::IPlugin
#include "uavsettingsimportexportfactory.h"
class UAVSETTINGSIMPORTEXPORT_EXPORT UAVSettingsImportExportPlugin : public ExtensionSystem::IPlugin
{
Q_OBJECT
@ -42,16 +43,10 @@ public:
void extensionsInitialized();
bool initialize(const QStringList & arguments, QString * errorString);
void shutdown();
private:
QString createXMLDocument(const QString docName,
const bool isSettings,
const bool fullExport);
UAVSettingsImportExportFactory *mf;
private slots:
void importUAVSettings();
void exportUAVSettings();
void exportUAVData();
};

View File

@ -0,0 +1,2 @@
include(uavsettingsimportexport_dependencies.pri)
LIBS *= -l$$qtLibraryName(UAVSettingsImportExport)

View File

@ -3,14 +3,16 @@ TEMPLATE = lib
QT += xml
TARGET = UAVSettingsImportExport
DEFINES += UAVSETTINGSIMPORTEXPORT_LIBRARY
include(../../openpilotgcsplugin.pri)
include(uavsettingsimportexport_dependencies.pri)
HEADERS += uavsettingsimportexport.h \
importsummary.h
importsummary.h \
uavsettingsimportexportfactory.h
SOURCES += uavsettingsimportexport.cpp \
importsummary.cpp
importsummary.cpp \
uavsettingsimportexportfactory.cpp
OTHER_FILES += uavsettingsimportexport.pluginspec

View File

@ -0,0 +1,40 @@
/**
******************************************************************************
*
* @file uavsettingsimportexport_global.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @see The GNU Public License (GPL) Version 3
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup
* @{
* @brief
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef UAVSETTINGSIMPORTEXPORT_GLOBAL_H
#define UAVSETTINGSIMPORTEXPORT_GLOBAL_H
#include <QtCore/qglobal.h>
#if defined(UAVSETTINGSIMPORTEXPORT_LIBRARY)
# define UAVSETTINGSIMPORTEXPORT_EXPORT Q_DECL_EXPORT
#else
# define UAVSETTINGSIMPORTEXPORT_EXPORT Q_DECL_IMPORT
#endif
#endif // UAVSETTINGSIMPORTEXPORT_GLOBAL_H

View File

@ -0,0 +1,365 @@
/**
******************************************************************************
*
* @file uavsettingsimportexportfactory.cpp
* @author (C) 2011 The OpenPilot Team, http://www.openpilot.org
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup UAVSettingsImportExport UAVSettings Import/Export Plugin
* @{
* @brief UAVSettings Import/Export Plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "uavsettingsimportexportfactory.h"
#include <QtPlugin>
#include <QStringList>
#include <QDebug>
#include <QCheckBox>
#include "importsummary.h"
// for menu item
#include <coreplugin/coreconstants.h>
#include <coreplugin/actionmanager/actionmanager.h>
#include <coreplugin/icore.h>
#include <QKeySequence>
// for UAVObjects
#include "uavdataobject.h"
#include "uavobjectmanager.h"
#include "extensionsystem/pluginmanager.h"
// for XML object
#include <QDomDocument>
// for file dialog and error messages
#include <QFileDialog>
#include <QMessageBox>
UAVSettingsImportExportFactory::~UAVSettingsImportExportFactory()
{
// Do nothing
}
UAVSettingsImportExportFactory::UAVSettingsImportExportFactory(QObject * parent):QObject(parent)
{
// Add Menu entry
Core::ActionManager* am = Core::ICore::instance()->actionManager();
Core::ActionContainer* ac = am->actionContainer(Core::Constants::M_FILE);
Core::Command* cmd = am->registerAction(new QAction(this),
"UAVSettingsImportExportPlugin.UAVSettingsExport",
QList<int>() <<
Core::Constants::C_GLOBAL_ID);
cmd->setDefaultKeySequence(QKeySequence("Ctrl+E"));
cmd->action()->setText(tr("Export UAV Settings..."));
ac->addAction(cmd, Core::Constants::G_FILE_SAVE);
connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVSettings()));
cmd = am->registerAction(new QAction(this),
"UAVSettingsImportExportPlugin.UAVSettingsImport",
QList<int>() <<
Core::Constants::C_GLOBAL_ID);
cmd->setDefaultKeySequence(QKeySequence("Ctrl+I"));
cmd->action()->setText(tr("Import UAV Settings..."));
ac->addAction(cmd, Core::Constants::G_FILE_SAVE);
connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(importUAVSettings()));
cmd = am->registerAction(new QAction(this),
"UAVSettingsImportExportPlugin.UAVDataExport",
QList<int>() <<
Core::Constants::C_GLOBAL_ID);
cmd->action()->setText(tr("Export UAV Data..."));
ac->addAction(cmd, Core::Constants::G_FILE_SAVE);
connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVData()));
}
// Slot called by the menu manager on user action
void UAVSettingsImportExportFactory::importUAVSettings()
{
// ask for file name
QString fileName;
QString filters = tr("UAVSettings XML files (*.uav);; XML files (*.xml)");
fileName = QFileDialog::getOpenFileName(0, tr("Import UAV Settings"), "", filters);
if (fileName.isEmpty()) {
return;
}
// Now open the file
QFile file(fileName);
QDomDocument doc("UAVSettings");
file.open(QFile::ReadOnly|QFile::Text);
if (!doc.setContent(file.readAll())) {
QMessageBox msgBox;
msgBox.setText(tr("File Parsing Failed."));
msgBox.setInformativeText(tr("This file is not a correct XML file"));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.exec();
return;
}
file.close();
emit importAboutToBegin();
qDebug()<<"Import about to begin";
QDomElement root = doc.documentElement();
if (root.tagName() != "settings") {
QMessageBox msgBox;
msgBox.setText(tr("Wrong file contents."));
msgBox.setInformativeText(tr("This file is not a correct UAVSettings file"));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.exec();
return;
}
// We are now ok: setup the import summary dialog & update it as we
// go along.
ImportSummaryDialog swui;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
swui.show();
QDomNode node = root.firstChild();
while (!node.isNull()) {
QDomElement e = node.toElement();
if (e.tagName() == "object") {
// - Read each object
QString uavObjectName = e.attribute("name");
uint uavObjectID = e.attribute("id").toUInt(NULL,16);
// Sanity Check:
UAVObject* obj = objManager->getObject(uavObjectName);
if (obj == NULL) {
// This object is unknown!
qDebug() << "Object unknown:" << uavObjectName << uavObjectID;
swui.addLine(uavObjectName, "Error (Object unknown)", false);
} else {
// - Update each field
// - Issue and "updated" command
bool error=false;
QDomNode field = node.firstChild();
while(!field.isNull()) {
QDomElement f = field.toElement();
if (f.tagName() == "field") {
UAVObjectField *uavfield = obj->getField(f.attribute("name"));
if (uavfield) {
QStringList list = f.attribute("values").split(",");
if (list.length() == 1) {
uavfield->setValue(f.attribute("values"));
} else {
// This is an enum:
int i=0;
QStringList list = f.attribute("values").split(",");
foreach (QString element, list) {
uavfield->setValue(element,i++);
}
}
error = false;
} else {
error = true;
}
}
field = field.nextSibling();
}
obj->updated();
if (error) {
swui.addLine(uavObjectName, "Warning (Object field unknown)", true);
} else if (uavObjectID != obj->getObjID()) {
qDebug() << "Mismatch for Object " << uavObjectName << uavObjectID << " - " << obj->getObjID();
swui.addLine(uavObjectName, "Warning (ObjectID mismatch)", true);
} else
swui.addLine(uavObjectName, "OK", true);
}
}
node = node.nextSibling();
}
qDebug()<<"End import";
swui.exec();
}
// Create an XML document from UAVObject database
QString UAVSettingsImportExportFactory::createXMLDocument(
const QString docName, const bool isSettings, const bool fullExport)
{
// generate an XML first (used for all export formats as a formatted data source)
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
QDomDocument doc(docName);
QDomElement root = doc.createElement(isSettings ? "settings" : "data");
doc.appendChild(root);
QDomElement versionInfo =doc.createElement("versionInfo");
root.appendChild(versionInfo);
QDomElement fw=doc.createElement("Embedded");
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
fw.setAttribute("gitcommittag",utilMngr->getBoardDescriptionStruct().gitTag);
fw.setAttribute("fwtag",utilMngr->getBoardDescriptionStruct().description);
fw.setAttribute("cpuSerial",QString(utilMngr->getBoardCPUSerial().toHex()));
versionInfo.appendChild(fw);
QDomElement gcs=doc.createElement("GCS");
gcs.setAttribute("revision",QString::fromLatin1(Core::Constants::GCS_REVISION_STR));
versionInfo.appendChild(gcs);
// iterate over settings objects
QList< QList<UAVDataObject*> > objList = objManager->getDataObjects();
foreach (QList<UAVDataObject*> list, objList) {
foreach (UAVDataObject* obj, list) {
if (obj->isSettings() == isSettings) {
// add each object to the XML
QDomElement o = doc.createElement("object");
o.setAttribute("name", obj->getName());
o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper());
if (fullExport) {
QDomElement d = doc.createElement("description");
QDomText t = doc.createTextNode(obj->getDescription().remove("@Ref ", Qt::CaseInsensitive));
d.appendChild(t);
o.appendChild(d);
}
// iterate over fields
QList<UAVObjectField*> fieldList = obj->getFields();
foreach (UAVObjectField* field, fieldList) {
QDomElement f = doc.createElement("field");
// iterate over values
QString vals;
quint32 nelem = field->getNumElements();
for (unsigned int n = 0; n < nelem; ++n) {
vals.append(QString("%1,").arg(field->getValue(n).toString()));
}
vals.chop(1);
f.setAttribute("name", field->getName());
f.setAttribute("values", vals);
if (fullExport) {
f.setAttribute("type", field->getTypeAsString());
f.setAttribute("units", field->getUnits());
f.setAttribute("elements", nelem);
if (field->getType() == UAVObjectField::ENUM) {
f.setAttribute("options", field->getOptions().join(","));
}
}
o.appendChild(f);
}
root.appendChild(o);
}
}
}
return doc.toString(4);
}
// Slot called by the menu manager on user action
void UAVSettingsImportExportFactory::exportUAVSettings()
{
// ask for file name
QString fileName;
QString filters = tr("UAVSettings XML files (*.uav)");
fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Settings File As"), "", filters);
if (fileName.isEmpty()) {
return;
}
bool fullExport = false;
// If the filename ends with .xml, we will do a full export, otherwise, a simple export
if (fileName.endsWith(".xml")) {
fullExport = true;
} else if (!fileName.endsWith(".uav")) {
fileName.append(".uav");
}
// generate an XML first (used for all export formats as a formatted data source)
QString xml = createXMLDocument("UAVSettings", true, fullExport);
// save file
QFile file(fileName);
if (file.open(QIODevice::WriteOnly) &&
(file.write(xml.toAscii()) != -1)) {
file.close();
} else {
QMessageBox::critical(0,
tr("UAV Settings Export"),
tr("Unable to save settings: ") + fileName,
QMessageBox::Ok);
return;
}
QMessageBox msgBox;
msgBox.setText(tr("Settings saved."));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.exec();
}
// Slot called by the menu manager on user action
void UAVSettingsImportExportFactory::exportUAVData()
{
if (QMessageBox::question(0, tr("Are you sure?"),
tr("This option is only useful for passing your current "
"system data to the technical support staff. "
"Do you really want to export?"),
QMessageBox::Ok | QMessageBox::Cancel,
QMessageBox::Ok) != QMessageBox::Ok) {
return;
}
// ask for file name
QString fileName;
QString filters = tr("UAVData XML files (*.uav)");
fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Data File As"), "", filters);
if (fileName.isEmpty()) {
return;
}
bool fullExport = false;
// If the filename ends with .xml, we will do a full export, otherwise, a simple export
if (fileName.endsWith(".xml")) {
fullExport = true;
} else if (!fileName.endsWith(".uav")) {
fileName.append(".uav");
}
// generate an XML first (used for all export formats as a formatted data source)
QString xml = createXMLDocument("UAVData", false, fullExport);
// save file
QFile file(fileName);
if (file.open(QIODevice::WriteOnly) &&
(file.write(xml.toAscii()) != -1)) {
file.close();
} else {
QMessageBox::critical(0,
tr("UAV Data Export"),
tr("Unable to save data: ") + fileName,
QMessageBox::Ok);
return;
}
QMessageBox msgBox;
msgBox.setText(tr("Data saved."));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.exec();
}

View File

@ -0,0 +1,55 @@
/**
******************************************************************************
*
* @file uavsettingsimportexportfactory.h
* @author (C) 2011 The OpenPilot Team, http://www.openpilot.org
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup UAVSettingsImportExport UAVSettings Import/Export Plugin
* @{
* @brief UAVSettings Import/Export Plugin
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef UAVSETTINGSIMPORTEXPORTFACTORY_H
#define UAVSETTINGSIMPORTEXPORTFACTORY_H
#include "uavsettingsimportexport_global.h"
#include "uavobjectutil/uavobjectutilmanager.h"
#include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h"
class UAVSETTINGSIMPORTEXPORT_EXPORT UAVSettingsImportExportFactory : public QObject
{
Q_OBJECT
public:
UAVSettingsImportExportFactory(QObject *parent = 0);
~UAVSettingsImportExportFactory();
private:
QString createXMLDocument(const QString docName,
const bool isSettings,
const bool fullExport);
private slots:
void importUAVSettings();
void exportUAVSettings();
void exportUAVData();
signals:
void importAboutToBegin();
void importEnded();
};
#endif // UAVSETTINGSIMPORTEXPORTFACTORY_H

View File

@ -282,9 +282,15 @@ bool UAVTalk::processInputByte(quint8 rxbyte)
// Determine data length
if (rxType == TYPE_OBJ_REQ || rxType == TYPE_ACK || rxType == TYPE_NACK)
{
rxLength = 0;
rxInstanceLength = 0;
}
else
{
rxLength = rxObj->getNumBytes();
rxInstanceLength = (rxObj->isSingleInstance() ? 0 : 2);
}
// Check length and determine next state
if (rxLength >= MAX_PAYLOAD_LENGTH)
@ -295,7 +301,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte)
}
// Check the lengths match
if ((rxPacketLength + rxLength + (rxObj->isSingleInstance() ? 0 : 2)) != packetSize)
if ((rxPacketLength + rxInstanceLength + rxLength) != packetSize)
{ // packet error - mismatched packet size
stats.rxErrors++;
rxState = STATE_SYNC;

View File

@ -107,6 +107,7 @@ private:
quint16 rxInstId;
quint16 rxLength;
quint16 rxPacketLength;
quint8 rxInstanceLength;
quint8 rxCSPacket, rxCS;
qint32 rxCount;

View File

@ -48,7 +48,8 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent)
connect(m_config->resetButton, SIGNAL(clicked()), this, SLOT(systemReset()));
connect(m_config->bootButton, SIGNAL(clicked()), this, SLOT(systemBoot()));
connect(m_config->rescueButton, SIGNAL(clicked()), this, SLOT(systemRescue()));
Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager();
connect(cm,SIGNAL(deviceConnected(QIODevice*)),this,SLOT(onPhisicalHWConnect()));
getSerialPorts();
QIcon rbi;
@ -105,7 +106,12 @@ QString UploaderGadgetWidget::getPortDevice(const QString &friendName)
}
return "";
}
void UploaderGadgetWidget::onPhisicalHWConnect()
{
m_config->bootButton->setEnabled(false);
m_config->rescueButton->setEnabled(false);
m_config->telemetryLink->setEnabled(false);
}
/**
Enables widget buttons if autopilot connected

View File

@ -85,6 +85,7 @@ private:
QLineEdit* openFileNameLE;
QEventLoop m_eventloop;
private slots:
void onPhisicalHWConnect();
void error(QString errorString,int errorNumber);
void info(QString infoString,int infoNumber);
void goToBootloader(UAVObject* = NULL, bool = false);

View File

@ -31,7 +31,7 @@
#include "generator_io.h"
// These special chars (regexp) will be removed from C/java identifiers
#define ENUM_SPECIAL_CHARS "[\\.\\-\\s/]"
#define ENUM_SPECIAL_CHARS "[\\.\\-\\s\\+/]"
void replaceCommonTags(QString& out, ObjectInfo* info);
void replaceCommonTags(QString& out);

View File

@ -1,7 +1,7 @@
<xml>
<object name="ActuatorCommand" singleinstance="true" settings="false">
<description>Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule</description>
<field name="Channel" units="us" type="int16" elements="8"/>
<field name="Channel" units="us" type="int16" elements="10"/>
<field name="UpdateTime" units="ms" type="uint8" elements="1"/>
<field name="MaxUpdateTime" units="ms" type="uint16" elements="1"/>
<field name="NumFailedUpdates" units="" type="uint8" elements="1"/>

View File

@ -1,27 +1,27 @@
<xml>
<object name="ActuatorSettings" singleinstance="true" settings="true">
<description>Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType</description>
<field name="FixedWingRoll1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="FixedWingRoll2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="FixedWingPitch1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="FixedWingPitch2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="FixedWingYaw1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="FixedWingYaw2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="FixedWingThrottle" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="VTOLMotorN" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="VTOLMotorNE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="VTOLMotorE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="VTOLMotorSE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="VTOLMotorS" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="VTOLMotorSW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="VTOLMotorW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="VTOLMotorNW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/>
<field name="FixedWingRoll1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingRoll2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingPitch1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingPitch2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingYaw1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingYaw2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingThrottle" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorN" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorNE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorSE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorS" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorSW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorNW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="ChannelUpdateFreq" units="Hz" type="uint16" elements="4" defaultvalue="50"/>
<field name="ChannelMax" units="us" type="int16" elements="8" defaultvalue="1000"/>
<field name="ChannelNeutral" units="us" type="int16" elements="8" defaultvalue="1000"/>
<field name="ChannelMin" units="us" type="int16" elements="8" defaultvalue="1000"/>
<field name="ChannelType" units="" type="enum" elements="8" options="PWM,MK,ASTEC4,PWM Alarm Buzzer" defaultvalue="PWM"/>
<field name="ChannelAddr" units="" type="uint8" elements="8" defaultvalue="0,1,2,3,4,5,6,7"/>
<field name="ChannelMax" units="us" type="int16" elements="10" defaultvalue="1000"/>
<field name="ChannelNeutral" units="us" type="int16" elements="10" defaultvalue="1000"/>
<field name="ChannelMin" units="us" type="int16" elements="10" defaultvalue="1000"/>
<field name="ChannelType" units="" type="enum" elements="10" options="PWM,MK,ASTEC4,PWM Alarm Buzzer" defaultvalue="PWM"/>
<field name="ChannelAddr" units="" type="uint8" elements="10" defaultvalue="0,1,2,3,4,5,6,7,8,9"/>
<field name="MotorsSpinWhileArmed" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>

View File

@ -3,7 +3,7 @@
<description>Selection of optional hardware configurations.</description>
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,Spektrum1,Spektrum2,ComAux,I2C" defaultvalue="Disabled"/>
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,S.Bus,GPS,Spektrum1,Spektrum2,ComAux" defaultvalue="Telemetry"/>
<field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM" defaultvalue="PWM"/>
<field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+Servo,Servo" defaultvalue="PWM"/>
<field name="OP_FlexiPort" units="function" type="enum" elements="1" options="Disabled,GPS" defaultvalue="GPS"/>
<field name="OP_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry" defaultvalue="Telemetry"/>

View File

@ -24,6 +24,10 @@
<field name="Mixer7Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
<field name="Mixer8Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
<field name="Mixer8Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
<field name="Mixer9Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
<field name="Mixer9Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
<field name="Mixer10Type" units="" type="enum" elements="1" options="Disabled,Motor,Servo,CameraRoll,CameraPitch,CameraYaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5" defaultvalue="Disabled"/>
<field name="Mixer10Vector" units="" type="int8" elements="5" elementnames="ThrottleCurve1,ThrottleCurve2,Roll,Pitch,Yaw" defaultvalue="0"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>