mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
Merge remote-tracking branch 'remotes/origin/next' into GCS_ChangesToUI-RuntimeCFG
Conflicts: ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp ground/openpilotgcs/src/plugins/config/configgadgetwidget.h ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp
This commit is contained in:
commit
e736b17cc4
56
HISTORY.txt
56
HISTORY.txt
@ -1,26 +1,30 @@
|
||||
Short summary of changes. For a complete list see the git log.
|
||||
|
||||
2011-07-29
|
||||
Added support for PPM receivers from James W. Now all 4 interfaces (R/C
|
||||
standard PWM, combined PPM (MK), Spektrum satellite, Futaba S.Bus) are
|
||||
supported and configurable through the GCS hardware configuration tab.
|
||||
|
||||
2011-07-17
|
||||
Updated module initialization from Mathieu which separates the initialization
|
||||
from the task startup. Also implements a method to reclaim unused ram from
|
||||
initialization and end of memory for the FreeRTOS heap.
|
||||
|
||||
2011-07-12
|
||||
Improvements to the stabilization code. Included a LPF on the gyros to smooth
|
||||
out noise in high vibration environments. Also two new modes: axis-lock and
|
||||
weak leveling. Axis-lock will try and hold an axis at a fixed position and
|
||||
reject any disturbances. This is like heading-hold on a heli for the tail but
|
||||
can be useful for other axes. Weak leveling is rate mode with a weak
|
||||
correction to self level the craft - good for easier rate mode flying.
|
||||
|
||||
2011-07-07
|
||||
Dynamic hardware configuration from Stac. The input type is now
|
||||
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.
|
||||
Short summary of changes. For a complete list see the git log.
|
||||
|
||||
2011-08-04
|
||||
Fixed packaging aesthetic issues. Also avoid runtime issues on OSX Lion by
|
||||
disabling the ModelView and Notify plugins for now (sorry).
|
||||
|
||||
2011-07-29
|
||||
Added support for PPM receivers from James W. Now all 4 interfaces (R/C
|
||||
standard PWM, combined PPM (MK), Spektrum satellite, Futaba S.Bus) are
|
||||
supported and configurable through the GCS hardware configuration tab.
|
||||
|
||||
2011-07-17
|
||||
Updated module initialization from Mathieu which separates the initialization
|
||||
from the task startup. Also implements a method to reclaim unused ram from
|
||||
initialization and end of memory for the FreeRTOS heap.
|
||||
|
||||
2011-07-12
|
||||
Improvements to the stabilization code. Included a LPF on the gyros to smooth
|
||||
out noise in high vibration environments. Also two new modes: axis-lock and
|
||||
weak leveling. Axis-lock will try and hold an axis at a fixed position and
|
||||
reject any disturbances. This is like heading-hold on a heli for the tail but
|
||||
can be useful for other axes. Weak leveling is rate mode with a weak
|
||||
correction to self level the craft - good for easier rate mode flying.
|
||||
|
||||
2011-07-07
|
||||
Dynamic hardware configuration from Stac. The input type is now
|
||||
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.
|
||||
|
@ -100,10 +100,13 @@
|
||||
#define PIOS_SYSTEM_STACK_SIZE 460
|
||||
#define PIOS_STABILIZATION_STACK_SIZE 524
|
||||
#define PIOS_TELEM_STACK_SIZE 500
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 96
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 130
|
||||
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998
|
||||
//#define PIOS_QUATERNION_STABILIZATION
|
||||
|
||||
// This can't be too high to stop eventdispatcher thread overflowing
|
||||
#define PIOS_EVENTDISAPTCHER_QUEUE 10
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
|
@ -26,7 +26,7 @@
|
||||
#ifndef _FIFO_BUFFER_H_
|
||||
#define _FIFO_BUFFER_H_
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#include <stdint.h>
|
||||
|
||||
// *********************
|
||||
|
||||
|
@ -76,7 +76,7 @@ static void AttitudeTask(void *parameters);
|
||||
static float gyro_correct_int[3] = {0,0,0};
|
||||
static xQueueHandle gyro_queue;
|
||||
|
||||
static void updateSensors(AttitudeRawData *);
|
||||
static int8_t updateSensors(AttitudeRawData *);
|
||||
static void updateAttitude(AttitudeRawData *);
|
||||
static void settingsUpdatedCb(UAVObjEvent * objEv);
|
||||
|
||||
@ -162,14 +162,19 @@ static void AttitudeTask(void *parameters)
|
||||
// Keep flash CS pin high while talking accel
|
||||
PIOS_FLASH_DISABLE;
|
||||
PIOS_ADXL345_Init();
|
||||
|
||||
|
||||
|
||||
// Set critical error and wait until the accel is producing data
|
||||
while(PIOS_ADXL345_FifoElements() == 0) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE);
|
||||
}
|
||||
|
||||
// Force settings update to make sure rotation loaded
|
||||
settingsUpdatedCb(AttitudeSettingsHandle());
|
||||
|
||||
// Main task loop
|
||||
while (1) {
|
||||
|
||||
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
|
||||
@ -197,14 +202,24 @@ static void AttitudeTask(void *parameters)
|
||||
|
||||
AttitudeRawData attitudeRaw;
|
||||
AttitudeRawGet(&attitudeRaw);
|
||||
updateSensors(&attitudeRaw);
|
||||
updateAttitude(&attitudeRaw);
|
||||
AttitudeRawSet(&attitudeRaw);
|
||||
if(updateSensors(&attitudeRaw) != 0)
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
|
||||
else {
|
||||
// Only update attitude when sensor data is good
|
||||
updateAttitude(&attitudeRaw);
|
||||
AttitudeRawSet(&attitudeRaw);
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
/**
|
||||
* Get an update from the sensors
|
||||
* @param[in] attitudeRaw Populate the UAVO instead of saving right here
|
||||
* @return 0 if successfull, -1 if not
|
||||
*/
|
||||
static int8_t updateSensors(AttitudeRawData * attitudeRaw)
|
||||
{
|
||||
struct pios_adxl345_data accel_data;
|
||||
float gyro[4];
|
||||
@ -212,9 +227,12 @@ static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
// Only wait the time for two nominal updates before setting an alarm
|
||||
if(xQueueReceive(gyro_queue, (void * const) gyro, UPDATE_RATE * 2) == errQUEUE_EMPTY) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
|
||||
return;
|
||||
return -1;
|
||||
}
|
||||
|
||||
// No accel data available
|
||||
if(PIOS_ADXL345_FifoElements() == 0)
|
||||
return -1;
|
||||
|
||||
// First sample is temperature
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_X] = -(gyro[1] - GYRO_NEUTRAL) * gyroGain;
|
||||
@ -270,6 +288,8 @@ static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
// Because most crafts wont get enough information from gravity to zero yaw gyro, we try
|
||||
// and make it average zero (weakly)
|
||||
gyro_correct_int[2] += - attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] * yawBiasRate;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void updateAttitude(AttitudeRawData * attitudeRaw)
|
||||
@ -307,6 +327,7 @@ static void updateAttitude(AttitudeRawData * attitudeRaw)
|
||||
// Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s
|
||||
gyro_correct_int[0] += accel_err[0] * accelKi;
|
||||
gyro_correct_int[1] += accel_err[1] * accelKi;
|
||||
|
||||
//gyro_correct_int[2] += accel_err[2] * settings.AccelKI * dT;
|
||||
|
||||
// Correct rates based on error, integral component dealt with in updateSensors
|
||||
@ -329,6 +350,13 @@ static void updateAttitude(AttitudeRawData * attitudeRaw)
|
||||
q[1] = q[1] + qdot[1];
|
||||
q[2] = q[2] + qdot[2];
|
||||
q[3] = q[3] + qdot[3];
|
||||
|
||||
if(q[0] < 0) {
|
||||
q[0] = -q[0];
|
||||
q[1] = -q[1];
|
||||
q[2] = -q[2];
|
||||
q[3] = -q[3];
|
||||
}
|
||||
}
|
||||
|
||||
// Renomalize
|
||||
|
@ -84,6 +84,7 @@ uint8_t max_axis_lock = 0;
|
||||
uint8_t max_axislock_rate = 0;
|
||||
float weak_leveling_kp = 0;
|
||||
uint8_t weak_leveling_max = 0;
|
||||
bool lowThrottleZeroIntegral;
|
||||
|
||||
pid_type pids[PID_MAX];
|
||||
|
||||
@ -329,6 +330,7 @@ static void stabilizationTask(void* parameters)
|
||||
}
|
||||
|
||||
if(flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED ||
|
||||
(lowThrottleZeroIntegral && stabDesired.Throttle < 0) ||
|
||||
!shouldUpdate)
|
||||
{
|
||||
ZeroPids();
|
||||
@ -427,6 +429,9 @@ static void SettingsUpdatedCb(UAVObjEvent * ev)
|
||||
weak_leveling_kp = settings.WeakLevelingKp;
|
||||
weak_leveling_max = settings.MaxWeakLevelingRate;
|
||||
|
||||
// Whether to zero the PID integrals while throttle is low
|
||||
lowThrottleZeroIntegral = settings.LowThrottleZeroIntegral == STABILIZATIONSETTINGS_LOWTHROTTLEZEROINTEGRAL_TRUE;
|
||||
|
||||
// The dT has some jitter iteration to iteration that we don't want to
|
||||
// make thie result unpredictable. Still, it's nicer to specify the constant
|
||||
// based on a time (in ms) rather than a fixed multiplier. The error between
|
||||
|
@ -165,6 +165,7 @@ endif
|
||||
SRC += $(PIOSPOSIX)/pios_crc.c
|
||||
SRC += $(PIOSPOSIX)/pios_sys.c
|
||||
SRC += $(PIOSPOSIX)/pios_led.c
|
||||
SRC += $(PIOSPOSIX)/pios_irq.c
|
||||
SRC += $(PIOSPOSIX)/pios_delay.c
|
||||
SRC += $(PIOSPOSIX)/pios_sdcard.c
|
||||
SRC += $(PIOSPOSIX)/pios_udp.c
|
||||
@ -176,7 +177,7 @@ SRC += $(PIOSPOSIX)/pios_debug.c
|
||||
SRC += $(PIOSPOSIX)/pios_rcvr.c
|
||||
|
||||
## Libraries for flight calculations
|
||||
#SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/CoordinateConversions.c
|
||||
## RTOS and RTOS Portable
|
||||
|
@ -52,15 +52,22 @@
|
||||
//-------------------------
|
||||
//#define PIOS_USART_TX_BUFFER_SIZE 256
|
||||
#define PIOS_COM_BUFFER_SIZE 1024
|
||||
#define PIOS_COM_MAX_DEVS 256
|
||||
#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE
|
||||
|
||||
#define PIOS_COM_TELEM_RF 0
|
||||
#define PIOS_COM_GPS 1
|
||||
#define PIOS_COM_TELEM_USB 2
|
||||
extern uint32_t pios_com_telem_rf_id;
|
||||
extern uint32_t pios_com_telem_usb_id;
|
||||
extern uint32_t pios_com_gps_id;
|
||||
extern uint32_t pios_com_aux_id;
|
||||
extern uint32_t pios_com_spectrum_id;
|
||||
|
||||
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
|
||||
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
|
||||
#define PIOS_COM_GPS (pios_com_gps_id)
|
||||
|
||||
#ifdef PIOS_ENABLE_AUX_UART
|
||||
#define PIOS_COM_AUX 3
|
||||
#define PIOS_COM_DEBUG PIOS_COM_AUX
|
||||
#define PIOS_COM_AUX (pios_com_aux_id)
|
||||
#define PIOS_COM_DEBUG (PIOS_COM_AUX
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -36,6 +36,8 @@
|
||||
#define PIOS_INCLUDE_SDCARD
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_TELEMETRY_RF
|
||||
#define PIOS_INCLUDE_UDP
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
|
@ -40,42 +40,16 @@ void Stack_Change() {
|
||||
void Stack_Change_Weak() {
|
||||
}
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core systems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
void PIOS_Board_Init(void) {
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
UAVObjectsInitializeAll();
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
/* Initialize the task monitor library */
|
||||
TaskMonitorInitialize();
|
||||
|
||||
/* Initialize the PiOS library */
|
||||
PIOS_COM_Init();
|
||||
|
||||
}
|
||||
|
||||
|
||||
const struct pios_udp_cfg pios_udp0_cfg = {
|
||||
const struct pios_udp_cfg pios_udp_telem_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9000,
|
||||
};
|
||||
const struct pios_udp_cfg pios_udp1_cfg = {
|
||||
const struct pios_udp_cfg pios_udp_gps_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9001,
|
||||
};
|
||||
const struct pios_udp_cfg pios_udp2_cfg = {
|
||||
const struct pios_udp_cfg pios_udp_debug_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9002,
|
||||
};
|
||||
@ -84,15 +58,19 @@ const struct pios_udp_cfg pios_udp2_cfg = {
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
const struct pios_udp_cfg pios_udp3_cfg = {
|
||||
const struct pios_udp_cfg pios_udp_aux_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9003,
|
||||
};
|
||||
#endif
|
||||
|
||||
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
/*
|
||||
struct pios_udp_dev pios_udp_devs[] = {
|
||||
#define PIOS_UDP_TELEM 0
|
||||
{
|
||||
@ -115,7 +93,7 @@ struct pios_udp_dev pios_udp_devs[] = {
|
||||
};
|
||||
|
||||
uint8_t pios_udp_num_devices = NELEMENTS(pios_udp_devs);
|
||||
|
||||
*/
|
||||
/*
|
||||
* COM devices
|
||||
*/
|
||||
@ -126,28 +104,72 @@ uint8_t pios_udp_num_devices = NELEMENTS(pios_udp_devs);
|
||||
extern const struct pios_com_driver pios_serial_com_driver;
|
||||
extern const struct pios_com_driver pios_udp_com_driver;
|
||||
|
||||
struct pios_com_dev pios_com_devs[] = {
|
||||
{
|
||||
.id = PIOS_UDP_TELEM,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_UDP_GPS,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_UDP_LOCAL,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
#ifdef PIOS_COM_AUX
|
||||
{
|
||||
.id = PIOS_UDP_AUX,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
uint32_t pios_com_telem_rf_id;
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
uint32_t pios_com_gps_id;
|
||||
uint32_t pios_com_aux_id;
|
||||
uint32_t pios_com_spectrum_id;
|
||||
|
||||
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core systems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
void PIOS_Board_Init(void) {
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
UAVObjectsInitializeAll();
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
/* Initialize the task monitor library */
|
||||
TaskMonitorInitialize();
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_TELEMETRY_RF)
|
||||
{
|
||||
uint32_t pios_udp_telem_rf_id;
|
||||
if (PIOS_UDP_Init(&pios_udp_telem_rf_id, &pios_udp_telem_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_udp_com_driver, pios_udp_telem_rf_id,
|
||||
rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
{
|
||||
uint32_t pios_udp_gps_id;
|
||||
if (PIOS_USART_Init(&pios_udp_gps_id, &pios_udp_gps_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_udp_com_driver, pios_udp_gps_id,
|
||||
rx_buffer, PIOS_COM_GPS_RX_BUF_LEN,
|
||||
NULL, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
#endif
|
||||
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -1,55 +1,65 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_com.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org)
|
||||
* @brief COM layer functions header
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 PIOS_COM_H
|
||||
#define PIOS_COM_H
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_COM_Init(void);
|
||||
extern int32_t PIOS_COM_ChangeBaud(uint8_t port, uint32_t baud);
|
||||
extern int32_t PIOS_COM_SendCharNonBlocking(uint8_t port, char c);
|
||||
extern int32_t PIOS_COM_SendChar(uint8_t port, char c);
|
||||
extern int32_t PIOS_COM_SendBufferNonBlocking(uint8_t port, uint8_t *buffer, uint16_t len);
|
||||
extern int32_t PIOS_COM_SendBuffer(uint8_t port, uint8_t *buffer, uint16_t len);
|
||||
extern int32_t PIOS_COM_SendStringNonBlocking(uint8_t port, char *str);
|
||||
extern int32_t PIOS_COM_SendString(uint8_t port, char *str);
|
||||
extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint8_t port, char *format, ...);
|
||||
extern int32_t PIOS_COM_SendFormattedString(uint8_t port, char *format, ...);
|
||||
extern uint8_t PIOS_COM_ReceiveBuffer(uint8_t port);
|
||||
extern int32_t PIOS_COM_ReceiveBufferUsed(uint8_t port);
|
||||
|
||||
extern int32_t PIOS_COM_ReceiveHandler(void);
|
||||
|
||||
struct pios_com_driver {
|
||||
void (*init)(uint8_t id);
|
||||
void (*set_baud)(uint8_t id, uint32_t baud);
|
||||
int32_t (*tx_nb)(uint8_t id, uint8_t *buffer, uint16_t len);
|
||||
int32_t (*tx)(uint8_t id, uint8_t *buffer, uint16_t len);
|
||||
int32_t (*rx)(uint8_t id);
|
||||
int32_t (*rx_avail)(uint8_t id);
|
||||
};
|
||||
|
||||
#endif /* PIOS_COM_H */
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_COM COM layer functions
|
||||
* @brief Hardware communication layer
|
||||
* @{
|
||||
*
|
||||
* @file pios_com.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org)
|
||||
* @brief COM layer functions header
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 PIOS_COM_H
|
||||
#define PIOS_COM_H
|
||||
|
||||
typedef uint16_t (*pios_com_callback)(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * task_woken);
|
||||
|
||||
struct pios_com_driver {
|
||||
void (*init)(uint32_t id);
|
||||
void (*set_baud)(uint32_t id, uint32_t baud);
|
||||
void (*tx_start)(uint32_t id, uint16_t tx_bytes_avail);
|
||||
void (*rx_start)(uint32_t id, uint16_t rx_bytes_avail);
|
||||
void (*bind_rx_cb)(uint32_t id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
void (*bind_tx_cb)(uint32_t id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t * rx_buffer, uint16_t rx_buffer_len, uint8_t * tx_buffer, uint16_t tx_buffer_len);
|
||||
extern int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud);
|
||||
extern int32_t PIOS_COM_SendCharNonBlocking(uint32_t com_id, char c);
|
||||
extern int32_t PIOS_COM_SendChar(uint32_t com_id, char c);
|
||||
extern int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, uint16_t len);
|
||||
extern int32_t PIOS_COM_SendBuffer(uint32_t com_id, const uint8_t *buffer, uint16_t len);
|
||||
extern int32_t PIOS_COM_SendStringNonBlocking(uint32_t com_id, const char *str);
|
||||
extern int32_t PIOS_COM_SendString(uint32_t com_id, const char *str);
|
||||
extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint32_t com_id, const char *format, ...);
|
||||
extern int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...);
|
||||
extern uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len, uint32_t timeout_ms);
|
||||
extern int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id);
|
||||
|
||||
#endif /* PIOS_COM_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
@ -1,5 +1,10 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_COM COM layer functions
|
||||
* @brief Hardware communication layer
|
||||
* @{
|
||||
*
|
||||
* @file pios_com_priv.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
@ -29,13 +34,11 @@
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
struct pios_com_dev {
|
||||
uint8_t id;
|
||||
const struct pios_com_driver * const driver;
|
||||
};
|
||||
|
||||
extern struct pios_com_dev pios_com_devs[];
|
||||
extern const uint8_t pios_com_num_devices;
|
||||
extern int32_t PIOS_COM_ReceiveHandler(uint32_t com_id);
|
||||
|
||||
#endif /* PIOS_COM_PRIV_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
38
flight/PiOS.posix/inc/pios_irq.h
Normal file
38
flight/PiOS.posix/inc/pios_irq.h
Normal file
@ -0,0 +1,38 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_IRQ IRQ Setup Functions
|
||||
* @{
|
||||
*
|
||||
* @file pios_irq.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org)
|
||||
* @brief IRQ functions header.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 PIOS_IRQ_H
|
||||
#define PIOS_IRQ_H
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_IRQ_Disable(void);
|
||||
extern int32_t PIOS_IRQ_Enable(void);
|
||||
|
||||
#endif /* PIOS_IRQ_H */
|
@ -31,21 +31,5 @@
|
||||
/* Global Types */
|
||||
|
||||
/* Public Functions */
|
||||
//extern void PIOS_UDP_Init(void);
|
||||
void PIOS_UDP_Init(void);
|
||||
extern void PIOS_UDP_ChangeBaud(uint8_t usart, uint32_t baud);
|
||||
|
||||
extern int32_t PIOS_UDP_RxBufferFree(uint8_t usart);
|
||||
extern int32_t PIOS_UDP_RxBufferUsed(uint8_t usart);
|
||||
extern int32_t PIOS_UDP_RxBufferGet(uint8_t usart);
|
||||
extern int32_t PIOS_UDP_RxBufferPeek(uint8_t usart);
|
||||
extern int32_t PIOS_UDP_RxBufferPut(uint8_t usart, uint8_t b);
|
||||
|
||||
extern int32_t PIOS_UDP_TxBufferFree(uint8_t usart);
|
||||
extern int32_t PIOS_UDP_TxBufferGet(uint8_t usart);
|
||||
extern int32_t PIOS_UDP_TxBufferPutMoreNonBlocking(uint8_t usart, uint8_t *buffer, uint16_t len);
|
||||
extern int32_t PIOS_UDP_TxBufferPutMore(uint8_t usart, uint8_t *buffer, uint16_t len);
|
||||
extern int32_t PIOS_UDP_TxBufferPutNonBlocking(uint8_t usart, uint8_t b);
|
||||
extern int32_t PIOS_UDP_TxBufferPut(uint8_t usart, uint8_t b);
|
||||
|
||||
#endif /* PIOS_UDP_H */
|
||||
|
@ -29,6 +29,7 @@
|
||||
|
||||
#include <pios.h>
|
||||
#include <stdio.h>
|
||||
#include <pthread.h>
|
||||
#include <sys/socket.h>
|
||||
#include <arpa/inet.h>
|
||||
#include <stdlib.h>
|
||||
@ -37,30 +38,34 @@
|
||||
#include <fcntl.h>
|
||||
#include <netinet/in.h>
|
||||
|
||||
|
||||
|
||||
struct pios_udp_cfg {
|
||||
const char * ip;
|
||||
uint16_t port;
|
||||
};
|
||||
|
||||
struct pios_udp_buffer {
|
||||
uint8_t buf[PIOS_UDP_RX_BUFFER_SIZE];
|
||||
uint16_t head;
|
||||
uint16_t tail;
|
||||
uint16_t size;
|
||||
};
|
||||
typedef struct {
|
||||
const struct pios_udp_cfg * cfg;
|
||||
pthread_t rxThread;
|
||||
|
||||
struct pios_udp_dev {
|
||||
const struct pios_udp_cfg * const cfg;
|
||||
struct pios_udp_buffer rx;
|
||||
int socket;
|
||||
struct sockaddr_in server;
|
||||
struct sockaddr_in client;
|
||||
uint32_t clientLength;
|
||||
};
|
||||
|
||||
extern struct pios_udp_dev pios_udp_devs[];
|
||||
extern uint8_t pios_udp_num_devices;
|
||||
pthread_cond_t cond;
|
||||
pthread_mutex_t mutex;
|
||||
|
||||
pios_com_callback tx_out_cb;
|
||||
uint32_t tx_out_context;
|
||||
pios_com_callback rx_in_cb;
|
||||
uint32_t rx_in_context;
|
||||
|
||||
uint8_t rx_buffer[PIOS_UDP_RX_BUFFER_SIZE];
|
||||
uint8_t tx_buffer[PIOS_UDP_RX_BUFFER_SIZE];
|
||||
} pios_udp_dev;
|
||||
|
||||
extern int32_t PIOS_UDP_Init(uint32_t * udp_id, const struct pios_udp_cfg * cfg);
|
||||
|
||||
|
||||
|
||||
#endif /* PIOS_UDP_PRIV_H */
|
||||
|
@ -58,6 +58,7 @@
|
||||
#include <pios_sys.h>
|
||||
#include <pios_delay.h>
|
||||
#include <pios_led.h>
|
||||
#include <pios_irq.h>
|
||||
#include <pios_sdcard.h>
|
||||
#include <pios_udp.h>
|
||||
#include <pios_com.h>
|
||||
|
@ -1,285 +1,522 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_com.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org)
|
||||
* @brief COM layer functions
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup PIOS_COM COM layer functions
|
||||
* @{
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
*/
|
||||
|
||||
|
||||
/* Project Includes */
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_COM COM layer functions
|
||||
* @brief Hardware communication layer
|
||||
* @{
|
||||
*
|
||||
* @file pios_com.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org)
|
||||
* @brief COM layer functions
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
#include "fifo_buffer.h"
|
||||
#include <pios_com_priv.h>
|
||||
|
||||
static struct pios_com_dev * find_com_dev_by_id (uint8_t port)
|
||||
{
|
||||
if (port >= pios_com_num_devices) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
return NULL;
|
||||
}
|
||||
#if !defined(PIOS_INCLUDE_FREERTOS)
|
||||
#include "pios_delay.h" /* PIOS_DELAY_WaitmS */
|
||||
#endif
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
return &(pios_com_devs[port]);
|
||||
enum pios_com_dev_magic {
|
||||
PIOS_COM_DEV_MAGIC = 0xaa55aa55,
|
||||
};
|
||||
|
||||
struct pios_com_dev {
|
||||
enum pios_com_dev_magic magic;
|
||||
uint32_t lower_id;
|
||||
const struct pios_com_driver * driver;
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
xSemaphoreHandle tx_sem;
|
||||
xSemaphoreHandle rx_sem;
|
||||
#endif
|
||||
|
||||
bool has_rx;
|
||||
bool has_tx;
|
||||
|
||||
t_fifo_buffer rx;
|
||||
t_fifo_buffer tx;
|
||||
};
|
||||
|
||||
static bool PIOS_COM_validate(struct pios_com_dev * com_dev)
|
||||
{
|
||||
return (com_dev && (com_dev->magic == PIOS_COM_DEV_MAGIC));
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialises COM layer
|
||||
* \param[in] mode currently only mode 0 supported
|
||||
* \return < 0 if initialisation failed
|
||||
*/
|
||||
int32_t PIOS_COM_Init(void)
|
||||
{
|
||||
int32_t ret = 0;
|
||||
|
||||
/* If any COM assignment: */
|
||||
#if defined(PIOS_INCLUDE_SERIAL)
|
||||
PIOS_SERIAL_Init();
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_UDP)
|
||||
PIOS_UDP_Init();
|
||||
#endif
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the port speed without re-initializing
|
||||
* \param[in] port COM port
|
||||
* \param[in] baud Requested baud rate
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_ChangeBaud(uint8_t port, uint32_t baud)
|
||||
#if defined(PIOS_INCLUDE_FREERTOS) && 0
|
||||
// static struct pios_com_dev * PIOS_COM_alloc(void)
|
||||
//{
|
||||
// struct pios_com_dev * com_dev;
|
||||
//
|
||||
// com_dev = (struct pios_com_dev *)malloc(sizeof(*com_dev));
|
||||
// if (!com_dev) return (NULL);
|
||||
//
|
||||
// com_dev->magic = PIOS_COM_DEV_MAGIC;
|
||||
// return(com_dev);
|
||||
//}
|
||||
#else
|
||||
static struct pios_com_dev pios_com_devs[PIOS_COM_MAX_DEVS];
|
||||
static uint8_t pios_com_num_devs;
|
||||
static uint32_t PIOS_COM_create(void)
|
||||
{
|
||||
struct pios_com_dev * com_dev;
|
||||
struct pios_com_dev * com_dev;
|
||||
|
||||
com_dev = find_com_dev_by_id (port);
|
||||
if (pios_com_num_devs >= PIOS_COM_MAX_DEVS) {
|
||||
return (PIOS_COM_MAX_DEVS+1);
|
||||
}
|
||||
|
||||
if (!com_dev) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
return -1;
|
||||
}
|
||||
com_dev = &pios_com_devs[pios_com_num_devs++];
|
||||
com_dev->magic = PIOS_COM_DEV_MAGIC;
|
||||
|
||||
/* Invoke the driver function if it exists */
|
||||
if (com_dev->driver->set_baud) {
|
||||
com_dev->driver->set_baud(com_dev->id, baud);
|
||||
}
|
||||
|
||||
return 0;
|
||||
return (pios_com_num_devs);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a package over given port
|
||||
* \param[in] port COM port
|
||||
* \param[in] buffer character buffer
|
||||
* \param[in] len buffer length
|
||||
* \return -1 if port not available
|
||||
* \return -2 if non-blocking mode activated: buffer is full
|
||||
* caller should retry until buffer is free again
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendBufferNonBlocking(uint8_t port, uint8_t *buffer, uint16_t len)
|
||||
static struct pios_com_dev * PIOS_COM_find_dev(uint32_t com_dev_id)
|
||||
{
|
||||
struct pios_com_dev * com_dev;
|
||||
if (!com_dev_id) return NULL;
|
||||
if (com_dev_id>pios_com_num_devs+1) return NULL;
|
||||
return &pios_com_devs[com_dev_id-1];
|
||||
}
|
||||
#endif
|
||||
|
||||
com_dev = find_com_dev_by_id (port);
|
||||
static uint16_t PIOS_COM_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield);
|
||||
static uint16_t PIOS_COM_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield);
|
||||
static void PIOS_COM_UnblockRx(struct pios_com_dev * com_dev, bool * need_yield);
|
||||
static void PIOS_COM_UnblockTx(struct pios_com_dev * com_dev, bool * need_yield);
|
||||
|
||||
if (!com_dev) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
return -1;
|
||||
}
|
||||
/**
|
||||
* Initialises COM layer
|
||||
* \param[out] handle
|
||||
* \param[in] driver
|
||||
* \param[in] id
|
||||
* \return < 0 if initialisation failed
|
||||
*/
|
||||
int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t * rx_buffer, uint16_t rx_buffer_len, uint8_t * tx_buffer, uint16_t tx_buffer_len)
|
||||
{
|
||||
PIOS_Assert(com_id);
|
||||
PIOS_Assert(driver);
|
||||
|
||||
/* Invoke the driver function if it exists */
|
||||
if (com_dev->driver->tx_nb) {
|
||||
return com_dev->driver->tx_nb(com_dev->id, buffer, len);
|
||||
}
|
||||
bool has_rx = (rx_buffer && rx_buffer_len > 0);
|
||||
bool has_tx = (tx_buffer && tx_buffer_len > 0);
|
||||
PIOS_Assert(has_rx || has_tx);
|
||||
PIOS_Assert(driver->bind_tx_cb || !has_tx);
|
||||
PIOS_Assert(driver->bind_rx_cb || !has_rx);
|
||||
|
||||
return 0;
|
||||
uint32_t com_dev_id;
|
||||
struct pios_com_dev * com_dev;
|
||||
|
||||
com_dev_id = PIOS_COM_create();
|
||||
com_dev = PIOS_COM_find_dev(com_dev_id);
|
||||
if (!com_dev) goto out_fail;
|
||||
|
||||
com_dev->driver = driver;
|
||||
com_dev->lower_id = lower_id;
|
||||
|
||||
com_dev->has_rx = has_rx;
|
||||
com_dev->has_tx = has_tx;
|
||||
|
||||
if (has_rx) {
|
||||
fifoBuf_init(&com_dev->rx, rx_buffer, rx_buffer_len);
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
vSemaphoreCreateBinary(com_dev->rx_sem);
|
||||
#endif /* PIOS_INCLUDE_FREERTOS */
|
||||
(com_dev->driver->bind_rx_cb)(lower_id, PIOS_COM_RxInCallback, com_dev_id);
|
||||
if (com_dev->driver->rx_start) {
|
||||
/* Start the receiver */
|
||||
(com_dev->driver->rx_start)(com_dev->lower_id,
|
||||
fifoBuf_getFree(&com_dev->rx));
|
||||
}
|
||||
}
|
||||
|
||||
if (has_tx) {
|
||||
fifoBuf_init(&com_dev->tx, tx_buffer, tx_buffer_len);
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
vSemaphoreCreateBinary(com_dev->tx_sem);
|
||||
#endif /* PIOS_INCLUDE_FREERTOS */
|
||||
(com_dev->driver->bind_tx_cb)(lower_id, PIOS_COM_TxOutCallback, com_dev_id);
|
||||
}
|
||||
|
||||
*com_id = com_dev_id;
|
||||
return(0);
|
||||
|
||||
out_fail:
|
||||
return(-1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a package over given port
|
||||
* (blocking function)
|
||||
* \param[in] port COM port
|
||||
* \param[in] buffer character buffer
|
||||
* \param[in] len buffer length
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendBuffer(uint8_t port, uint8_t *buffer, uint16_t len)
|
||||
static void PIOS_COM_UnblockRx(struct pios_com_dev * com_dev, bool * need_yield)
|
||||
{
|
||||
struct pios_com_dev * com_dev;
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static signed portBASE_TYPE xHigherPriorityTaskWoken;
|
||||
xSemaphoreGiveFromISR(com_dev->rx_sem, &xHigherPriorityTaskWoken);
|
||||
|
||||
com_dev = find_com_dev_by_id (port);
|
||||
|
||||
if (!com_dev) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Invoke the driver function if it exists */
|
||||
if (com_dev->driver->tx) {
|
||||
return com_dev->driver->tx(com_dev->id, buffer, len);
|
||||
}
|
||||
|
||||
return 0;
|
||||
if (xHigherPriorityTaskWoken != pdFALSE) {
|
||||
*need_yield = true;
|
||||
} else {
|
||||
*need_yield = false;
|
||||
}
|
||||
#else
|
||||
*need_yield = false;
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a single character over given port
|
||||
* \param[in] port COM port
|
||||
* \param[in] c character
|
||||
* \return -1 if port not available
|
||||
* \return -2 buffer is full
|
||||
* caller should retry until buffer is free again
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendCharNonBlocking(uint8_t port, char c)
|
||||
{
|
||||
return PIOS_COM_SendBufferNonBlocking(port, (uint8_t *)&c, 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a single character over given port
|
||||
* (blocking function)
|
||||
* \param[in] port COM port
|
||||
* \param[in] c character
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendChar(uint8_t port, char c)
|
||||
{
|
||||
return PIOS_COM_SendBuffer(port, (uint8_t *)&c, 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a string over given port
|
||||
* \param[in] port COM port
|
||||
* \param[in] str zero-terminated string
|
||||
* \return -1 if port not available
|
||||
* \return -2 buffer is full
|
||||
* caller should retry until buffer is free again
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendStringNonBlocking(uint8_t port, char *str)
|
||||
{
|
||||
return PIOS_COM_SendBufferNonBlocking(port, (uint8_t *)str, (uint16_t)strlen(str));
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a string over given port
|
||||
* (blocking function)
|
||||
* \param[in] port COM port
|
||||
* \param[in] str zero-terminated string
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendString(uint8_t port, char *str)
|
||||
{
|
||||
return PIOS_COM_SendBuffer(port, (uint8_t *)str, strlen(str));
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a formatted string (-> printf) over given port
|
||||
* \param[in] port COM port
|
||||
* \param[in] *format zero-terminated format string - 128 characters supported maximum!
|
||||
* \param[in] ... optional arguments,
|
||||
* 128 characters supported maximum!
|
||||
* \return -2 if non-blocking mode activated: buffer is full
|
||||
* caller should retry until buffer is free again
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendFormattedStringNonBlocking(uint8_t port, char *format, ...)
|
||||
{
|
||||
uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later!
|
||||
|
||||
va_list args;
|
||||
|
||||
va_start(args, format);
|
||||
vsprintf((char *)buffer, format, args);
|
||||
return PIOS_COM_SendBufferNonBlocking(port, buffer, (uint16_t)strlen((char *)buffer));
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a formatted string (-> printf) over given port
|
||||
* (blocking function)
|
||||
* \param[in] port COM port
|
||||
* \param[in] *format zero-terminated format string - 128 characters supported maximum!
|
||||
* \param[in] ... optional arguments,
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendFormattedString(uint8_t port, char *format, ...)
|
||||
{
|
||||
uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later!
|
||||
va_list args;
|
||||
|
||||
va_start(args, format);
|
||||
vsprintf((char *)buffer, format, args);
|
||||
return PIOS_COM_SendBuffer(port, buffer, (uint16_t)strlen((char *)buffer));
|
||||
}
|
||||
|
||||
/**
|
||||
* Transfer bytes from port buffers into another buffer
|
||||
* \param[in] port COM port
|
||||
static void PIOS_COM_UnblockTx(struct pios_com_dev * com_dev, bool * need_yield)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static signed portBASE_TYPE xHigherPriorityTaskWoken;
|
||||
xSemaphoreGiveFromISR(com_dev->tx_sem, &xHigherPriorityTaskWoken);
|
||||
|
||||
if (xHigherPriorityTaskWoken != pdFALSE) {
|
||||
*need_yield = true;
|
||||
} else {
|
||||
*need_yield = false;
|
||||
}
|
||||
#else
|
||||
*need_yield = false;
|
||||
#endif
|
||||
}
|
||||
|
||||
static uint16_t PIOS_COM_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
|
||||
{
|
||||
struct pios_com_dev * com_dev = PIOS_COM_find_dev(context);
|
||||
|
||||
bool valid = PIOS_COM_validate(com_dev);
|
||||
PIOS_Assert(valid);
|
||||
PIOS_Assert(com_dev->has_rx);
|
||||
|
||||
PIOS_IRQ_Disable();
|
||||
uint16_t bytes_into_fifo = fifoBuf_putData(&com_dev->rx, buf, buf_len);
|
||||
PIOS_IRQ_Enable();
|
||||
|
||||
if (bytes_into_fifo > 0) {
|
||||
/* Data has been added to the buffer */
|
||||
PIOS_COM_UnblockRx(com_dev, need_yield);
|
||||
}
|
||||
|
||||
if (headroom) {
|
||||
*headroom = fifoBuf_getFree(&com_dev->rx);
|
||||
}
|
||||
|
||||
return (bytes_into_fifo);
|
||||
}
|
||||
|
||||
static uint16_t PIOS_COM_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
|
||||
{
|
||||
struct pios_com_dev * com_dev = PIOS_COM_find_dev(context);
|
||||
|
||||
bool valid = PIOS_COM_validate(com_dev);
|
||||
PIOS_Assert(valid);
|
||||
PIOS_Assert(buf);
|
||||
PIOS_Assert(buf_len);
|
||||
PIOS_Assert(com_dev->has_tx);
|
||||
|
||||
PIOS_IRQ_Disable();
|
||||
uint16_t bytes_from_fifo = fifoBuf_getData(&com_dev->tx, buf, buf_len);
|
||||
PIOS_IRQ_Enable();
|
||||
|
||||
if (bytes_from_fifo > 0) {
|
||||
/* More space has been made in the buffer */
|
||||
PIOS_COM_UnblockTx(com_dev, need_yield);
|
||||
}
|
||||
|
||||
if (headroom) {
|
||||
*headroom = fifoBuf_getUsed(&com_dev->tx);
|
||||
}
|
||||
|
||||
return (bytes_from_fifo);
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the port speed without re-initializing
|
||||
* \param[in] port COM port
|
||||
* \param[in] baud Requested baud rate
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud)
|
||||
{
|
||||
struct pios_com_dev * com_dev = PIOS_COM_find_dev(com_id);
|
||||
|
||||
if (!PIOS_COM_validate(com_dev)) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Invoke the driver function if it exists */
|
||||
if (com_dev->driver->set_baud) {
|
||||
com_dev->driver->set_baud(com_dev->lower_id, baud);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a package over given port
|
||||
* \param[in] port COM port
|
||||
* \param[in] buffer character buffer
|
||||
* \param[in] len buffer length
|
||||
* \return -1 if port not available
|
||||
* \return -2 if non-blocking mode activated: buffer is full
|
||||
* caller should retry until buffer is free again
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, uint16_t len)
|
||||
{
|
||||
struct pios_com_dev * com_dev = PIOS_COM_find_dev(com_id);
|
||||
|
||||
if (!PIOS_COM_validate(com_dev)) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
return -1;
|
||||
}
|
||||
|
||||
PIOS_Assert(com_dev->has_tx);
|
||||
|
||||
if (len >= fifoBuf_getFree(&com_dev->tx)) {
|
||||
/* Buffer cannot accept all requested bytes (retry) */
|
||||
return -2;
|
||||
}
|
||||
|
||||
PIOS_IRQ_Disable();
|
||||
uint16_t bytes_into_fifo = fifoBuf_putData(&com_dev->tx, buffer, len);
|
||||
PIOS_IRQ_Enable();
|
||||
|
||||
if (bytes_into_fifo > 0) {
|
||||
/* More data has been put in the tx buffer, make sure the tx is started */
|
||||
if (com_dev->driver->tx_start) {
|
||||
com_dev->driver->tx_start(com_dev->lower_id,
|
||||
fifoBuf_getUsed(&com_dev->tx));
|
||||
}
|
||||
}
|
||||
|
||||
return (0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a package over given port
|
||||
* (blocking function)
|
||||
* \param[in] port COM port
|
||||
* \param[in] buffer character buffer
|
||||
* \param[in] len buffer length
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendBuffer(uint32_t com_id, const uint8_t *buffer, uint16_t len)
|
||||
{
|
||||
struct pios_com_dev * com_dev = PIOS_COM_find_dev(com_id);
|
||||
|
||||
if (!PIOS_COM_validate(com_dev)) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
return -1;
|
||||
}
|
||||
|
||||
PIOS_Assert(com_dev->has_tx);
|
||||
|
||||
int32_t rc;
|
||||
do {
|
||||
rc = PIOS_COM_SendBufferNonBlocking(com_id, buffer, len);
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
if (rc == -2) {
|
||||
/* Make sure the transmitter is running while we wait */
|
||||
if (com_dev->driver->tx_start) {
|
||||
(com_dev->driver->tx_start)(com_dev->lower_id,
|
||||
fifoBuf_getUsed(&com_dev->tx));
|
||||
}
|
||||
if (xSemaphoreTake(com_dev->tx_sem, portMAX_DELAY) != pdTRUE) {
|
||||
return -3;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
} while (rc == -2);
|
||||
|
||||
return rc;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a single character over given port
|
||||
* \param[in] port COM port
|
||||
* \param[in] c character
|
||||
* \return -1 if port not available
|
||||
* \return -2 buffer is full
|
||||
* caller should retry until buffer is free again
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendCharNonBlocking(uint32_t com_id, char c)
|
||||
{
|
||||
return PIOS_COM_SendBufferNonBlocking(com_id, (uint8_t *)&c, 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a single character over given port
|
||||
* (blocking function)
|
||||
* \param[in] port COM port
|
||||
* \param[in] c character
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendChar(uint32_t com_id, char c)
|
||||
{
|
||||
return PIOS_COM_SendBuffer(com_id, (uint8_t *)&c, 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a string over given port
|
||||
* \param[in] port COM port
|
||||
* \param[in] str zero-terminated string
|
||||
* \return -1 if port not available
|
||||
* \return -2 buffer is full
|
||||
* caller should retry until buffer is free again
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendStringNonBlocking(uint32_t com_id, const char *str)
|
||||
{
|
||||
return PIOS_COM_SendBufferNonBlocking(com_id, (uint8_t *)str, (uint16_t)strlen(str));
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a string over given port
|
||||
* (blocking function)
|
||||
* \param[in] port COM port
|
||||
* \param[in] str zero-terminated string
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendString(uint32_t com_id, const char *str)
|
||||
{
|
||||
return PIOS_COM_SendBuffer(com_id, (uint8_t *)str, strlen(str));
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a formatted string (-> printf) over given port
|
||||
* \param[in] port COM port
|
||||
* \param[in] *format zero-terminated format string - 128 characters supported maximum!
|
||||
* \param[in] ... optional arguments,
|
||||
* 128 characters supported maximum!
|
||||
* \return -2 if non-blocking mode activated: buffer is full
|
||||
* caller should retry until buffer is free again
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendFormattedStringNonBlocking(uint32_t com_id, const char *format, ...)
|
||||
{
|
||||
uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later!
|
||||
|
||||
va_list args;
|
||||
|
||||
va_start(args, format);
|
||||
vsprintf((char *)buffer, format, args);
|
||||
return PIOS_COM_SendBufferNonBlocking(com_id, buffer, (uint16_t)strlen((char *)buffer));
|
||||
}
|
||||
|
||||
/**
|
||||
* Sends a formatted string (-> printf) over given port
|
||||
* (blocking function)
|
||||
* \param[in] port COM port
|
||||
* \param[in] *format zero-terminated format string - 128 characters supported maximum!
|
||||
* \param[in] ... optional arguments,
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...)
|
||||
{
|
||||
uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later!
|
||||
va_list args;
|
||||
|
||||
va_start(args, format);
|
||||
vsprintf((char *)buffer, format, args);
|
||||
return PIOS_COM_SendBuffer(com_id, buffer, (uint16_t)strlen((char *)buffer));
|
||||
}
|
||||
|
||||
/**
|
||||
* Transfer bytes from port buffers into another buffer
|
||||
* \param[in] port COM port
|
||||
* \returns Byte from buffer
|
||||
*/
|
||||
uint8_t PIOS_COM_ReceiveBuffer(uint8_t port)
|
||||
{
|
||||
struct pios_com_dev * com_dev;
|
||||
|
||||
com_dev = find_com_dev_by_id (port);
|
||||
//PIOS_DEBUG_Assert(com_dev);
|
||||
//PIOS_DEBUG_Assert(com_dev->driver->rx);
|
||||
|
||||
return com_dev->driver->rx(com_dev->id);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the number of bytes waiting in the buffer
|
||||
* \param[in] port COM port
|
||||
* \return Number of bytes used in buffer
|
||||
*/
|
||||
int32_t PIOS_COM_ReceiveBufferUsed(uint8_t port)
|
||||
*/
|
||||
uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len, uint32_t timeout_ms)
|
||||
{
|
||||
struct pios_com_dev * com_dev;
|
||||
PIOS_Assert(buf);
|
||||
PIOS_Assert(buf_len);
|
||||
|
||||
com_dev = find_com_dev_by_id (port);
|
||||
struct pios_com_dev * com_dev = PIOS_COM_find_dev(com_id);
|
||||
|
||||
if (!com_dev) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
return 0;
|
||||
}
|
||||
if (!PIOS_COM_validate(com_dev)) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
PIOS_Assert(com_dev->has_rx);
|
||||
|
||||
if (!com_dev->driver->rx_avail) {
|
||||
return 0;
|
||||
}
|
||||
check_again:
|
||||
PIOS_IRQ_Disable();
|
||||
uint16_t bytes_from_fifo = fifoBuf_getData(&com_dev->rx, buf, buf_len);
|
||||
PIOS_IRQ_Enable();
|
||||
|
||||
return com_dev->driver->rx_avail(com_dev->id);
|
||||
if (bytes_from_fifo == 0 && timeout_ms > 0) {
|
||||
/* No more bytes in receive buffer */
|
||||
/* Make sure the receiver is running while we wait */
|
||||
if (com_dev->driver->rx_start) {
|
||||
/* Notify the lower layer that there is now room in the rx buffer */
|
||||
(com_dev->driver->rx_start)(com_dev->lower_id,
|
||||
fifoBuf_getFree(&com_dev->rx));
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
if (xSemaphoreTake(com_dev->rx_sem, timeout_ms / portTICK_RATE_MS) == pdTRUE) {
|
||||
/* Make sure we don't come back here again */
|
||||
timeout_ms = 0;
|
||||
goto check_again;
|
||||
}
|
||||
#else
|
||||
PIOS_DELAY_WaitmS(1);
|
||||
timeout_ms--;
|
||||
goto check_again;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Return received byte */
|
||||
return (bytes_from_fifo);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Get the number of bytes waiting in the buffer
|
||||
* \param[in] port COM port
|
||||
* \return Number of bytes used in buffer
|
||||
*/
|
||||
int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id)
|
||||
{
|
||||
struct pios_com_dev * com_dev = PIOS_COM_find_dev(com_id);
|
||||
|
||||
if (!PIOS_COM_validate(com_dev)) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
PIOS_Assert(com_dev->has_rx);
|
||||
return (fifoBuf_getUsed(&com_dev->rx));
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
69
flight/PiOS.posix/posix/pios_irq.c
Normal file
69
flight/PiOS.posix/posix/pios_irq.c
Normal file
@ -0,0 +1,69 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_IRQ IRQ Setup Functions
|
||||
* @brief STM32 Hardware code to enable and disable interrupts
|
||||
* @{
|
||||
*
|
||||
* @file pios_irq.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org)
|
||||
* @brief IRQ Enable/Disable routines
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_IRQ)
|
||||
|
||||
/* Private Function Prototypes */
|
||||
|
||||
/**
|
||||
* Disables all interrupts (nested)
|
||||
* \return < 0 On errors
|
||||
*/
|
||||
int32_t PIOS_IRQ_Disable(void)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
taskENTER_CRITICAL();
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Enables all interrupts (nested)
|
||||
* \return < 0 on errors
|
||||
* \return -1 on nesting errors (PIOS_IRQ_Disable() hasn't been called before)
|
||||
*/
|
||||
int32_t PIOS_IRQ_Enable(void)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
taskEXIT_CRITICAL();
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -32,18 +32,35 @@
|
||||
|
||||
#if defined(PIOS_INCLUDE_UDP)
|
||||
|
||||
#include <signal.h>
|
||||
#include <pios_udp_priv.h>
|
||||
|
||||
/* We need a list of UDP devices */
|
||||
|
||||
#define PIOS_UDP_MAX_DEV 256
|
||||
static int8_t pios_udp_num_devices = 0;
|
||||
|
||||
static pios_udp_dev pios_udp_devices[PIOS_UDP_MAX_DEV];
|
||||
|
||||
|
||||
|
||||
/* Provide a COM driver */
|
||||
static void PIOS_UDP_ChangeBaud(uint32_t udp_id, uint32_t baud);
|
||||
static void PIOS_UDP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
static void PIOS_UDP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail);
|
||||
static void PIOS_UDP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail);
|
||||
|
||||
const struct pios_com_driver pios_udp_com_driver = {
|
||||
.set_baud = PIOS_UDP_ChangeBaud,
|
||||
.tx_nb = PIOS_UDP_TxBufferPutMoreNonBlocking,
|
||||
.tx = PIOS_UDP_TxBufferPutMore,
|
||||
.rx = PIOS_UDP_RxBufferGet,
|
||||
.rx_avail = PIOS_UDP_RxBufferUsed,
|
||||
.set_baud = PIOS_UDP_ChangeBaud,
|
||||
.tx_start = PIOS_UDP_TxStart,
|
||||
.rx_start = PIOS_UDP_RxStart,
|
||||
.bind_tx_cb = PIOS_UDP_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_UDP_RegisterRxCallback,
|
||||
};
|
||||
|
||||
static struct pios_udp_dev * find_udp_dev_by_id (uint8_t udp)
|
||||
|
||||
static pios_udp_dev * find_udp_dev_by_id (uint8_t udp)
|
||||
{
|
||||
if (udp >= pios_udp_num_devices) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
@ -51,410 +68,174 @@ static struct pios_udp_dev * find_udp_dev_by_id (uint8_t udp)
|
||||
}
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
return &(pios_udp_devs[udp]);
|
||||
return &(pios_udp_devices[udp]);
|
||||
}
|
||||
|
||||
/**
|
||||
* Open some UDP sockets
|
||||
*/
|
||||
void PIOS_UDP_Init(void)
|
||||
{
|
||||
struct pios_udp_dev * udp_dev;
|
||||
uint8_t i;
|
||||
|
||||
for (i = 0; i < pios_udp_num_devices; i++) {
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(i);
|
||||
//PIOS_DEBUG_Assert(udp_dev);
|
||||
|
||||
/* Clear buffer counters */
|
||||
udp_dev->rx.head = udp_dev->rx.tail = udp_dev->rx.size = 0;
|
||||
|
||||
/* assign socket */
|
||||
udp_dev->socket = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP);
|
||||
memset(&udp_dev->server,0,sizeof(udp_dev->server));
|
||||
memset(&udp_dev->client,0,sizeof(udp_dev->client));
|
||||
udp_dev->server.sin_family = AF_INET;
|
||||
udp_dev->server.sin_addr.s_addr = inet_addr(udp_dev->cfg->ip);
|
||||
udp_dev->server.sin_port = htons(udp_dev->cfg->port);
|
||||
int res= bind(udp_dev->socket, (struct sockaddr *)&udp_dev->server,sizeof(udp_dev->server));
|
||||
/* use nonblocking IO */
|
||||
int flags = fcntl(udp_dev->socket, F_GETFL, 0);
|
||||
fcntl(udp_dev->socket, F_SETFL, flags | O_NONBLOCK);
|
||||
printf("udp dev %i - socket %i opened - result %i\n",i,udp_dev->socket,res);
|
||||
|
||||
/* TODO do some error handling - wait no, we can't - we are void anyway ;) */
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Changes the baud rate of the UDP peripheral without re-initialising.
|
||||
* \param[in] udp UDP name (GPS, TELEM, AUX)
|
||||
* \param[in] baud Requested baud rate
|
||||
*/
|
||||
void PIOS_UDP_ChangeBaud(uint8_t udp, uint32_t baud)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* puts a byte onto the receive buffer
|
||||
* \param[in] UDP UDP name
|
||||
* \param[in] b byte which should be put into Rx buffer
|
||||
* \return 0 if no error
|
||||
* \return -1 if UDP not available
|
||||
* \return -2 if buffer full (retry)
|
||||
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
int32_t PIOS_UDP_RxBufferPut(uint8_t udp, uint8_t b)
|
||||
{
|
||||
struct pios_udp_dev * udp_dev;
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(udp);
|
||||
|
||||
if (!udp_dev) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (udp_dev->rx.size >= sizeof(udp_dev->rx.buf)) {
|
||||
/* Buffer full (retry) */
|
||||
return -2;
|
||||
}
|
||||
|
||||
/* Copy received byte into receive buffer */
|
||||
udp_dev->rx.buf[udp_dev->rx.head++] = b;
|
||||
if (udp_dev->rx.head >= sizeof(udp_dev->rx.buf)) {
|
||||
udp_dev->rx.head = 0;
|
||||
}
|
||||
udp_dev->rx.size++;
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* attempt to receive
|
||||
* RxThread
|
||||
*/
|
||||
void PIOS_UDP_RECV(uint8_t udp) {
|
||||
|
||||
struct pios_udp_dev * udp_dev;
|
||||
unsigned char localbuffer[PIOS_UDP_RX_BUFFER_SIZE];
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(udp);
|
||||
|
||||
if (!udp_dev) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
return;
|
||||
}
|
||||
|
||||
/* use nonblocking IO */
|
||||
int flags = fcntl(udp_dev->socket, F_GETFL, 0);
|
||||
fcntl(udp_dev->socket, F_SETFL, flags | O_NONBLOCK);
|
||||
|
||||
/* receive data */
|
||||
int received;
|
||||
udp_dev->clientLength=sizeof(udp_dev->client);
|
||||
if ((received = recvfrom(udp_dev->socket,
|
||||
localbuffer,
|
||||
(PIOS_UDP_RX_BUFFER_SIZE - udp_dev->rx.size),
|
||||
0,
|
||||
(struct sockaddr *) &udp_dev->client,
|
||||
(socklen_t*)&udp_dev->clientLength)) < 0) {
|
||||
|
||||
return;
|
||||
}
|
||||
/* copy received data to buffer */
|
||||
int t;
|
||||
for (t=0;t<received;t++) {
|
||||
PIOS_UDP_RxBufferPut(udp,localbuffer[t]);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns number of free bytes in receive buffer
|
||||
* \param[in] UDP UDP name
|
||||
* \return UDP number of free bytes
|
||||
* \return 1: UDP available
|
||||
* \return 0: UDP not available
|
||||
*/
|
||||
int32_t PIOS_UDP_RxBufferFree(uint8_t udp)
|
||||
void * PIOS_UDP_RxThread(void * udp_dev_n)
|
||||
{
|
||||
struct pios_udp_dev * udp_dev;
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(udp);
|
||||
/* needed because of FreeRTOS.posix scheduling */
|
||||
sigset_t set;
|
||||
sigfillset(&set);
|
||||
sigprocmask(SIG_BLOCK, &set, NULL);
|
||||
|
||||
if (!udp_dev) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
return -2;
|
||||
}
|
||||
pios_udp_dev * udp_dev = (pios_udp_dev*) udp_dev_n;
|
||||
|
||||
/* fill buffer */
|
||||
PIOS_UDP_RECV(udp);
|
||||
/**
|
||||
* com devices never get closed except by application "reboot"
|
||||
* we also never give up our mutex except for waiting
|
||||
*/
|
||||
while(1) {
|
||||
|
||||
return (sizeof(udp_dev->rx.buf) - udp_dev->rx.size);
|
||||
}
|
||||
/**
|
||||
* receive
|
||||
*/
|
||||
int received;
|
||||
udp_dev->clientLength=sizeof(udp_dev->client);
|
||||
if ((received = recvfrom(udp_dev->socket,
|
||||
&udp_dev->rx_buffer,
|
||||
PIOS_UDP_RX_BUFFER_SIZE,
|
||||
0,
|
||||
(struct sockaddr *) &udp_dev->client,
|
||||
(socklen_t*)&udp_dev->clientLength)) >= 0)
|
||||
{
|
||||
|
||||
/**
|
||||
* Returns number of used bytes in receive buffer
|
||||
* \param[in] UDP UDP name
|
||||
* \return > 0: number of used bytes
|
||||
* \return 0 if UDP not available
|
||||
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
int32_t PIOS_UDP_RxBufferUsed(uint8_t udp)
|
||||
{
|
||||
struct pios_udp_dev * udp_dev;
|
||||
/* copy received data to buffer if possible */
|
||||
/* we do NOT buffer data locally. If the com buffer can't receive, data is discarded! */
|
||||
/* (thats what the USART driver does too!) */
|
||||
bool rx_need_yield = false;
|
||||
if (udp_dev->rx_in_cb) {
|
||||
(void) (udp_dev->rx_in_cb)(udp_dev->rx_in_context, udp_dev->rx_buffer, received, NULL, &rx_need_yield);
|
||||
}
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(udp);
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
if (rx_need_yield) {
|
||||
vPortYieldFromISR();
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_FREERTOS */
|
||||
|
||||
if (!udp_dev) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
return -2;
|
||||
}
|
||||
}
|
||||
|
||||
/* fill buffer */
|
||||
PIOS_UDP_RECV(udp);
|
||||
|
||||
return (udp_dev->rx.size);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets a byte from the receive buffer
|
||||
* \param[in] UDP UDP name
|
||||
* \return -1 if UDP not available
|
||||
* \return -2 if no new byte available
|
||||
* \return >= 0: number of received bytes
|
||||
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
int32_t PIOS_UDP_RxBufferGet(uint8_t udp)
|
||||
{
|
||||
struct pios_udp_dev * udp_dev;
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(udp);
|
||||
|
||||
if (!udp_dev) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
return -2;
|
||||
}
|
||||
|
||||
/* fill buffer */
|
||||
PIOS_UDP_RECV(udp);
|
||||
|
||||
if (!udp_dev->rx.size) {
|
||||
/* Nothing new in the buffer */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* get byte */
|
||||
uint8_t b = udp_dev->rx.buf[udp_dev->rx.tail++];
|
||||
if (udp_dev->rx.tail >= sizeof(udp_dev->rx.buf)) {
|
||||
udp_dev->rx.tail = 0;
|
||||
}
|
||||
udp_dev->rx.size--;
|
||||
|
||||
/* Return received byte */
|
||||
return b;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the next byte of the receive buffer without taking it
|
||||
* \param[in] UDP UDP name
|
||||
* \return -1 if UDP not available
|
||||
* \return -2 if no new byte available
|
||||
* \return >= 0: number of received bytes
|
||||
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
int32_t PIOS_UDP_RxBufferPeek(uint8_t udp)
|
||||
{
|
||||
struct pios_udp_dev * udp_dev;
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(udp);
|
||||
|
||||
if (!udp_dev) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
return -2;
|
||||
}
|
||||
|
||||
/* fill buffer */
|
||||
PIOS_UDP_RECV(udp);
|
||||
|
||||
if (!udp_dev->rx.size) {
|
||||
/* Nothing new in the buffer */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* get byte */
|
||||
uint8_t b = udp_dev->rx.buf[udp_dev->rx.tail];
|
||||
|
||||
/* Return received byte */
|
||||
return b;
|
||||
}
|
||||
|
||||
/**
|
||||
* returns number of free bytes in transmit buffer
|
||||
* \param[in] UDP UDP name
|
||||
* \return number of free bytes
|
||||
* \return 0 if UDP not available
|
||||
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
int32_t PIOS_UDP_TxBufferFree(uint8_t udp)
|
||||
{
|
||||
struct pios_udp_dev * udp_dev;
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(udp);
|
||||
|
||||
if (!udp_dev) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
return 0;
|
||||
}
|
||||
|
||||
return PIOS_UDP_RX_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
/**
|
||||
* returns number of used bytes in transmit buffer
|
||||
* \param[in] UDP UDP name
|
||||
* \return number of used bytes
|
||||
* \return 0 if UDP not available
|
||||
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
int32_t PIOS_UDP_TxBufferUsed(uint8_t udp)
|
||||
{
|
||||
struct pios_udp_dev * udp_dev;
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(udp);
|
||||
|
||||
if (!udp_dev) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
return 0;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* puts more than one byte onto the transmit buffer (used for atomic sends)
|
||||
* \param[in] UDP UDP name
|
||||
* \param[in] *buffer pointer to buffer to be sent
|
||||
* \param[in] len number of bytes to be sent
|
||||
* \return 0 if no error
|
||||
* \return -1 if UDP not available
|
||||
* \return -2 if buffer full or cannot get all requested bytes (retry)
|
||||
* \return -3 if UDP not supported by UDPTxBufferPut Routine
|
||||
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
|
||||
* Open UDP socket
|
||||
*/
|
||||
int32_t PIOS_UDP_TxBufferPutMoreNonBlocking(uint8_t udp, uint8_t *buffer, uint16_t len)
|
||||
int32_t PIOS_UDP_Init(uint32_t * udp_id, const struct pios_udp_cfg * cfg)
|
||||
{
|
||||
struct pios_udp_dev * udp_dev;
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(udp);
|
||||
pios_udp_dev * udp_dev = &pios_udp_devices[pios_udp_num_devices];
|
||||
|
||||
if (!udp_dev) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (len >= PIOS_UDP_RX_BUFFER_SIZE) {
|
||||
/* Buffer cannot accept all requested bytes (retry) */
|
||||
return -2;
|
||||
}
|
||||
/* send data to client - non blocking*/
|
||||
|
||||
/* use nonblocking IO */
|
||||
int flags = fcntl(udp_dev->socket, F_GETFL, 0);
|
||||
fcntl(udp_dev->socket, F_SETFL, flags | O_NONBLOCK);
|
||||
sendto(udp_dev->socket, buffer, len, 0,
|
||||
(struct sockaddr *) &udp_dev->client,
|
||||
(socklen_t)sizeof(udp_dev->client));
|
||||
pios_udp_num_devices++;
|
||||
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
/* initialize */
|
||||
udp_dev->rx_in_cb = NULL;
|
||||
udp_dev->tx_out_cb = NULL;
|
||||
udp_dev->cfg=cfg;
|
||||
|
||||
/* assign socket */
|
||||
udp_dev->socket = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP);
|
||||
memset(&udp_dev->server,0,sizeof(udp_dev->server));
|
||||
memset(&udp_dev->client,0,sizeof(udp_dev->client));
|
||||
udp_dev->server.sin_family = AF_INET;
|
||||
udp_dev->server.sin_addr.s_addr = inet_addr(udp_dev->cfg->ip);
|
||||
udp_dev->server.sin_port = htons(udp_dev->cfg->port);
|
||||
int res= bind(udp_dev->socket, (struct sockaddr *)&udp_dev->server,sizeof(udp_dev->server));
|
||||
|
||||
/* Create transmit thread for this connection */
|
||||
pthread_create(&udp_dev->rxThread, NULL, PIOS_UDP_RxThread, (void*)udp_dev);
|
||||
|
||||
printf("udp dev %i - socket %i opened - result %i\n",pios_udp_num_devices-1,udp_dev->socket,res);
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
* puts more than one byte onto the transmit buffer (used for atomic sends)<BR>
|
||||
* (blocking function)
|
||||
* \param[in] UDP UDP name
|
||||
* \param[in] *buffer pointer to buffer to be sent
|
||||
* \param[in] len number of bytes to be sent
|
||||
* \return 0 if no error
|
||||
* \return -1 if UDP not available
|
||||
* \return -3 if UDP not supported by UDPTxBufferPut Routine
|
||||
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
int32_t PIOS_UDP_TxBufferPutMore(uint8_t udp, uint8_t *buffer, uint16_t len)
|
||||
|
||||
void PIOS_UDP_ChangeBaud(uint32_t udp_id, uint32_t baud)
|
||||
{
|
||||
struct pios_udp_dev * udp_dev;
|
||||
|
||||
/* Get a handle for the device configuration */
|
||||
udp_dev = find_udp_dev_by_id(udp);
|
||||
|
||||
if (!udp_dev) {
|
||||
/* Undefined UDP port for this board (see pios_board.c) */
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (len >= PIOS_UDP_RX_BUFFER_SIZE) {
|
||||
/* Buffer cannot accept all requested bytes (retry) */
|
||||
return -2;
|
||||
}
|
||||
|
||||
/* send data to client - blocking*/
|
||||
/* use blocking IO */
|
||||
int flags = fcntl(udp_dev->socket, F_GETFL, 0);
|
||||
fcntl(udp_dev->socket, F_SETFL, flags & ~O_NONBLOCK);
|
||||
sendto(udp_dev->socket, buffer, len, 0,
|
||||
(struct sockaddr *) &udp_dev->client,
|
||||
sizeof(udp_dev->client));
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
/**
|
||||
* doesn't apply!
|
||||
*/
|
||||
}
|
||||
|
||||
/**
|
||||
* puts a byte onto the transmit buffer
|
||||
* \param[in] UDP UDP name
|
||||
* \param[in] b byte which should be put into Tx buffer
|
||||
* \return 0 if no error
|
||||
* \return -1 if UDP not available
|
||||
* \return -2 if buffer full (retry)
|
||||
* \return -3 if UDP not supported by UDPTxBufferPut Routine
|
||||
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
int32_t PIOS_UDP_TxBufferPut_NonBlocking(uint8_t udp, uint8_t b)
|
||||
|
||||
static void PIOS_UDP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail)
|
||||
{
|
||||
return PIOS_UDP_TxBufferPutMoreNonBlocking(udp, &b, 1);
|
||||
/**
|
||||
* lazy!
|
||||
*/
|
||||
}
|
||||
|
||||
/**
|
||||
* puts a byte onto the transmit buffer<BR>
|
||||
* (blocking function)
|
||||
* \param[in] UDP UDP name
|
||||
* \param[in] b byte which should be put into Tx buffer
|
||||
* \return 0 if no error
|
||||
* \return -1 if UDP not available
|
||||
* \return -3 if UDP not supported by UDPTxBufferPut Routine
|
||||
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
int32_t PIOS_UDP_TxBufferPut(uint8_t udp, uint8_t b)
|
||||
|
||||
static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail)
|
||||
{
|
||||
return PIOS_UDP_TxBufferPutMore(udp, &b, 1);
|
||||
pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id);
|
||||
|
||||
PIOS_Assert(udp_dev);
|
||||
|
||||
int32_t length,len,rem;
|
||||
|
||||
/**
|
||||
* we send everything directly whenever notified of data to send (lazy!)
|
||||
*/
|
||||
if (udp_dev->tx_out_cb) {
|
||||
while (tx_bytes_avail>0) {
|
||||
bool tx_need_yield = false;
|
||||
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,
|
||||
(struct sockaddr *) &udp_dev->client,
|
||||
sizeof(udp_dev->client));
|
||||
if (len<=0) {
|
||||
rem=0;
|
||||
} else {
|
||||
rem -= len;
|
||||
}
|
||||
}
|
||||
tx_bytes_avail -= length;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
static void PIOS_UDP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context)
|
||||
{
|
||||
pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id);
|
||||
|
||||
PIOS_Assert(udp_dev);
|
||||
|
||||
/*
|
||||
* Order is important in these assignments since ISR uses _cb
|
||||
* field to determine if it's ok to dereference _cb and _context
|
||||
*/
|
||||
udp_dev->rx_in_context = context;
|
||||
udp_dev->rx_in_cb = rx_in_cb;
|
||||
}
|
||||
|
||||
static void PIOS_UDP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context)
|
||||
{
|
||||
pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id);
|
||||
|
||||
PIOS_Assert(udp_dev);
|
||||
|
||||
/*
|
||||
* Order is important in these assignments since ISR uses _cb
|
||||
* field to determine if it's ok to dereference _cb and _context
|
||||
*/
|
||||
udp_dev->tx_out_context = context;
|
||||
udp_dev->tx_out_cb = tx_out_cb;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#endif
|
||||
|
@ -96,6 +96,22 @@ void PIOS_ADXL345_Init()
|
||||
PIOS_ADXL345_SetMeasure(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Return number of entries in the fifo
|
||||
*/
|
||||
uint8_t PIOS_ADXL345_FifoElements()
|
||||
{
|
||||
uint8_t buf[2] = {0,0};
|
||||
uint8_t rec[2] = {0,0};
|
||||
buf[0] = ADXL_FIFOSTATUS_ADDR | ADXL_READ_BIT ; // Read fifo status
|
||||
|
||||
PIOS_ADXL345_ClaimBus();
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,&buf[0],&rec[0],sizeof(buf),NULL);
|
||||
PIOS_ADXL345_ReleaseBus();
|
||||
|
||||
return rec[1] & 0x3f;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read a single set of values from the x y z channels
|
||||
* @returns The number of samples remaining in the fifo
|
||||
|
@ -16,6 +16,7 @@
|
||||
#define ADXL_MULTI_BIT 0x40
|
||||
|
||||
#define ADXL_X0_ADDR 0x32
|
||||
#define ADXL_FIFOSTATUS_ADDR 0x39
|
||||
|
||||
#define ADXL_RATE_ADDR 0x2C
|
||||
#define ADXL_RATE_100 0x0A
|
||||
@ -52,5 +53,6 @@ void PIOS_ADXL345_FifoDepth(uint8_t depth);
|
||||
void PIOS_ADXL345_Attach(uint32_t spi_id);
|
||||
void PIOS_ADXL345_Init();
|
||||
uint8_t PIOS_ADXL345_Read(struct pios_adxl345_data * data);
|
||||
uint8_t PIOS_ADXL345_FifoElements();
|
||||
|
||||
#endif
|
||||
|
@ -27,7 +27,11 @@
|
||||
#include "openpilot.h"
|
||||
|
||||
// Private constants
|
||||
#if defined(PIOS_EVENTDISAPTCHER_QUEUE)
|
||||
#define MAX_QUEUE_SIZE PIOS_EVENTDISAPTCHER_QUEUE
|
||||
#else
|
||||
#define MAX_QUEUE_SIZE 20
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_EVENTDISPATCHER_STACK_SIZE)
|
||||
#define STACK_SIZE PIOS_EVENTDISPATCHER_STACK_SIZE
|
||||
|
@ -19,6 +19,19 @@ defineReplace(addNewline) {
|
||||
return($$escape_expand(\\n\\t))
|
||||
}
|
||||
|
||||
defineReplace(qtLibraryName) {
|
||||
unset(LIBRARY_NAME)
|
||||
LIBRARY_NAME = $$1
|
||||
CONFIG(debug, debug|release) {
|
||||
!debug_and_release|build_pass {
|
||||
mac:RET = $$member(LIBRARY_NAME, 0)_debug
|
||||
else:win32:RET = $$member(LIBRARY_NAME, 0)d
|
||||
}
|
||||
}
|
||||
isEmpty(RET):RET = $$LIBRARY_NAME
|
||||
return($$RET)
|
||||
}
|
||||
|
||||
# For use in custom compilers which just copy files
|
||||
win32:i_flag = i
|
||||
defineReplace(stripSrcDir) {
|
||||
|
@ -11,16 +11,15 @@ SOURCES += main.cpp
|
||||
include(../rpath.pri)
|
||||
include(../libs/utils/utils.pri)
|
||||
|
||||
win32 {
|
||||
CONFIG(debug, debug|release):LIBS *= -lExtensionSystemd -lAggregationd -lQExtSerialPortd
|
||||
else:LIBS *= -lExtensionSystem -lAggregation -lQExtSerialPort
|
||||
LIBS *= -l$$qtLibraryName(ExtensionSystem) -l$$qtLibraryName(Aggregation)
|
||||
|
||||
win32 {
|
||||
# CONFIG(debug, debug|release):LIBS *= -lExtensionSystemd -lAggregationd -lQExtSerialPortd
|
||||
# else:LIBS *= -lExtensionSystem -lAggregation -lQExtSerialPort
|
||||
RC_FILE = openpilotgcs.rc
|
||||
target.path = /bin
|
||||
INSTALLS += target
|
||||
} else:macx {
|
||||
CONFIG(debug, debug|release):LIBS *= -lExtensionSystem_debug -lAggregation_debug
|
||||
else:LIBS *= -lExtensionSystem -lAggregation
|
||||
LIBS += -framework CoreFoundation
|
||||
ICON = openpilotgcs.icns
|
||||
QMAKE_INFO_PLIST = Info.plist
|
||||
@ -28,8 +27,6 @@ win32 {
|
||||
FILETYPES.path = Contents/Resources
|
||||
QMAKE_BUNDLE_DATA += FILETYPES
|
||||
} else {
|
||||
LIBS *= -lExtensionSystem -lAggregation
|
||||
|
||||
target.path = /bin
|
||||
INSTALLS += target
|
||||
}
|
||||
|
@ -1 +1 @@
|
||||
LIBS *= -l$$qtLibraryTarget(Aggregation)
|
||||
LIBS *= -l$$qtLibraryName(Aggregation)
|
||||
|
@ -1,3 +1,3 @@
|
||||
include(extensionsystem_dependencies.pri)
|
||||
|
||||
LIBS *= -l$$qtLibraryTarget(ExtensionSystem)
|
||||
LIBS *= -l$$qtLibraryName(ExtensionSystem)
|
||||
|
@ -1,2 +1,2 @@
|
||||
QT += opengl
|
||||
LIBS += -l$$qtLibraryTarget(GLC_lib)
|
||||
LIBS *= -l$$qtLibraryName(GLC_lib)
|
||||
|
@ -1,4 +1,4 @@
|
||||
LIBS += -l$$qtLibraryTarget(QxtCore)
|
||||
LIBS *= -l$$qtLibraryName(QxtCore)
|
||||
|
||||
INCLUDEPATH += \
|
||||
$$GCS_SOURCE_TREE/src/libs/libqxt/src/core
|
||||
|
@ -1 +1 @@
|
||||
LIBS *= -l$$qtLibraryTarget(opmapwidget)
|
||||
LIBS *= -l$$qtLibraryName(opmapwidget)
|
||||
|
@ -1,2 +1,2 @@
|
||||
LIBS += -l$$qtLibraryTarget(QExtSerialPort)
|
||||
LIBS *= -l$$qtLibraryName(QExtSerialPort)
|
||||
|
||||
|
@ -1 +1 @@
|
||||
LIBS *= -l$$qtLibraryTarget(QScienceSpinBox)
|
||||
LIBS *= -l$$qtLibraryName(QScienceSpinBox)
|
||||
|
@ -1 +1 @@
|
||||
LIBS *= -l$$qtLibraryTarget(QtConcurrent)
|
||||
LIBS *= -l$$qtLibraryName(QtConcurrent)
|
||||
|
@ -1,2 +1,2 @@
|
||||
LIBS += -l$$qtLibraryTarget(Qwt)
|
||||
LIBS *= -l$$qtLibraryName(Qwt)
|
||||
|
||||
|
@ -1 +1 @@
|
||||
LIBS += -l$$qtLibraryTarget(sdlgamepad)
|
||||
LIBS *= -l$$qtLibraryName(sdlgamepad)
|
||||
|
38
ground/openpilotgcs/src/libs/utils/mylistwidget.cpp
Normal file
38
ground/openpilotgcs/src/libs/utils/mylistwidget.cpp
Normal file
@ -0,0 +1,38 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mylistwidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup
|
||||
* @{
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "mylistwidget.h"
|
||||
|
||||
QStyleOptionViewItem MyListWidget::viewOptions() const
|
||||
{
|
||||
QStyleOptionViewItem option = QListWidget::viewOptions();
|
||||
if (m_iconAbove) {
|
||||
option.decorationPosition = QStyleOptionViewItem::Top;
|
||||
option.displayAlignment = Qt::AlignCenter;
|
||||
}
|
||||
return option;
|
||||
}
|
53
ground/openpilotgcs/src/libs/utils/mylistwidget.h
Normal file
53
ground/openpilotgcs/src/libs/utils/mylistwidget.h
Normal file
@ -0,0 +1,53 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mylistwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup
|
||||
* @{
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 MYLISTWIDGET_H
|
||||
#define MYLISTWIDGET_H
|
||||
|
||||
#include "utils_global.h"
|
||||
|
||||
#include <QtGui/QListWidget>
|
||||
|
||||
/*
|
||||
* MyListWidget is a plain QListWidget but with the added option
|
||||
* to place the icon above the label in ListMode. This is achieved
|
||||
* the easiest by subclassing QListWidget and overriding viewOptions().
|
||||
*/
|
||||
class QTCREATOR_UTILS_EXPORT MyListWidget : public QListWidget
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
MyListWidget(QWidget *parent) : QListWidget(parent), m_iconAbove(false) { }
|
||||
void setIconAbove(bool iconAbove) { m_iconAbove = iconAbove; }
|
||||
protected:
|
||||
QStyleOptionViewItem viewOptions() const;
|
||||
private:
|
||||
bool m_iconAbove;
|
||||
};
|
||||
|
||||
#endif // MYLISTWIDGET_H
|
109
ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp
Normal file
109
ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp
Normal file
@ -0,0 +1,109 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mytabbedstackwidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup
|
||||
* @{
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "mytabbedstackwidget.h"
|
||||
#include <QtGui/QVBoxLayout>
|
||||
#include <QtGui/QHBoxLayout>
|
||||
#include <QtGui/QLabel>
|
||||
#include <QtCore/QDebug>
|
||||
|
||||
MyTabbedStackWidget::MyTabbedStackWidget(QWidget *parent, bool isVertical, bool iconAbove)
|
||||
: QWidget(parent),
|
||||
m_vertical(isVertical),
|
||||
m_iconAbove(iconAbove)
|
||||
{
|
||||
m_listWidget = new MyListWidget(this);
|
||||
m_listWidget->setIconAbove(m_iconAbove);
|
||||
m_stackWidget = new QStackedWidget();
|
||||
m_stackWidget->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
|
||||
|
||||
QBoxLayout *toplevelLayout;
|
||||
if (m_vertical) {
|
||||
toplevelLayout = new QHBoxLayout;
|
||||
toplevelLayout->addWidget(m_listWidget);
|
||||
toplevelLayout->addWidget(m_stackWidget);
|
||||
m_listWidget->setFlow(QListView::TopToBottom);
|
||||
m_listWidget->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Expanding);
|
||||
} else {
|
||||
toplevelLayout = new QVBoxLayout;
|
||||
toplevelLayout->addWidget(m_stackWidget);
|
||||
toplevelLayout->addWidget(m_listWidget);
|
||||
m_listWidget->setFlow(QListView::LeftToRight);
|
||||
m_listWidget->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed);
|
||||
}
|
||||
if (m_iconAbove && m_vertical)
|
||||
m_listWidget->setFixedWidth(90); // this should be computed instead
|
||||
|
||||
toplevelLayout->setSpacing(0);
|
||||
toplevelLayout->setContentsMargins(0, 0, 0, 0);
|
||||
m_listWidget->setSpacing(0);
|
||||
m_listWidget->setContentsMargins(0, 0, 0, 0);
|
||||
m_stackWidget->setContentsMargins(0, 0, 0, 0);
|
||||
setLayout(toplevelLayout);
|
||||
|
||||
connect(m_listWidget, SIGNAL(currentRowChanged(int)), this, SLOT(showWidget(int)));
|
||||
}
|
||||
|
||||
void MyTabbedStackWidget::insertTab(const int index, QWidget *tab, const QIcon &icon, const QString &label)
|
||||
{
|
||||
tab->setContentsMargins(0, 0, 0, 0);
|
||||
m_stackWidget->insertWidget(index, tab);
|
||||
QListWidgetItem *item = new QListWidgetItem(icon, label);
|
||||
item->setToolTip(label);
|
||||
m_listWidget->insertItem(index, item);
|
||||
}
|
||||
|
||||
void MyTabbedStackWidget::removeTab(int index)
|
||||
{
|
||||
m_stackWidget->removeWidget(m_stackWidget->widget(index));
|
||||
QListWidgetItem *item = m_listWidget->item(index);
|
||||
m_listWidget->removeItemWidget(item);
|
||||
delete item;
|
||||
}
|
||||
|
||||
int MyTabbedStackWidget::currentIndex() const
|
||||
{
|
||||
return m_listWidget->currentRow();
|
||||
}
|
||||
|
||||
void MyTabbedStackWidget::setCurrentIndex(int index)
|
||||
{
|
||||
m_listWidget->setCurrentRow(index);
|
||||
}
|
||||
|
||||
void MyTabbedStackWidget::showWidget(int index)
|
||||
{
|
||||
emit currentAboutToShow(index);
|
||||
m_stackWidget->setCurrentIndex(index);
|
||||
emit currentChanged(index);
|
||||
}
|
||||
|
||||
void MyTabbedStackWidget::insertCornerWidget(int index, QWidget *widget)
|
||||
{
|
||||
widget->hide();
|
||||
}
|
||||
|
74
ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h
Normal file
74
ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h
Normal file
@ -0,0 +1,74 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mytabbedstackwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup
|
||||
* @{
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 MYTABBEDSTACKWIDGET_H
|
||||
#define MYTABBEDSTACKWIDGET_H
|
||||
|
||||
#include "utils/mylistwidget.h"
|
||||
#include <QtGui/QStackedWidget>
|
||||
|
||||
/*
|
||||
* MyTabbedStackWidget is a MyListWidget combined with a QStackedWidget,
|
||||
* similar in function to QTabWidget.
|
||||
*/
|
||||
class QTCREATOR_UTILS_EXPORT MyTabbedStackWidget : public QWidget
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
MyTabbedStackWidget(QWidget *parent = 0, bool isVertical = false, bool iconAbove = true);
|
||||
|
||||
void insertTab(int index, QWidget *tab, const QIcon &icon, const QString &label);
|
||||
void removeTab(int index);
|
||||
void setIconSize(int size) { m_listWidget->setIconSize(QSize(size, size)); }
|
||||
|
||||
int currentIndex() const;
|
||||
|
||||
void insertCornerWidget(int index, QWidget *widget);
|
||||
int cornerWidgetCount() { return m_cornerWidgetCount; }
|
||||
|
||||
signals:
|
||||
void currentAboutToShow(int index);
|
||||
void currentChanged(int index);
|
||||
|
||||
public slots:
|
||||
void setCurrentIndex(int index);
|
||||
|
||||
private slots:
|
||||
void showWidget(int index);
|
||||
|
||||
private:
|
||||
MyListWidget *m_listWidget;
|
||||
QStackedWidget *m_stackWidget;
|
||||
QWidget *m_selectionWidget;
|
||||
bool m_vertical;
|
||||
bool m_iconAbove;
|
||||
int m_cornerWidgetCount;
|
||||
};
|
||||
|
||||
#endif // MYTABBEDSTACKWIDGET_H
|
48
ground/openpilotgcs/src/libs/utils/mytabwidget.cpp
Normal file
48
ground/openpilotgcs/src/libs/utils/mytabwidget.cpp
Normal file
@ -0,0 +1,48 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mytabwidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup
|
||||
* @{
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "mytabwidget.h"
|
||||
#include <QtGui/QTabBar>
|
||||
|
||||
MyTabWidget::MyTabWidget(QWidget *parent)
|
||||
: QTabWidget(parent)
|
||||
{
|
||||
QTabBar *tabBar = QTabWidget::tabBar();
|
||||
connect(tabBar, SIGNAL(tabMoved(int, int)), this, SLOT(myTabMoved(int,int)));
|
||||
}
|
||||
|
||||
void MyTabWidget::moveTab(int from, int to)
|
||||
{
|
||||
QTabBar *tabBar = QTabWidget::tabBar();
|
||||
tabBar->moveTab(from, to);
|
||||
}
|
||||
|
||||
|
||||
void MyTabWidget::myTabMoved(int from, int to)
|
||||
{
|
||||
emit tabMoved(from, to);
|
||||
}
|
55
ground/openpilotgcs/src/libs/utils/mytabwidget.h
Normal file
55
ground/openpilotgcs/src/libs/utils/mytabwidget.h
Normal file
@ -0,0 +1,55 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mytabwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup
|
||||
* @{
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 MYTABWIDGET_H
|
||||
#define MYTABWIDGET_H
|
||||
|
||||
#include "utils_global.h"
|
||||
|
||||
#include <QtGui/QTabWidget>
|
||||
|
||||
/*
|
||||
* MyTabWidget is a plain QTabWidget with the addition of the signal
|
||||
* tabMoved(int, int) which QTabBar has but for some reason is
|
||||
* not made available from QTabWidget.
|
||||
*/
|
||||
class QTCREATOR_UTILS_EXPORT MyTabWidget : public QTabWidget
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
MyTabWidget(QWidget *parent = 0);
|
||||
void moveTab(int from, int to);
|
||||
|
||||
private slots:
|
||||
void myTabMoved(int from, int to);
|
||||
|
||||
signals:
|
||||
void tabMoved(int from, int to);
|
||||
};
|
||||
|
||||
#endif // MYTABWIDGET_H
|
@ -1,9 +1 @@
|
||||
macx {
|
||||
CONFIG(debug, debug|release):LIBS *= -lUtils_debug
|
||||
else:LIBS *= -lUtils
|
||||
} else:win32 {
|
||||
CONFIG(debug, debug|release):LIBS *= -lUtilsd
|
||||
else:LIBS *= -lUtils
|
||||
} else {
|
||||
LIBS += -l$$qtLibraryTarget(Utils)
|
||||
}
|
||||
LIBS *= -l$$qtLibraryName(Utils)
|
||||
|
@ -45,7 +45,10 @@ SOURCES += reloadpromptutils.cpp \
|
||||
coordinateconversions.cpp \
|
||||
pathutils.cpp \
|
||||
worldmagmodel.cpp \
|
||||
homelocationutil.cpp
|
||||
homelocationutil.cpp \
|
||||
mytabbedstackwidget.cpp \
|
||||
mytabwidget.cpp \
|
||||
mylistwidget.cpp
|
||||
SOURCES += xmlconfig.cpp
|
||||
|
||||
win32 {
|
||||
@ -96,7 +99,10 @@ HEADERS += utils_global.h \
|
||||
coordinateconversions.h \
|
||||
pathutils.h \
|
||||
worldmagmodel.h \
|
||||
homelocationutil.h
|
||||
homelocationutil.h \
|
||||
mytabbedstackwidget.h \
|
||||
mytabwidget.h \
|
||||
mylistwidget.h
|
||||
HEADERS += xmlconfig.h
|
||||
|
||||
FORMS += filewizardpage.ui \
|
||||
|
@ -8,7 +8,7 @@ DESTDIR = $$GCS_LIBRARY_PATH
|
||||
|
||||
include(rpath.pri)
|
||||
|
||||
TARGET = $$qtLibraryTarget($$TARGET)
|
||||
TARGET = $$qtLibraryName($$TARGET)
|
||||
|
||||
contains(QT_CONFIG, reduce_exports):CONFIG += hGCS_symbols
|
||||
|
||||
|
@ -23,7 +23,7 @@ copy2build.name = COPY ${QMAKE_FILE_IN}
|
||||
copy2build.CONFIG += no_link
|
||||
QMAKE_EXTRA_COMPILERS += copy2build
|
||||
|
||||
TARGET = $$qtLibraryTarget($$TARGET)
|
||||
TARGET = $$qtLibraryName($$TARGET)
|
||||
|
||||
macx {
|
||||
QMAKE_LFLAGS_SONAME = -Wl,-install_name,@executable_path/../Plugins/$${PROVIDER}/
|
||||
|
@ -31,7 +31,7 @@
|
||||
<string/>
|
||||
</property>
|
||||
<property name="pixmap">
|
||||
<pixmap>:/configgadget/images/coptercontrol.svg</pixmap>
|
||||
<pixmap resource="configgadget.qrc">:/configgadget/images/coptercontrol.svg</pixmap>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>true</bool>
|
||||
@ -103,13 +103,6 @@
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>11</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Telemetry speed:</string>
|
||||
</property>
|
||||
@ -122,6 +115,19 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
@ -156,24 +162,24 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Changes on this page only take effect after board reset or power cycle</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Changes on this page only take effect after board reset or power cycle</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
@ -187,6 +193,44 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="cchwHelp">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../coreplugin/core.qrc">
|
||||
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveTelemetryToRAM">
|
||||
<property name="toolTip">
|
||||
@ -231,6 +275,9 @@ Beware of not locking yourself out!</string>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
<resources>
|
||||
<include location="configgadget.qrc"/>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
||||
|
@ -32,7 +32,8 @@
|
||||
#include <QtGui/QTextEdit>
|
||||
#include <QtGui/QVBoxLayout>
|
||||
#include <QtGui/QPushButton>
|
||||
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
|
||||
ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
@ -43,6 +44,7 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi);
|
||||
addUAVObjectToWidgetRelation("HwSettings","CC_MainPort",m_telemetry->cbTele);
|
||||
addUAVObjectToWidgetRelation("HwSettings","RcvrPort",m_telemetry->cbRcvr);
|
||||
connect(m_telemetry->cchwHelp,SIGNAL(clicked()),this,SLOT(openHelp()));
|
||||
enableControls(false);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
@ -72,3 +74,13 @@ void ConfigCCHWWidget::widgetsContentsChanged()
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigCCHWWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/CopterControl+HW+Settings", QUrl::StrictMode) );
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
@ -44,6 +44,7 @@ public:
|
||||
ConfigCCHWWidget(QWidget *parent = 0);
|
||||
~ConfigCCHWWidget();
|
||||
private slots:
|
||||
void openHelp();
|
||||
void refreshValues();
|
||||
void widgetsContentsChanged();
|
||||
|
||||
|
@ -37,6 +37,9 @@
|
||||
#include <math.h>
|
||||
#include <QMessageBox>
|
||||
|
||||
#include "mixersettings.h"
|
||||
#include "systemsettings.h"
|
||||
|
||||
#define Pi 3.14159265358979323846
|
||||
|
||||
|
||||
@ -1179,7 +1182,7 @@ void ConfigccpmWidget::requestccpmUpdate()
|
||||
{
|
||||
#define MaxAngleError 2
|
||||
int MixerDataFromHeli[8][5];
|
||||
QString MixerOutputType[8];
|
||||
quint8 MixerOutputType[8];
|
||||
int EngineChannel,TailRotorChannel,ServoChannels[4],ServoAngles[4],SortAngles[4],CalcAngles[4],ServoCurve2[4];
|
||||
int NumServos=0;
|
||||
double Collective=0.0;
|
||||
@ -1191,39 +1194,45 @@ void ConfigccpmWidget::requestccpmUpdate()
|
||||
if (updatingToHardware)return;
|
||||
updatingFromHardware=TRUE;
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
int i,j;
|
||||
UAVObjectField *field;
|
||||
UAVDataObject* obj;
|
||||
|
||||
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
|
||||
field = obj->getField(QString("GUIConfigData"));
|
||||
GUIConfigData.UAVObject[0]=field->getValue(0).toUInt();
|
||||
GUIConfigData.UAVObject[1]=field->getValue(1).toUInt();
|
||||
UpdatCCPMUIFromOptions();
|
||||
SystemSettings * systemSettings = SystemSettings::GetInstance(getObjectManager());
|
||||
SystemSettings::DataFields systemSettingsData = systemSettings->getData();
|
||||
|
||||
Q_ASSERT(SystemSettings::GUICONFIGDATA_NUMELEM ==
|
||||
(sizeof(GUIConfigData.UAVObject) / sizeof(GUIConfigData.UAVObject[0])));
|
||||
|
||||
for(i = 0; i < SystemSettings::GUICONFIGDATA_NUMELEM; i++)
|
||||
GUIConfigData.UAVObject[i]=systemSettingsData.GUIConfigData[i];
|
||||
|
||||
UpdatCCPMUIFromOptions();
|
||||
|
||||
// Get existing mixer settings
|
||||
MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager());
|
||||
MixerSettings::DataFields mixerSettingsData = mixerSettings->getData();
|
||||
|
||||
obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(obj);
|
||||
|
||||
//go through the user data and update the mixer matrix
|
||||
for (i=0;i<8;i++)
|
||||
for (j=0;j<5;j++)
|
||||
{
|
||||
field = obj->getField(tr( "Mixer%1Vector" ).arg(i+1));
|
||||
//config the vector
|
||||
for (j=0;j<5;j++)
|
||||
{
|
||||
MixerDataFromHeli[i][j] = field->getValue(j).toInt();
|
||||
//field->setValue(m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt(),j);
|
||||
}
|
||||
}
|
||||
for (i=0;i<8;i++)
|
||||
{
|
||||
field = obj->getField(tr( "Mixer%1Type" ).arg(i+1));
|
||||
MixerOutputType[i] = field->getValue().toString();
|
||||
MixerDataFromHeli[0][j] = mixerSettingsData.Mixer1Vector[j];
|
||||
MixerDataFromHeli[1][j] = mixerSettingsData.Mixer2Vector[j];
|
||||
MixerDataFromHeli[2][j] = mixerSettingsData.Mixer3Vector[j];
|
||||
MixerDataFromHeli[3][j] = mixerSettingsData.Mixer4Vector[j];
|
||||
MixerDataFromHeli[4][j] = mixerSettingsData.Mixer5Vector[j];
|
||||
MixerDataFromHeli[5][j] = mixerSettingsData.Mixer6Vector[j];
|
||||
MixerDataFromHeli[6][j] = mixerSettingsData.Mixer7Vector[j];
|
||||
MixerDataFromHeli[7][j] = mixerSettingsData.Mixer8Vector[j];
|
||||
}
|
||||
|
||||
MixerOutputType[0] = mixerSettingsData.Mixer1Type;
|
||||
MixerOutputType[1] = mixerSettingsData.Mixer2Type;
|
||||
MixerOutputType[2] = mixerSettingsData.Mixer3Type;
|
||||
MixerOutputType[3] = mixerSettingsData.Mixer4Type;
|
||||
MixerOutputType[4] = mixerSettingsData.Mixer5Type;
|
||||
MixerOutputType[5] = mixerSettingsData.Mixer6Type;
|
||||
MixerOutputType[6] = mixerSettingsData.Mixer7Type;
|
||||
MixerOutputType[7] = mixerSettingsData.Mixer8Type;
|
||||
|
||||
EngineChannel =-1;
|
||||
TailRotorChannel =-1;
|
||||
for (j=0;j<5;j++)
|
||||
@ -1239,7 +1248,7 @@ void ConfigccpmWidget::requestccpmUpdate()
|
||||
for (i=0;i<8;i++)
|
||||
{
|
||||
//check if this is the engine... Throttle only
|
||||
if ((MixerOutputType[i].compare("Motor")==0)&&
|
||||
if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_MOTOR)&&
|
||||
(MixerDataFromHeli[i][0]>0)&&//ThrottleCurve1
|
||||
(MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2
|
||||
(MixerDataFromHeli[i][2]==0)&&//Roll
|
||||
@ -1251,7 +1260,7 @@ void ConfigccpmWidget::requestccpmUpdate()
|
||||
|
||||
}
|
||||
//check if this is the tail rotor... REVO and YAW
|
||||
if ((MixerOutputType[i].compare("Servo")==0)&&
|
||||
if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_SERVO)&&
|
||||
//(MixerDataFromHeli[i][0]!=0)&&//ThrottleCurve1
|
||||
(MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2
|
||||
(MixerDataFromHeli[i][2]==0)&&//Roll
|
||||
@ -1264,7 +1273,7 @@ void ConfigccpmWidget::requestccpmUpdate()
|
||||
m_ccpm->ccpmREVOspinBox->setValue((MixerDataFromHeli[i][0]*100)/127);
|
||||
}
|
||||
//check if this is a swashplate servo... Throttle is zero
|
||||
if ((MixerOutputType[i].compare("Servo")==0)&&
|
||||
if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_SERVO)&&
|
||||
(MixerDataFromHeli[i][0]==0)&&//ThrottleCurve1
|
||||
//(MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2
|
||||
//(MixerDataFromHeli[i][2]==0)&&//Roll
|
||||
@ -1275,193 +1284,23 @@ void ConfigccpmWidget::requestccpmUpdate()
|
||||
ServoCurve2[NumServos]=MixerDataFromHeli[i][1];//record the ThrottleCurve2 contribution to this servo
|
||||
ServoAngles[NumServos]=NumServos*45;//make this 0 for the final version
|
||||
|
||||
//if (NumServos==0)m_ccpm->ccpmServoWChannel->setCurrentIndex(i);
|
||||
//if (NumServos==1)m_ccpm->ccpmServoXChannel->setCurrentIndex(i);
|
||||
//if (NumServos==2)m_ccpm->ccpmServoYChannel->setCurrentIndex(i);
|
||||
//if (NumServos==3)m_ccpm->ccpmServoZChannel->setCurrentIndex(i);
|
||||
NumServos++;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
//just call it user angles for now....
|
||||
/*
|
||||
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("Custom - User Angles"));
|
||||
|
||||
if (NumServos>1)
|
||||
{
|
||||
if((ServoCurve2[0]==0)&&(ServoCurve2[1]==0)&&(ServoCurve2[2]==0)&&(ServoCurve2[3]==0))
|
||||
{
|
||||
//fixed pitch heli
|
||||
isCCPM=0;
|
||||
m_ccpm->ccpmCollectiveSlider->setValue(0);
|
||||
Collective = 0.0;
|
||||
}
|
||||
if(ServoCurve2[0]==ServoCurve2[1])
|
||||
{
|
||||
if ((NumServos<3)||(ServoCurve2[1]==ServoCurve2[2]))
|
||||
{
|
||||
if ((NumServos<4)||(ServoCurve2[2]==ServoCurve2[3]))
|
||||
{//all the servos have the same ThrottleCurve2 setting so this must be a CCPM config
|
||||
isCCPM=1;
|
||||
Collective = ((double)ServoCurve2[0]*100.00)/127.00;
|
||||
m_ccpm->ccpmCollectiveSlider->setValue((int)Collective);
|
||||
m_ccpm->ccpmCollectivespinBox->setValue((int)Collective);
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{//must be a custom config... "Custom - Advanced Settings"
|
||||
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("Custom - Advanced Settings"));
|
||||
}
|
||||
|
||||
HeadRotation=0;
|
||||
|
||||
HeadRotation=m_ccpm->ccpmSingleServo->currentIndex();
|
||||
//calculate the angles
|
||||
for(j=0;j<NumServos;j++)
|
||||
{
|
||||
//MixerDataFromHeli[i][2]=(127.0*(1-CollectiveConstant)*sin((CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Roll
|
||||
//MixerDataFromHeli[i][3]=(127.0*(1-CollectiveConstant)*cos((CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Pitch
|
||||
a1=((double)MixerDataFromHeli[ServoChannels[j]][2]/(1.27*(100.0-Collective)));
|
||||
a2=((double)MixerDataFromHeli[ServoChannels[j]][3]/(1.27*(100.0-Collective)));
|
||||
ServoAngles[j]=fmod(360.0+atan2(-a1,a2)/(Pi/180.00),360.0);
|
||||
//check the angles for one being a multiple of 90deg
|
||||
if (fmod(ServoAngles[j],90)<MaxAngleError)
|
||||
{
|
||||
HeadRotation=ServoAngles[j]/90;
|
||||
}
|
||||
|
||||
}
|
||||
//set the head rotation
|
||||
//m_ccpm->ccpmSingleServo->setCurrentIndex(HeadRotation);
|
||||
|
||||
//calculate the un rotated angles
|
||||
for(j=0;j<NumServos;j++)
|
||||
{
|
||||
CalcAngles[j] = fmod(360.0+ServoAngles[j]-(double)HeadRotation*90.0,360.0);
|
||||
}
|
||||
//sort the calc angles do the smallest is first...brute force...
|
||||
for(i=0;i<5;i++)
|
||||
for(j=0;j<NumServos-1;j++)
|
||||
{
|
||||
if (CalcAngles[SortAngles[j]] > CalcAngles[SortAngles[j+1]])
|
||||
{//swap the sorted angles
|
||||
temp = SortAngles[j];
|
||||
SortAngles[j]=SortAngles[j+1];
|
||||
SortAngles[j+1]=temp;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//m_ccpm->ccpmAngleW->setValue(ServoAngles[SortAngles[0]]);
|
||||
//m_ccpm->ccpmAngleX->setValue(ServoAngles[SortAngles[1]]);
|
||||
//m_ccpm->ccpmAngleY->setValue(ServoAngles[SortAngles[2]]);
|
||||
//m_ccpm->ccpmAngleZ->setValue(ServoAngles[SortAngles[3]]);
|
||||
|
||||
//m_ccpm->ccpmServoWChannel->setCurrentIndex(ServoChannels[SortAngles[0]]);
|
||||
//m_ccpm->ccpmServoXChannel->setCurrentIndex(ServoChannels[SortAngles[1]]);
|
||||
//m_ccpm->ccpmServoYChannel->setCurrentIndex(ServoChannels[SortAngles[2]]);
|
||||
//m_ccpm->ccpmServoZChannel->setCurrentIndex(ServoChannels[SortAngles[3]]);
|
||||
m_ccpm->ccpmServoWChannel->setCurrentIndex(ServoChannels[0]);
|
||||
m_ccpm->ccpmServoXChannel->setCurrentIndex(ServoChannels[1]);
|
||||
m_ccpm->ccpmServoYChannel->setCurrentIndex(ServoChannels[2]);
|
||||
m_ccpm->ccpmServoZChannel->setCurrentIndex(ServoChannels[3]);
|
||||
|
||||
|
||||
//Types << "CCPM 2 Servo 90º" << "CCPM 3 Servo 120º" << "CCPM 3 Servo 140º" << "FP 2 Servo 90º" << "Custom - User Angles" << "Custom - Advanced Settings" ;
|
||||
|
||||
|
||||
//check this against known combinations
|
||||
if (NumServos==2)
|
||||
{
|
||||
if ((fabs(CalcAngles[SortAngles[0]])<MaxAngleError)&&
|
||||
(fabs(CalcAngles[SortAngles[1]]-90)<MaxAngleError))
|
||||
{// two servo 90º
|
||||
if (isCCPM)
|
||||
{
|
||||
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("CCPM 2 Servo 90º"));
|
||||
UpdateType();
|
||||
}
|
||||
else
|
||||
{
|
||||
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("FP 2 Servo 90º"));
|
||||
UpdateType();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
if (NumServos==3)
|
||||
{
|
||||
if ((fabs(CalcAngles[SortAngles[0]])<MaxAngleError)&&
|
||||
(fabs(CalcAngles[SortAngles[1]]-120)<MaxAngleError)&&
|
||||
(fabs(CalcAngles[SortAngles[2]]-240)<MaxAngleError))
|
||||
{// three servo 120º
|
||||
if (isCCPM)
|
||||
{
|
||||
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("CCPM 3 Servo 120º"));
|
||||
UpdateType();
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("FP 3 Servo 120º"));
|
||||
UpdateType();
|
||||
}
|
||||
|
||||
}
|
||||
else if ((fabs(CalcAngles[SortAngles[0]])<MaxAngleError)&&
|
||||
(fabs(CalcAngles[SortAngles[1]]-140)<MaxAngleError)&&
|
||||
(fabs(CalcAngles[SortAngles[2]]-220)<MaxAngleError))
|
||||
{// three servo 140º
|
||||
if (isCCPM)
|
||||
{
|
||||
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("CCPM 3 Servo 140º"));
|
||||
UpdateType();
|
||||
}
|
||||
else
|
||||
{
|
||||
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("FP 3 Servo 140º"));
|
||||
UpdateType();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
if (NumServos==4)
|
||||
{
|
||||
|
||||
}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
//get the settings for the curve from the mixer settings
|
||||
field = obj->getField(QString("ThrottleCurve1"));
|
||||
for (i=0;i<5;i++)
|
||||
{
|
||||
m_ccpm->CurveSettings->item(i, 0)->setText(QString().sprintf("%.3f",field->getValue(i).toDouble()));
|
||||
//m_ccpm->CurveSettings->item(i, 0)->setText(field->getValue(i).toString());
|
||||
m_ccpm->CurveSettings->item(i, 0)->setText(QString().sprintf("%.3f",
|
||||
mixerSettingsData.ThrottleCurve1[i]));
|
||||
m_ccpm->CurveSettings->item(i, 1)->setText(QString().sprintf("%.3f",
|
||||
mixerSettingsData.ThrottleCurve2[i]));
|
||||
}
|
||||
field = obj->getField(QString("ThrottleCurve2"));
|
||||
for (i=0;i<5;i++)
|
||||
{
|
||||
m_ccpm->CurveSettings->item(i, 1)->setText(QString().sprintf("%.3f",field->getValue(i).toDouble()));
|
||||
//m_ccpm->CurveSettings->item(i, 1)->setText(field->getValue(i).toString());
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
updatingFromHardware=FALSE;
|
||||
UpdatCCPMUIFromOptions();
|
||||
ccpmSwashplateUpdate();
|
||||
|
||||
}
|
||||
|
||||
|
||||
@ -1499,7 +1338,7 @@ void ConfigccpmWidget::sendccpmUpdate()
|
||||
//clear the output types
|
||||
for (i=0;i<8;i++)
|
||||
{
|
||||
field = obj->getField(tr( "Mixer%1Type" ).arg( i+1 ));
|
||||
field = obj->getField( QString( "Mixer%1Type" ).arg( i+1 ));
|
||||
//clear the mixer type
|
||||
field->setValue("Disabled");
|
||||
}
|
||||
@ -1520,7 +1359,7 @@ void ConfigccpmWidget::sendccpmUpdate()
|
||||
if (MixerChannelData[i]<8)
|
||||
{
|
||||
//select the correct mixer for this config element
|
||||
field = obj->getField(tr( "Mixer%1Type" ).arg( MixerChannelData[i]+1 ));
|
||||
field = obj->getField(QString( "Mixer%1Type" ).arg( MixerChannelData[i]+1 ));
|
||||
//set the mixer type
|
||||
if (i==0)
|
||||
{
|
||||
@ -1532,7 +1371,7 @@ void ConfigccpmWidget::sendccpmUpdate()
|
||||
}
|
||||
|
||||
//select the correct mixer for this config element
|
||||
field = obj->getField(tr( "Mixer%1Vector" ).arg( MixerChannelData[i]+1 ));
|
||||
field = obj->getField(QString( "Mixer%1Vector" ).arg( MixerChannelData[i]+1 ));
|
||||
//config the vector
|
||||
for (j=0;j<5;j++)
|
||||
{
|
||||
|
@ -1,7 +1,6 @@
|
||||
<RCC>
|
||||
<qresource prefix="/configgadget">
|
||||
<file>images/help2.png</file>
|
||||
<file>images/XBee.svg</file>
|
||||
<file>images/Airframe.png</file>
|
||||
<file>images/Servo.png</file>
|
||||
<file>images/ahrs-calib.svg</file>
|
||||
@ -11,10 +10,10 @@
|
||||
<file>images/quad-shapes.svg</file>
|
||||
<file>images/ccpm_setup.svg</file>
|
||||
<file>images/PipXtreme.png</file>
|
||||
<file>images/gyroscope.svg</file>
|
||||
<file>images/Transmitter.png</file>
|
||||
<file>images/help.png</file>
|
||||
<file>images/coptercontrol.svg</file>
|
||||
<file>images/hw_config.svg</file>
|
||||
<file>images/hw_config.png</file>
|
||||
<file>images/gyroscope.png</file>
|
||||
</qresource>
|
||||
</RCC>
|
||||
|
@ -52,11 +52,11 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
{
|
||||
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
|
||||
|
||||
ftw = new FancyTabWidget(this, true);
|
||||
|
||||
ftw = new MyTabbedStackWidget(this, true, true);
|
||||
ftw->setIconSize(64);
|
||||
|
||||
QVBoxLayout *layout = new QVBoxLayout;
|
||||
layout->setContentsMargins(0, 0, 0, 0);
|
||||
layout->addWidget(ftw);
|
||||
setLayout(layout);
|
||||
|
||||
@ -64,7 +64,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
QWidget *qwd;
|
||||
|
||||
qwd = new DefaultHwSettingsWidget(this);
|
||||
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.svg"), QString("HW Settings"));
|
||||
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings"));
|
||||
|
||||
qwd = new ConfigAirframeWidget(this);
|
||||
ftw->insertTab(ConfigGadgetWidget::aircraft, qwd, QIcon(":/configgadget/images/Airframe.png"), QString("Aircraft"));
|
||||
@ -79,7 +79,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS"));
|
||||
|
||||
qwd = new ConfigStabilizationWidget(this);
|
||||
ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, QIcon(":/configgadget/images/gyroscope.svg"), QString("Stabilization"));
|
||||
ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, QIcon(":/configgadget/images/gyroscope.png"), QString("Stabilization"));
|
||||
|
||||
|
||||
|
||||
@ -138,7 +138,7 @@ void ConfigGadgetWidget::onAutopilotConnect() {
|
||||
ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("Attitude"));
|
||||
ftw->removeTab(ConfigGadgetWidget::hardware);
|
||||
qwd = new ConfigCCHWWidget(this);
|
||||
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.svg"), QString("HW Settings"));
|
||||
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings"));
|
||||
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
|
||||
} else if ((board & 0xff00) == 256 ) {
|
||||
// Mainboard family
|
||||
@ -148,7 +148,7 @@ void ConfigGadgetWidget::onAutopilotConnect() {
|
||||
ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS"));
|
||||
ftw->removeTab(ConfigGadgetWidget::hardware);
|
||||
qwd = new ConfigProHWWidget(this);
|
||||
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.svg"), QString("HW Settings"));
|
||||
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings"));
|
||||
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
|
||||
}
|
||||
}
|
||||
|
@ -38,7 +38,8 @@
|
||||
#include <QTextBrowser>
|
||||
#include "utils/pathutils.h"
|
||||
#include <QMessageBox>
|
||||
#include "fancytabwidget.h"
|
||||
//#include "fancytabwidget.h"
|
||||
#include "utils/mytabbedstackwidget.h"
|
||||
#include "configtaskwidget.h"
|
||||
|
||||
class ConfigGadgetWidget: public QWidget
|
||||
@ -62,8 +63,7 @@ signals:
|
||||
|
||||
protected:
|
||||
void resizeEvent(QResizeEvent * event);
|
||||
FancyTabWidget *ftw;
|
||||
|
||||
MyTabbedStackWidget *ftw;
|
||||
};
|
||||
|
||||
#endif // CONFIGGADGETWIDGET_H
|
||||
|
BIN
ground/openpilotgcs/src/plugins/config/images/gyroscope.png
Normal file
BIN
ground/openpilotgcs/src/plugins/config/images/gyroscope.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 7.1 KiB |
BIN
ground/openpilotgcs/src/plugins/config/images/hw_config.png
Normal file
BIN
ground/openpilotgcs/src/plugins/config/images/hw_config.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 15 KiB |
@ -629,6 +629,13 @@ When you change one, the other is updated.</string>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="lowThrottleZeroIntegral">
|
||||
<property name="text">
|
||||
<string>Zero the integral when throttle is low</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
|
@ -32,36 +32,33 @@
|
||||
#include <coreplugin/iconnection.h>
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
|
||||
#include <utils/styledbar.h>
|
||||
|
||||
#include "fancytabwidget.h"
|
||||
#include "fancyactionbar.h"
|
||||
#include "qextserialport/src/qextserialenumerator.h"
|
||||
#include "qextserialport/src/qextserialport.h"
|
||||
#include <QDebug>
|
||||
#include <QLabel>
|
||||
#include <QHBoxLayout>
|
||||
#include <QComboBox>
|
||||
#include <QTimer>
|
||||
|
||||
namespace Core {
|
||||
|
||||
|
||||
ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, Internal::FancyTabWidget *modeStack) :
|
||||
ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, QTabWidget *modeStack) :
|
||||
QWidget(mainWindow), // Pip
|
||||
m_availableDevList(0),
|
||||
m_connectBtn(0),
|
||||
m_ioDev(NULL),m_mainWindow(mainWindow)
|
||||
m_ioDev(NULL),
|
||||
m_mainWindow(mainWindow)
|
||||
{
|
||||
// Q_UNUSED(mainWindow);
|
||||
|
||||
QVBoxLayout *top = new QVBoxLayout;
|
||||
/* QVBoxLayout *top = new QVBoxLayout;
|
||||
top->setSpacing(0);
|
||||
top->setMargin(0);
|
||||
top->setMargin(0);*/
|
||||
|
||||
QHBoxLayout *layout = new QHBoxLayout;
|
||||
layout->setSpacing(0);
|
||||
layout->setContentsMargins(5,0,5,0);
|
||||
layout->addWidget(new QLabel("Connections: "));
|
||||
layout->setSpacing(5);
|
||||
layout->setContentsMargins(5,5,5,5);
|
||||
layout->addWidget(new QLabel(tr("Connections:")));
|
||||
|
||||
m_availableDevList = new QComboBox;
|
||||
//m_availableDevList->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
|
||||
@ -70,17 +67,18 @@ ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, Internal:
|
||||
m_availableDevList->setContextMenuPolicy(Qt::CustomContextMenu);
|
||||
layout->addWidget(m_availableDevList);
|
||||
|
||||
m_connectBtn = new QPushButton("Connect");
|
||||
m_connectBtn = new QPushButton(tr("Connect"));
|
||||
m_connectBtn->setEnabled(false);
|
||||
layout->addWidget(m_connectBtn);
|
||||
|
||||
Utils::StyledBar *bar = new Utils::StyledBar;
|
||||
/* Utils::StyledBar *bar = new Utils::StyledBar;
|
||||
bar->setLayout(layout);
|
||||
|
||||
top->addWidget(bar);
|
||||
setLayout(top);
|
||||
top->addWidget(bar);*/
|
||||
setLayout(layout);
|
||||
|
||||
modeStack->insertCornerWidget(modeStack->cornerWidgetCount()-1, this);
|
||||
// modeStack->insertCornerWidget(modeStack->cornerWidgetCount()-1, this);
|
||||
modeStack->setCornerWidget(this, Qt::TopRightCorner);
|
||||
|
||||
QObject::connect(m_connectBtn, SIGNAL(pressed()), this, SLOT(onConnectPressed()));
|
||||
}
|
||||
|
@ -40,6 +40,10 @@
|
||||
|
||||
#include "core_global.h"
|
||||
|
||||
QT_BEGIN_NAMESPACE
|
||||
class QTabWidget;
|
||||
QT_END_NAMESPACE
|
||||
|
||||
namespace Core {
|
||||
|
||||
class IConnection;
|
||||
@ -65,7 +69,7 @@ class CORE_EXPORT ConnectionManager : public QWidget
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
ConnectionManager(Internal::MainWindow *mainWindow, Internal::FancyTabWidget *modeStack);
|
||||
ConnectionManager(Internal::MainWindow *mainWindow, QTabWidget *modeStack);
|
||||
virtual ~ConnectionManager();
|
||||
|
||||
void init();
|
||||
|
@ -187,9 +187,9 @@ void CoreImpl::openFiles(const QStringList &arguments)
|
||||
//m_mainwindow->openFiles(arguments);
|
||||
}
|
||||
|
||||
void CoreImpl::readMainSettings(QSettings* qs)
|
||||
void CoreImpl::readMainSettings(QSettings* qs, bool workspaceDiffOnly)
|
||||
{
|
||||
m_mainwindow->readSettings(qs);
|
||||
m_mainwindow->readSettings(qs, workspaceDiffOnly);
|
||||
}
|
||||
|
||||
void CoreImpl::saveMainSettings(QSettings* qs)
|
||||
|
@ -64,7 +64,7 @@ public:
|
||||
|
||||
QSettings *settings(QSettings::Scope scope = QSettings::UserScope) const;
|
||||
SettingsDatabase *settingsDatabase() const;
|
||||
void readMainSettings(QSettings* qs);
|
||||
void readMainSettings(QSettings* qs, bool workspaceDiffOnly);
|
||||
void saveMainSettings(QSettings* qs);
|
||||
void readSettings(IConfigurablePlugin* plugin, QSettings* qs = 0 );
|
||||
void saveSettings(IConfigurablePlugin* plugin, QSettings* qs = 0 );
|
||||
|
@ -1,2 +1,2 @@
|
||||
include(coreplugin_dependencies.pri)
|
||||
LIBS *= -l$$qtLibraryTarget(Core)
|
||||
LIBS *= -l$$qtLibraryName(Core)
|
||||
|
@ -24,10 +24,8 @@ SOURCES += mainwindow.cpp \
|
||||
uniqueidmanager.cpp \
|
||||
messagemanager.cpp \
|
||||
messageoutputwindow.cpp \
|
||||
viewmanager.cpp \
|
||||
versiondialog.cpp \
|
||||
iuavgadget.cpp \
|
||||
uavgadgetmode.cpp \
|
||||
uavgadgetmanager/uavgadgetmanager.cpp \
|
||||
uavgadgetmanager/uavgadgetview.cpp \
|
||||
uavgadgetmanager/splitterorview.cpp \
|
||||
@ -73,9 +71,7 @@ HEADERS += mainwindow.h \
|
||||
uniqueidmanager.h \
|
||||
messagemanager.h \
|
||||
messageoutputwindow.h \
|
||||
viewmanager.h \
|
||||
iuavgadget.h \
|
||||
uavgadgetmode.h \
|
||||
iuavgadgetfactory.h \
|
||||
uavgadgetmanager/uavgadgetmanager.h \
|
||||
uavgadgetmanager/uavgadgetview.h \
|
||||
|
@ -44,9 +44,10 @@ using namespace Utils;
|
||||
using namespace Core::Internal;
|
||||
|
||||
GeneralSettings::GeneralSettings():
|
||||
m_dialog(0),
|
||||
m_saveSettingsOnExit(true),
|
||||
m_autoConnect(true),m_autoSelect(true)
|
||||
m_dialog(0),
|
||||
m_autoConnect(true),
|
||||
m_autoSelect(true)
|
||||
{
|
||||
}
|
||||
|
||||
@ -119,24 +120,9 @@ QWidget *GeneralSettings::createPage(QWidget *parent)
|
||||
m_page->checkAutoConnect->setChecked(m_autoConnect);
|
||||
m_page->checkAutoSelect->setChecked(m_autoSelect);
|
||||
m_page->colorButton->setColor(StyleHelper::baseColor());
|
||||
#ifdef Q_OS_UNIX
|
||||
m_page->terminalEdit->setText(ConsoleProcess::terminalEmulator(Core::ICore::instance()->settings()));
|
||||
#else
|
||||
m_page->terminalLabel->hide();
|
||||
m_page->terminalEdit->hide();
|
||||
m_page->resetTerminalButton->hide();
|
||||
#endif
|
||||
|
||||
connect(m_page->resetButton, SIGNAL(clicked()),
|
||||
this, SLOT(resetInterfaceColor()));
|
||||
connect(m_page->resetEditorButton, SIGNAL(clicked()),
|
||||
this, SLOT(resetExternalEditor()));
|
||||
connect(m_page->helpExternalEditorButton, SIGNAL(clicked()),
|
||||
this, SLOT(showHelpForExternalEditor()));
|
||||
#ifdef Q_OS_UNIX
|
||||
connect(m_page->resetTerminalButton, SIGNAL(clicked()),
|
||||
this, SLOT(resetTerminal()));
|
||||
#endif
|
||||
|
||||
return w;
|
||||
}
|
||||
@ -151,11 +137,6 @@ void GeneralSettings::apply()
|
||||
m_saveSettingsOnExit = m_page->checkBoxSaveOnExit->isChecked();
|
||||
m_autoConnect = m_page->checkAutoConnect->isChecked();
|
||||
m_autoSelect = m_page->checkAutoSelect->isChecked();
|
||||
#ifdef Q_OS_UNIX
|
||||
ConsoleProcess::setTerminalEmulator(Core::ICore::instance()->settings(),
|
||||
m_page->terminalEdit->text());
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void GeneralSettings::finish()
|
||||
@ -171,7 +152,6 @@ void GeneralSettings::readSettings(QSettings* qs)
|
||||
m_autoConnect = qs->value(QLatin1String("AutoConnect"),m_autoConnect).toBool();
|
||||
m_autoSelect = qs->value(QLatin1String("AutoSelect"),m_autoSelect).toBool();
|
||||
qs->endGroup();
|
||||
|
||||
}
|
||||
|
||||
void GeneralSettings::saveSettings(QSettings* qs)
|
||||
@ -194,17 +174,6 @@ void GeneralSettings::resetInterfaceColor()
|
||||
m_page->colorButton->setColor(0x666666);
|
||||
}
|
||||
|
||||
void GeneralSettings::resetExternalEditor()
|
||||
{
|
||||
}
|
||||
|
||||
#ifdef Q_OS_UNIX
|
||||
void GeneralSettings::resetTerminal()
|
||||
{
|
||||
m_page->terminalEdit->setText(ConsoleProcess::defaultTerminalEmulator() + QLatin1String(" -e"));
|
||||
}
|
||||
#endif
|
||||
|
||||
void GeneralSettings::showHelpForExternalEditor()
|
||||
{
|
||||
if (m_dialog) {
|
||||
@ -238,10 +207,11 @@ QString GeneralSettings::language() const
|
||||
|
||||
void GeneralSettings::setLanguage(const QString &locale)
|
||||
{
|
||||
if (m_language != locale)
|
||||
{
|
||||
if (m_language != locale) {
|
||||
if (!locale.isEmpty()) {
|
||||
QMessageBox::information((QWidget*)Core::ICore::instance()->mainWindow(), tr("Restart required"),
|
||||
tr("The language change will take effect after a restart of the OpenPilot GCS."));
|
||||
}
|
||||
m_language = locale;
|
||||
}
|
||||
}
|
||||
|
@ -61,15 +61,13 @@ public:
|
||||
void readSettings(QSettings* qs);
|
||||
void saveSettings(QSettings* qs);
|
||||
|
||||
signals:
|
||||
|
||||
private slots:
|
||||
void resetInterfaceColor();
|
||||
void resetLanguage();
|
||||
void resetExternalEditor();
|
||||
void showHelpForExternalEditor();
|
||||
void slotAutoConnect(int);
|
||||
#ifdef Q_OS_UNIX
|
||||
void resetTerminal();
|
||||
#endif
|
||||
|
||||
private:
|
||||
void fillLanguageBox() const;
|
||||
|
@ -17,33 +17,6 @@
|
||||
<string>General settings</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="terminalLabel">
|
||||
<property name="text">
|
||||
<string>Terminal:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="0">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>External editor:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string>When files are externally modified:</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QLineEdit" name="terminalEdit"/>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="colorLabel">
|
||||
<property name="text">
|
||||
@ -51,44 +24,6 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QToolButton" name="resetTerminalButton">
|
||||
<property name="toolTip">
|
||||
<string>Reset to default</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>R</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="core.qrc">
|
||||
<normaloff>:/core/images/reset.png</normaloff>:/core/images/reset.png</iconset>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="1">
|
||||
<widget class="QLineEdit" name="externalEditorEdit"/>
|
||||
</item>
|
||||
<item row="8" column="2">
|
||||
<widget class="QToolButton" name="resetEditorButton">
|
||||
<property name="toolTip">
|
||||
<string>Reset to default</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>R</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="core.qrc">
|
||||
<normaloff>:/core/images/reset.png</normaloff>:/core/images/reset.png</iconset>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="3">
|
||||
<widget class="QToolButton" name="helpExternalEditorButton">
|
||||
<property name="text">
|
||||
<string>?</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QWidget" name="widget" native="true">
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
@ -144,53 +79,12 @@
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="1">
|
||||
<item row="8" column="1">
|
||||
<widget class="QWidget" name="widget_2" native="true">
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<property name="margin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="QComboBox" name="reloadBehavior">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="currentIndex">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Always ask</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Reload all modified files</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Ignore modifications</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>132</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
@ -221,7 +115,7 @@
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="11" column="1">
|
||||
<item row="9" column="1">
|
||||
<widget class="QCheckBox" name="checkBoxSaveOnExit">
|
||||
<property name="text">
|
||||
<string/>
|
||||
@ -231,27 +125,27 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="11" column="0">
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="text">
|
||||
<string>Save configuration settings on on exit</string>
|
||||
<string>Save configuration settings on exit:</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="12" column="0">
|
||||
<item row="10" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>Automatically connect an OpenPilot USB device</string>
|
||||
<string>Automatically connect an OpenPilot USB device:</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="12" column="1">
|
||||
<item row="10" column="1">
|
||||
<widget class="QCheckBox" name="checkAutoConnect">
|
||||
<property name="text">
|
||||
<string/>
|
||||
@ -261,17 +155,17 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="13" column="0">
|
||||
<item row="11" column="0">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="text">
|
||||
<string>Automatically select an OpenPilot USB device</string>
|
||||
<string>Automatically select an OpenPilot USB device:</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="13" column="1">
|
||||
<item row="11" column="1">
|
||||
<widget class="QCheckBox" name="checkAutoSelect">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
|
@ -88,7 +88,7 @@ public:
|
||||
|
||||
virtual QSettings *settings(QSettings::Scope scope = QSettings::UserScope) const = 0;
|
||||
virtual SettingsDatabase *settingsDatabase() const = 0;
|
||||
virtual void readMainSettings(QSettings* qs) = 0;
|
||||
virtual void readMainSettings(QSettings* qs, bool workspaceDiffOnly = false) = 0;
|
||||
virtual void saveMainSettings(QSettings* qs) = 0;
|
||||
virtual void readSettings(IConfigurablePlugin* plugin, QSettings* qs = 0) = 0;
|
||||
virtual void saveSettings(IConfigurablePlugin* plugin, QSettings* qs = 0) = 0;
|
||||
|
@ -49,6 +49,7 @@ public:
|
||||
virtual QString name() const = 0;
|
||||
virtual QIcon icon() const = 0;
|
||||
virtual int priority() const = 0;
|
||||
virtual void setPriority(int priority) = 0;
|
||||
virtual const char *uniqueModeName() const = 0;
|
||||
};
|
||||
|
||||
|
@ -33,7 +33,7 @@
|
||||
#include "connectionmanager.h"
|
||||
#include "coreimpl.h"
|
||||
#include "coreconstants.h"
|
||||
#include "fancytabwidget.h"
|
||||
#include "utils/mytabwidget.h"
|
||||
#include "generalsettings.h"
|
||||
#include "messagemanager.h"
|
||||
#include "modemanager.h"
|
||||
@ -43,7 +43,6 @@
|
||||
#include "qxtlogger.h"
|
||||
#include "qxtbasicstdloggerengine.h"
|
||||
#include "shortcutsettings.h"
|
||||
#include "uavgadgetmode.h"
|
||||
#include "uavgadgetmanager.h"
|
||||
#include "uavgadgetinstancemanager.h"
|
||||
#include "workspacesettings.h"
|
||||
@ -60,7 +59,6 @@
|
||||
#include "uniqueidmanager.h"
|
||||
#include "variablemanager.h"
|
||||
#include "versiondialog.h"
|
||||
#include "viewmanager.h"
|
||||
|
||||
#include <coreplugin/settingsdatabase.h>
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
@ -123,7 +121,6 @@ MainWindow::MainWindow() :
|
||||
m_actionManager(new ActionManagerPrivate(this)),
|
||||
m_variableManager(new VariableManager(this)),
|
||||
m_threadManager(new ThreadManager(this)),
|
||||
m_viewManager(0),
|
||||
m_modeManager(0),
|
||||
m_connectionManager(0),
|
||||
m_mimeDatabase(new MimeDatabase),
|
||||
@ -178,17 +175,25 @@ MainWindow::MainWindow() :
|
||||
registerDefaultContainers();
|
||||
registerDefaultActions();
|
||||
|
||||
m_modeStack = new FancyTabWidget(this);
|
||||
m_modeStack = new MyTabWidget(this);
|
||||
m_modeStack->setIconSize(QSize(24,24));
|
||||
m_modeStack->setTabPosition(QTabWidget::South);
|
||||
m_modeStack->setMovable(false);
|
||||
#ifndef Q_WS_MAC
|
||||
m_modeStack->setDocumentMode(true);
|
||||
#endif
|
||||
m_modeManager = new ModeManager(this, m_modeStack);
|
||||
|
||||
m_connectionManager = new ConnectionManager(this, m_modeStack);
|
||||
|
||||
m_viewManager = new ViewManager(this);
|
||||
m_messageManager = new MessageManager;
|
||||
setCentralWidget(m_modeStack);
|
||||
|
||||
connect(QApplication::instance(), SIGNAL(focusChanged(QWidget*,QWidget*)),
|
||||
this, SLOT(updateFocusWidget(QWidget*,QWidget*)));
|
||||
connect(m_workspaceSettings, SIGNAL(tabBarSettingsApplied(QTabWidget::TabPosition,bool)),
|
||||
this, SLOT(applyTabBarSettings(QTabWidget::TabPosition,bool)));
|
||||
connect(m_modeManager, SIGNAL(newModeOrder(QVector<IMode*>)), m_workspaceSettings, SLOT(newModeOrder(QVector<IMode*>)));
|
||||
|
||||
// setUnifiedTitleAndToolBarOnMac(true);
|
||||
#ifdef Q_OS_UNIX
|
||||
@ -218,8 +223,8 @@ MainWindow::~MainWindow()
|
||||
foreach (QString engine, qxtLog->allLoggerEngines())
|
||||
qxtLog->removeLoggerEngine(engine);
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
if (m_uavGadgetModes.count() > 0) {
|
||||
foreach (UAVGadgetMode *mode, m_uavGadgetModes)
|
||||
if (m_uavGadgetManagers.count() > 0) {
|
||||
foreach (UAVGadgetManager *mode, m_uavGadgetManagers)
|
||||
{
|
||||
pm->removeObject(mode);
|
||||
delete mode;
|
||||
@ -242,9 +247,6 @@ MainWindow::~MainWindow()
|
||||
delete m_uniqueIDManager;
|
||||
m_uniqueIDManager = 0;
|
||||
|
||||
delete m_viewManager;
|
||||
m_viewManager = 0;
|
||||
|
||||
pm->removeObject(m_coreImpl);
|
||||
delete m_coreImpl;
|
||||
m_coreImpl = 0;
|
||||
@ -264,7 +266,6 @@ bool MainWindow::init(QString *errorMessage)
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
pm->addObject(m_coreImpl);
|
||||
m_viewManager->init();
|
||||
m_modeManager->init();
|
||||
m_connectionManager->init();
|
||||
|
||||
@ -393,7 +394,7 @@ IContext *MainWindow::currentContextObject() const
|
||||
|
||||
QStatusBar *MainWindow::statusBar() const
|
||||
{
|
||||
return m_modeStack->statusBar();
|
||||
return new QStatusBar();// m_modeStack->statusBar();
|
||||
}
|
||||
|
||||
void MainWindow::registerDefaultContainers()
|
||||
@ -669,6 +670,60 @@ void MainWindow::registerDefaultActions()
|
||||
connect(m_toggleFullScreenAction, SIGNAL(triggered(bool)), this, SLOT(setFullScreen(bool)));
|
||||
#endif
|
||||
|
||||
/*
|
||||
* UavGadgetManager Actions
|
||||
*/
|
||||
const QList<int> uavGadgetManagerContext =
|
||||
QList<int>() << CoreImpl::instance()->uniqueIDManager()->uniqueIdentifier(Constants::C_UAVGADGETMANAGER);
|
||||
//Window menu separators
|
||||
QAction *tmpaction1 = new QAction(this);
|
||||
tmpaction1->setSeparator(true);
|
||||
cmd = am->registerAction(tmpaction1, QLatin1String("OpenPilot.Window.Sep.Split"), uavGadgetManagerContext);
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_HIDE_TOOLBAR);
|
||||
|
||||
m_showToolbarsAction = new QAction(tr("Edit Gadgets Mode"), this);
|
||||
m_showToolbarsAction->setCheckable(true);
|
||||
cmd = am->registerAction(m_showToolbarsAction, Constants::HIDE_TOOLBARS, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("Ctrl+Shift+F10")));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_HIDE_TOOLBAR);
|
||||
|
||||
//Window menu separators
|
||||
QAction *tmpaction2 = new QAction(this);
|
||||
tmpaction2->setSeparator(true);
|
||||
cmd = am->registerAction(tmpaction2, QLatin1String("OpenPilot.Window.Sep.Split2"), uavGadgetManagerContext);
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
|
||||
#ifdef Q_WS_MAC
|
||||
QString prefix = tr("Meta+Shift");
|
||||
#else
|
||||
QString prefix = tr("Ctrl+Shift");
|
||||
#endif
|
||||
|
||||
m_splitAction = new QAction(tr("Split"), this);
|
||||
cmd = am->registerAction(m_splitAction, Constants::SPLIT, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("%1+Down").arg(prefix)));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
|
||||
m_splitSideBySideAction = new QAction(tr("Split Side by Side"), this);
|
||||
cmd = am->registerAction(m_splitSideBySideAction, Constants::SPLIT_SIDE_BY_SIDE, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("%1+Right").arg(prefix)));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
|
||||
m_removeCurrentSplitAction = new QAction(tr("Close Current View"), this);
|
||||
cmd = am->registerAction(m_removeCurrentSplitAction, Constants::REMOVE_CURRENT_SPLIT, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("%1+C").arg(prefix)));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
|
||||
m_removeAllSplitsAction = new QAction(tr("Close All Other Views"), this);
|
||||
cmd = am->registerAction(m_removeAllSplitsAction, Constants::REMOVE_ALL_SPLITS, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("%1+A").arg(prefix)));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
|
||||
m_gotoOtherSplitAction = new QAction(tr("Goto Next View"), this);
|
||||
cmd = am->registerAction(m_gotoOtherSplitAction, Constants::GOTO_OTHER_SPLIT, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("%1+N").arg(prefix)));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
|
||||
//Help Action
|
||||
tmpaction = new QAction(QIcon(Constants::ICON_HELP), tr("&Help..."), this);
|
||||
cmd = am->registerAction(tmpaction, Constants::G_HELP_HELP, m_globalContext);
|
||||
@ -807,6 +862,12 @@ void MainWindow::openFileWith()
|
||||
|
||||
}
|
||||
|
||||
void MainWindow::applyTabBarSettings(QTabWidget::TabPosition pos, bool movable) {
|
||||
if (m_modeStack->tabPosition() != pos)
|
||||
m_modeStack->setTabPosition(pos);
|
||||
m_modeStack->setMovable(movable);
|
||||
}
|
||||
|
||||
ActionManager *MainWindow::actionManager() const
|
||||
{
|
||||
return m_actionManager;
|
||||
@ -845,12 +906,6 @@ ConnectionManager *MainWindow::connectionManager() const
|
||||
return m_connectionManager;
|
||||
}
|
||||
|
||||
void MainWindow::addUAVGadgetManager(UAVGadgetManager *manager)
|
||||
{
|
||||
if (!m_uavGadgetManagers.contains(manager))
|
||||
m_uavGadgetManagers.append(manager);
|
||||
}
|
||||
|
||||
QList<UAVGadgetManager*> MainWindow::uavGadgetManagers() const
|
||||
{
|
||||
return m_uavGadgetManagers;
|
||||
@ -986,40 +1041,83 @@ void MainWindow::shutdown()
|
||||
uavGadgetInstanceManager()->removeAllGadgets();
|
||||
}
|
||||
|
||||
void MainWindow::createWorkspaces() {
|
||||
/* Enable/disable menus for uavgadgets */
|
||||
void MainWindow::showUavGadgetMenus(bool show, bool hasSplitter)
|
||||
{
|
||||
m_showToolbarsAction->setChecked(show);
|
||||
m_splitAction->setEnabled(show);
|
||||
m_splitSideBySideAction->setEnabled(show);
|
||||
m_removeCurrentSplitAction->setEnabled(show && hasSplitter);
|
||||
m_removeAllSplitsAction->setEnabled(show && hasSplitter);
|
||||
m_gotoOtherSplitAction->setEnabled(show && hasSplitter);
|
||||
}
|
||||
|
||||
inline int takeLeastPriorityUavGadgetManager(const QList<Core::UAVGadgetManager*> m_uavGadgetManagers) {
|
||||
int index = 0;
|
||||
int prio = m_uavGadgetManagers.at(0)->priority();
|
||||
for (int i = 0; i < m_uavGadgetManagers.count(); i++) {
|
||||
int prio2 = m_uavGadgetManagers.at(i)->priority();
|
||||
if (prio2 < prio) {
|
||||
prio = prio2;
|
||||
index = i;
|
||||
}
|
||||
}
|
||||
return index;
|
||||
}
|
||||
|
||||
void MainWindow::createWorkspaces(QSettings* qs, bool diffOnly) {
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
|
||||
UAVGadgetMode *uavGadgetMode;
|
||||
Core::UAVGadgetManager *uavGadgetManager;
|
||||
|
||||
while (!m_uavGadgetModes.isEmpty()){
|
||||
pm->removeObject(m_uavGadgetModes.takeFirst());
|
||||
}
|
||||
while (!m_uavGadgetManagers.isEmpty()){
|
||||
Core::UAVGadgetManager* uavGadgetManager = m_uavGadgetManagers.takeLast();
|
||||
uavGadgetManager->removeAllSplits();
|
||||
// TODO Fixthis: This only happens, when settings are reloaded.
|
||||
// then the old GadgetManagers should be deleted, but if
|
||||
// I delete them the GCS segfaults.
|
||||
//delete uavGadgetManager;
|
||||
}
|
||||
m_uavGadgetManagers.clear();
|
||||
m_uavGadgetModes.clear();
|
||||
for (int i = 0; i < m_workspaceSettings->numberOfWorkspaces(); ++i) {
|
||||
// If diffOnly is true, we only add/remove the number of workspaces
|
||||
// that has changed,
|
||||
// otherwise a complete reload of workspaces is done
|
||||
int toRemoveFirst = m_uavGadgetManagers.count();
|
||||
int newWorkspacesNo = m_workspaceSettings->numberOfWorkspaces();
|
||||
if (diffOnly && m_uavGadgetManagers.count() > newWorkspacesNo)
|
||||
toRemoveFirst = m_uavGadgetManagers.count() - newWorkspacesNo;
|
||||
else
|
||||
toRemoveFirst = 0;
|
||||
|
||||
int removed = 0;
|
||||
|
||||
while (!m_uavGadgetManagers.isEmpty() && (toRemoveFirst > removed)) {
|
||||
int index = takeLeastPriorityUavGadgetManager(m_uavGadgetManagers);
|
||||
uavGadgetManager = m_uavGadgetManagers.takeAt(index);
|
||||
uavGadgetManager->removeAllSplits();
|
||||
pm->removeObject(uavGadgetManager);
|
||||
delete uavGadgetManager;
|
||||
removed++;
|
||||
}
|
||||
|
||||
int start = 0;
|
||||
if (diffOnly) {
|
||||
start = m_uavGadgetManagers.count();
|
||||
} else {
|
||||
m_uavGadgetManagers.clear();
|
||||
}
|
||||
for (int i = start; i < newWorkspacesNo; ++i) {
|
||||
|
||||
uavGadgetManager = new Core::UAVGadgetManager(CoreImpl::instance(), this);
|
||||
uavGadgetManager->hide();
|
||||
const QString name = m_workspaceSettings->name(i);
|
||||
const QString iconName = m_workspaceSettings->iconName(i);
|
||||
const QString modeName = m_workspaceSettings->modeName(i);
|
||||
uavGadgetManager = new Core::UAVGadgetManager(CoreImpl::instance(), name,
|
||||
QIcon(iconName), 90-i+1, modeName, this);
|
||||
|
||||
uavGadgetMode = new UAVGadgetMode(uavGadgetManager, name,
|
||||
QIcon(iconName), 90-i+1, modeName);
|
||||
uavGadgetManager->setUAVGadgetMode(uavGadgetMode);
|
||||
m_uavGadgetModes.append(uavGadgetMode);
|
||||
pm->addObject(uavGadgetMode);
|
||||
addUAVGadgetManager(uavGadgetManager);
|
||||
connect(uavGadgetManager, SIGNAL(showUavGadgetMenus(bool, bool)), this, SLOT(showUavGadgetMenus(bool, bool)));
|
||||
|
||||
connect(m_showToolbarsAction, SIGNAL(triggered(bool)), uavGadgetManager, SLOT(showToolbars(bool)));
|
||||
connect(m_splitAction, SIGNAL(triggered()), uavGadgetManager, SLOT(split()));
|
||||
connect(m_splitSideBySideAction, SIGNAL(triggered()), uavGadgetManager, SLOT(splitSideBySide()));
|
||||
connect(m_removeCurrentSplitAction, SIGNAL(triggered()), uavGadgetManager, SLOT(removeCurrentSplit()));
|
||||
connect(m_removeAllSplitsAction, SIGNAL(triggered()), uavGadgetManager, SLOT(removeAllSplits()));
|
||||
connect(m_gotoOtherSplitAction, SIGNAL(triggered()), uavGadgetManager, SLOT(gotoOtherSplit()));
|
||||
|
||||
pm->addObject(uavGadgetManager);
|
||||
m_uavGadgetManagers.append(uavGadgetManager);
|
||||
uavGadgetManager->readSettings(qs);
|
||||
}
|
||||
}
|
||||
|
||||
@ -1028,13 +1126,19 @@ static const char *geometryKey = "Geometry";
|
||||
static const char *colorKey = "Color";
|
||||
static const char *maxKey = "Maximized";
|
||||
static const char *fullScreenKey = "FullScreen";
|
||||
static const char *modePriorities = "ModePriorities";
|
||||
|
||||
void MainWindow::readSettings(QSettings* qs)
|
||||
void MainWindow::readSettings(QSettings* qs, bool workspaceDiffOnly)
|
||||
{
|
||||
if ( !qs ){
|
||||
qs = m_settings;
|
||||
}
|
||||
|
||||
if (workspaceDiffOnly) {
|
||||
createWorkspaces(qs, workspaceDiffOnly);
|
||||
return;
|
||||
}
|
||||
|
||||
m_generalSettings->readSettings(qs);
|
||||
m_actionManager->readSettings(qs);
|
||||
|
||||
@ -1056,13 +1160,18 @@ void MainWindow::readSettings(QSettings* qs)
|
||||
|
||||
m_workspaceSettings->readSettings(qs);
|
||||
|
||||
createWorkspaces();
|
||||
createWorkspaces(qs);
|
||||
|
||||
foreach (UAVGadgetManager *manager, m_uavGadgetManagers) {
|
||||
manager->readSettings(qs);
|
||||
// Read tab ordering
|
||||
qs->beginGroup(QLatin1String(modePriorities));
|
||||
QStringList modeNames = qs->childKeys();
|
||||
QMap<QString, int> map;
|
||||
foreach (QString modeName, modeNames) {
|
||||
map.insert(modeName, qs->value(modeName).toInt());
|
||||
}
|
||||
m_modeManager->reorderModes(map);
|
||||
|
||||
m_viewManager->readSettings(qs);
|
||||
qs->endGroup();
|
||||
|
||||
}
|
||||
|
||||
@ -1092,11 +1201,18 @@ void MainWindow::saveSettings(QSettings* qs)
|
||||
|
||||
qs->endGroup();
|
||||
|
||||
// Write tab ordering
|
||||
qs->beginGroup(QLatin1String(modePriorities));
|
||||
QVector<IMode*> modes = m_modeManager->modes();
|
||||
foreach (IMode *mode, modes) {
|
||||
qs->setValue(QLatin1String(mode->uniqueModeName()), mode->priority());
|
||||
}
|
||||
qs->endGroup();
|
||||
|
||||
foreach (UAVGadgetManager *manager, m_uavGadgetManagers) {
|
||||
manager->saveSettings(qs);
|
||||
}
|
||||
|
||||
m_viewManager->saveSettings(qs);
|
||||
m_actionManager->saveSettings(qs);
|
||||
m_generalSettings->saveSettings(qs);
|
||||
|
||||
|
@ -40,6 +40,7 @@ QT_BEGIN_NAMESPACE
|
||||
class QSettings;
|
||||
class QShortcut;
|
||||
class QToolButton;
|
||||
class MyTabWidget;
|
||||
QT_END_NAMESPACE
|
||||
|
||||
namespace Core {
|
||||
@ -73,10 +74,8 @@ class FancyTabWidget;
|
||||
class GeneralSettings;
|
||||
class ShortcutSettings;
|
||||
class WorkspaceSettings;
|
||||
class ViewManager;
|
||||
class VersionDialog;
|
||||
class AuthorsDialog;
|
||||
class UAVGadgetMode;
|
||||
|
||||
class CORE_EXPORT MainWindow : public EventFilteringMainWindow
|
||||
{
|
||||
@ -94,7 +93,7 @@ public:
|
||||
void addContextObject(IContext *contex);
|
||||
void removeContextObject(IContext *contex);
|
||||
void resetContext();
|
||||
void readSettings(QSettings* qs = 0);
|
||||
void readSettings(QSettings* qs = 0, bool workspaceDiffOnly = false);
|
||||
void saveSettings(QSettings* qs = 0);
|
||||
void readSettings(IConfigurablePlugin* plugin, QSettings* qs = 0);
|
||||
void saveSettings(IConfigurablePlugin* plugin, QSettings* qs = 0);
|
||||
@ -162,14 +161,14 @@ private slots:
|
||||
void destroyVersionDialog();
|
||||
void destroyAuthorsDialog();
|
||||
void modeChanged(Core::IMode *mode);
|
||||
void showUavGadgetMenus(bool show, bool hasSplitter);
|
||||
void applyTabBarSettings(QTabWidget::TabPosition pos, bool movable);
|
||||
|
||||
private:
|
||||
void addUAVGadgetManager(Core::UAVGadgetManager *manager);
|
||||
void updateContextObject(IContext *context);
|
||||
void registerDefaultContainers();
|
||||
void registerDefaultActions();
|
||||
|
||||
void createWorkspaces();
|
||||
void createWorkspaces(QSettings* qs, bool diffOnly = false);
|
||||
|
||||
CoreImpl *m_coreImpl;
|
||||
UniqueIDManager *m_uniqueIDManager;
|
||||
@ -183,15 +182,12 @@ private:
|
||||
MessageManager *m_messageManager;
|
||||
VariableManager *m_variableManager;
|
||||
ThreadManager *m_threadManager;
|
||||
ViewManager *m_viewManager;
|
||||
ModeManager *m_modeManager;
|
||||
QList<UAVGadgetManager*> m_uavGadgetManagers;
|
||||
QList<UAVGadgetMode*> m_uavGadgetModes;
|
||||
UAVGadgetInstanceManager *m_uavGadgetInstanceManager;
|
||||
ConnectionManager *m_connectionManager;
|
||||
MimeDatabase *m_mimeDatabase;
|
||||
FancyTabWidget *m_modeStack;
|
||||
// RightPaneWidget *m_rightPaneWidget;
|
||||
MyTabWidget *m_modeStack;
|
||||
Core::BaseView *m_outputView;
|
||||
VersionDialog *m_versionDialog;
|
||||
AuthorsDialog *m_authorsDialog;
|
||||
@ -213,6 +209,14 @@ private:
|
||||
QAction *m_exitAction;
|
||||
QAction *m_optionsAction;
|
||||
QAction *m_toggleFullScreenAction;
|
||||
// UavGadgetManager actions
|
||||
QAction *m_showToolbarsAction;
|
||||
QAction *m_splitAction;
|
||||
QAction *m_splitSideBySideAction;
|
||||
QAction *m_removeCurrentSplitAction;
|
||||
QAction *m_removeAllSplitsAction;
|
||||
QAction *m_gotoOtherSplitAction;
|
||||
|
||||
#ifdef Q_WS_MAC
|
||||
QAction *m_minimizeAction;
|
||||
QAction *m_zoomAction;
|
||||
|
@ -30,6 +30,7 @@
|
||||
|
||||
#include "fancytabwidget.h"
|
||||
#include "fancyactionbar.h"
|
||||
#include "utils/mytabwidget.h"
|
||||
#include "icore.h"
|
||||
#include "mainwindow.h"
|
||||
|
||||
@ -59,18 +60,17 @@ using namespace Core::Internal;
|
||||
|
||||
ModeManager *ModeManager::m_instance = 0;
|
||||
|
||||
ModeManager::ModeManager(Internal::MainWindow *mainWindow, FancyTabWidget *modeStack) :
|
||||
ModeManager::ModeManager(Internal::MainWindow *mainWindow, MyTabWidget *modeStack) :
|
||||
m_mainWindow(mainWindow),
|
||||
m_modeStack(modeStack),
|
||||
m_signalMapper(new QSignalMapper(this))
|
||||
m_signalMapper(new QSignalMapper(this)),
|
||||
m_isReprioritizing(false)
|
||||
{
|
||||
m_instance = this;
|
||||
|
||||
m_actionBar = new FancyActionBar(modeStack);
|
||||
// m_modeStack->addCornerWidget(m_actionBar);
|
||||
|
||||
connect(m_modeStack, SIGNAL(currentAboutToShow(int)), SLOT(currentTabAboutToChange(int)));
|
||||
connect(m_modeStack, SIGNAL(currentChanged(int)), SLOT(currentTabChanged(int)));
|
||||
// connect((m_modeStack), SIGNAL(currentAboutToShow(int)), SLOT(currentTabAboutToChange(int)));
|
||||
connect(m_modeStack, SIGNAL(currentChanged(int)), this, SLOT(currentTabChanged(int)));
|
||||
connect(m_modeStack, SIGNAL(tabMoved(int,int)), this, SLOT(tabMoved(int,int)));
|
||||
connect(m_signalMapper, SIGNAL(mapped(QString)), this, SLOT(activateMode(QString)));
|
||||
}
|
||||
|
||||
@ -87,7 +87,7 @@ void ModeManager::addWidget(QWidget *widget)
|
||||
// We want the actionbar to stay on the bottom
|
||||
// so m_modeStack->cornerWidgetCount() -1 inserts it at the position immediately above
|
||||
// the actionbar
|
||||
m_modeStack->insertCornerWidget(m_modeStack->cornerWidgetCount() -1, widget);
|
||||
// m_modeStack->insertCornerWidget(m_modeStack->cornerWidgetCount() -1, widget);
|
||||
}
|
||||
|
||||
IMode *ModeManager::currentMode() const
|
||||
@ -150,6 +150,14 @@ void ModeManager::objectAdded(QObject *obj)
|
||||
|
||||
m_modeShortcuts.insert(index, cmd);
|
||||
connect(cmd, SIGNAL(keySequenceChanged()), this, SLOT(updateModeToolTip()));
|
||||
|
||||
setDefaultKeyshortcuts();
|
||||
|
||||
m_signalMapper->setMapping(shortcut, mode->uniqueModeName());
|
||||
connect(shortcut, SIGNAL(activated()), m_signalMapper, SLOT(map()));
|
||||
}
|
||||
|
||||
void ModeManager::setDefaultKeyshortcuts() {
|
||||
for (int i = 0; i < m_modeShortcuts.size(); ++i) {
|
||||
Command *currentCmd = m_modeShortcuts.at(i);
|
||||
bool currentlyHasDefaultSequence = (currentCmd->keySequence()
|
||||
@ -162,9 +170,6 @@ void ModeManager::objectAdded(QObject *obj)
|
||||
if (currentlyHasDefaultSequence)
|
||||
currentCmd->setKeySequence(currentCmd->defaultKeySequence());
|
||||
}
|
||||
|
||||
m_signalMapper->setMapping(shortcut, mode->uniqueModeName());
|
||||
connect(shortcut, SIGNAL(activated()), m_signalMapper, SLOT(map()));
|
||||
}
|
||||
|
||||
void ModeManager::updateModeToolTip()
|
||||
@ -182,7 +187,8 @@ void ModeManager::updateModeNameIcon(IMode *mode, const QIcon &icon, const QStri
|
||||
int index = indexOf(mode->uniqueModeName());
|
||||
if (index < 0)
|
||||
return;
|
||||
m_modeStack->updateTabNameIcon(index, icon, label);
|
||||
m_modeStack->setTabIcon(index, icon);
|
||||
m_modeStack->setTabText(index, label);
|
||||
}
|
||||
|
||||
void ModeManager::aboutToRemoveObject(QObject *obj)
|
||||
@ -194,7 +200,9 @@ void ModeManager::aboutToRemoveObject(QObject *obj)
|
||||
const int index = m_modes.indexOf(mode);
|
||||
m_modes.remove(index);
|
||||
m_modeShortcuts.remove(index);
|
||||
disconnect(m_modeStack, SIGNAL(currentChanged(int)), this, SLOT(currentTabChanged(int)));
|
||||
m_modeStack->removeTab(index);
|
||||
connect(m_modeStack, SIGNAL(currentChanged(int)), this, SLOT(currentTabChanged(int)));
|
||||
|
||||
m_mainWindow->removeContextObject(mode);
|
||||
}
|
||||
@ -209,7 +217,7 @@ void ModeManager::addAction(Command *command, int priority, QMenu *menu)
|
||||
if (p > priority)
|
||||
++index;
|
||||
|
||||
m_actionBar->insertAction(index, command->action(), menu);
|
||||
// m_actionBar->insertAction(index, command->action(), menu);
|
||||
}
|
||||
|
||||
void ModeManager::currentTabAboutToChange(int index)
|
||||
@ -223,6 +231,7 @@ void ModeManager::currentTabAboutToChange(int index)
|
||||
|
||||
void ModeManager::currentTabChanged(int index)
|
||||
{
|
||||
// qDebug() << "Current tab changed " << index;
|
||||
// Tab index changes to -1 when there is no tab left.
|
||||
if (index >= 0) {
|
||||
IMode *mode = m_modes.at(index);
|
||||
@ -242,6 +251,53 @@ void ModeManager::currentTabChanged(int index)
|
||||
}
|
||||
}
|
||||
|
||||
void ModeManager::tabMoved(int from, int to)
|
||||
{
|
||||
IMode *mode = m_modes.at(from);
|
||||
m_modes.remove(from);
|
||||
m_modes.insert(to, mode);
|
||||
Command *cmd = m_modeShortcuts.at(from);
|
||||
m_modeShortcuts.remove(from);
|
||||
m_modeShortcuts.insert(to, cmd);
|
||||
setDefaultKeyshortcuts();
|
||||
// Reprioritize, high priority means show to the left
|
||||
if (!m_isReprioritizing) {
|
||||
for (int i = 0; i < m_modes.count(); ++i) {
|
||||
m_modes.at(i)->setPriority(100-i);
|
||||
}
|
||||
emit newModeOrder(m_modes);
|
||||
}
|
||||
}
|
||||
|
||||
void ModeManager::reorderModes(QMap<QString, int> priorities)
|
||||
{
|
||||
foreach (IMode *mode, m_modes)
|
||||
mode->setPriority(priorities.value(QString(QLatin1String(mode->uniqueModeName())), mode->priority()));
|
||||
|
||||
m_isReprioritizing = true;
|
||||
IMode *current = currentMode();
|
||||
// Bubble sort
|
||||
bool swapped = false;
|
||||
do {
|
||||
swapped = false;
|
||||
for (int i = 0; i < m_modes.count()-1; ++i) {
|
||||
IMode *mode1 = m_modes.at(i);
|
||||
IMode *mode2 = m_modes.at(i+1);
|
||||
// qDebug() << "Comparing " << i << " to " << i+1 << " p1 " << mode1->priority() << " p2 " << mode2->priority();
|
||||
if (mode2->priority() > mode1->priority()) {
|
||||
m_modeStack->moveTab(i, i+1);
|
||||
// qDebug() << "Tab moved from " << i << " to " << i+1;
|
||||
swapped = true;
|
||||
}
|
||||
}
|
||||
} while (swapped);
|
||||
m_isReprioritizing = false;
|
||||
m_modeStack->setCurrentIndex(0);
|
||||
activateMode(current->uniqueModeName());
|
||||
emit newModeOrder(m_modes);
|
||||
}
|
||||
|
||||
|
||||
void ModeManager::setFocusToCurrentMode()
|
||||
{
|
||||
IMode *mode = currentMode();
|
||||
|
@ -40,6 +40,7 @@ QT_BEGIN_NAMESPACE
|
||||
class QSignalMapper;
|
||||
class QMenu;
|
||||
class QIcon;
|
||||
class MyTabWidget;
|
||||
QT_END_NAMESPACE
|
||||
|
||||
namespace Core {
|
||||
@ -58,7 +59,7 @@ class CORE_EXPORT ModeManager : public QObject
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
ModeManager(Internal::MainWindow *mainWindow, Internal::FancyTabWidget *modeStack);
|
||||
ModeManager(Internal::MainWindow *mainWindow, MyTabWidget *modeStack);
|
||||
|
||||
void init();
|
||||
static ModeManager *instance() { return m_instance; }
|
||||
@ -69,10 +70,13 @@ public:
|
||||
void addAction(Command *command, int priority, QMenu *menu = 0);
|
||||
void addWidget(QWidget *widget);
|
||||
void updateModeNameIcon(IMode *mode, const QIcon &icon, const QString &label);
|
||||
QVector<IMode*> modes() const { return m_modes; }
|
||||
void reorderModes(QMap<QString, int> priorities);
|
||||
|
||||
signals:
|
||||
void currentModeAboutToChange(Core::IMode *mode);
|
||||
void currentModeChanged(Core::IMode *mode);
|
||||
void newModeOrder(QVector<IMode*> modes);
|
||||
|
||||
public slots:
|
||||
void activateMode(const QString &id);
|
||||
@ -84,19 +88,22 @@ private slots:
|
||||
void currentTabAboutToChange(int index);
|
||||
void currentTabChanged(int index);
|
||||
void updateModeToolTip();
|
||||
void tabMoved(int from, int to);
|
||||
|
||||
private:
|
||||
int indexOf(const QString &id) const;
|
||||
void setDefaultKeyshortcuts();
|
||||
|
||||
static ModeManager *m_instance;
|
||||
Internal::MainWindow *m_mainWindow;
|
||||
Internal::FancyTabWidget *m_modeStack;
|
||||
Internal::FancyActionBar *m_actionBar;
|
||||
MyTabWidget *m_modeStack;
|
||||
QMap<Command*, int> m_actions;
|
||||
QVector<IMode*> m_modes;
|
||||
QVector<Command*> m_modeShortcuts;
|
||||
QSignalMapper *m_signalMapper;
|
||||
QList<int> m_addedContexts;
|
||||
QList<int> m_tabOrder;
|
||||
bool m_isReprioritizing;
|
||||
};
|
||||
|
||||
} // namespace Core
|
||||
|
@ -73,57 +73,6 @@ void SplitterOrView::mousePressEvent(QMouseEvent *e)
|
||||
}
|
||||
}
|
||||
|
||||
//void SplitterOrView::paintEvent(QPaintEvent *event)
|
||||
//{
|
||||
// if (m_uavGadgetManager->currentSplitterOrView() != this)
|
||||
// return;
|
||||
//
|
||||
// if (!m_view)
|
||||
// return;
|
||||
//
|
||||
// if (hasGadget())
|
||||
// return;
|
||||
//
|
||||
// if (m_uavGadgetManager->toolbarsShown())
|
||||
// return;
|
||||
//
|
||||
// // Discreet indication where an uavGadget would be if there is none
|
||||
// QPainter painter(this);
|
||||
// painter.setRenderHint(QPainter::Antialiasing, true);
|
||||
// painter.setPen(Qt::NoPen);
|
||||
// QColor shadeBrush(Qt::black);
|
||||
// shadeBrush.setAlpha(25);
|
||||
// painter.setBrush(shadeBrush);
|
||||
// const int r = 3;
|
||||
// painter.drawRoundedRect(rect().adjusted(r, r, -r, -r), r * 2, r * 2);
|
||||
//
|
||||
//#if 0
|
||||
// if (hasFocus()) {
|
||||
//#ifdef Q_WS_MAC
|
||||
// // With QMacStyle, we have to draw our own focus rect, since I didn't find
|
||||
// // a way to draw the nice mac focus rect _inside_ this widget
|
||||
// if (qobject_cast<QMacStyle *>(style())) {
|
||||
// painter.setPen(Qt::DotLine);
|
||||
// painter.setBrush(Qt::NoBrush);
|
||||
// painter.setOpacity(0.75);
|
||||
// painter.drawRect(rect());
|
||||
// } else {
|
||||
//#endif
|
||||
// QStyleOptionFocusRect option;
|
||||
// option.initFrom(this);
|
||||
// option.backgroundColor = palette().color(QPalette::Background);
|
||||
//
|
||||
// // Some styles require a certain state flag in order to draw the focus rect
|
||||
// option.state |= QStyle::State_KeyboardFocusChange;
|
||||
//
|
||||
// style()->drawPrimitive(QStyle::PE_FrameFocusRect, &option, &painter);
|
||||
//#ifdef Q_WS_MAC
|
||||
// }
|
||||
//#endif
|
||||
// }
|
||||
//#endif
|
||||
//}
|
||||
|
||||
/* Contract: return SplitterOrView that is not splitter, or 0 if not found.
|
||||
* Implications: must not return SplitterOrView that is splitter.
|
||||
*/
|
||||
|
@ -29,7 +29,6 @@
|
||||
#include "uavgadgetmanager.h"
|
||||
#include "uavgadgetview.h"
|
||||
#include "splitterorview.h"
|
||||
#include "uavgadgetmode.h"
|
||||
#include "uavgadgetinstancemanager.h"
|
||||
#include "iuavgadgetfactory.h"
|
||||
#include "iuavgadget.h"
|
||||
@ -79,229 +78,76 @@ static inline ExtensionSystem::PluginManager *pluginManager()
|
||||
|
||||
//===================UAVGadgetManager=====================
|
||||
|
||||
//UAVGadgetManagerPlaceHolder *UAVGadgetManagerPlaceHolder::m_current = 0;
|
||||
|
||||
UAVGadgetManagerPlaceHolder::UAVGadgetManagerPlaceHolder(Core::Internal::UAVGadgetMode *mode, QWidget *parent)
|
||||
: QWidget(parent),
|
||||
m_uavGadgetMode(mode),
|
||||
m_current(0)
|
||||
{
|
||||
m_mode = dynamic_cast<Core::IMode*>(mode);
|
||||
setLayout(new QVBoxLayout);
|
||||
layout()->setMargin(0);
|
||||
connect(Core::ModeManager::instance(), SIGNAL(currentModeChanged(Core::IMode *)),
|
||||
this, SLOT(currentModeChanged(Core::IMode *)));
|
||||
|
||||
currentModeChanged(Core::ModeManager::instance()->currentMode());
|
||||
}
|
||||
|
||||
UAVGadgetManagerPlaceHolder::~UAVGadgetManagerPlaceHolder()
|
||||
{
|
||||
if (m_current == this) {
|
||||
m_uavGadgetMode->uavGadgetManager()->setParent(0);
|
||||
m_uavGadgetMode->uavGadgetManager()->hide();
|
||||
}
|
||||
}
|
||||
|
||||
void UAVGadgetManagerPlaceHolder::currentModeChanged(Core::IMode *mode)
|
||||
{
|
||||
UAVGadgetManager *gm = m_uavGadgetMode->uavGadgetManager();
|
||||
if (m_current == this) {
|
||||
m_current = 0;
|
||||
gm->setParent(0);
|
||||
gm->hide();
|
||||
}
|
||||
if (m_mode == mode) {
|
||||
m_current = this;
|
||||
layout()->addWidget(gm);
|
||||
gm->showToolbars(gm->toolbarsShown());
|
||||
gm->show();
|
||||
}
|
||||
}
|
||||
|
||||
// ---------------- UAVGadgetManager
|
||||
|
||||
namespace Core {
|
||||
|
||||
|
||||
struct UAVGadgetManagerPrivate {
|
||||
explicit UAVGadgetManagerPrivate(ICore *core, QWidget *parent);
|
||||
~UAVGadgetManagerPrivate();
|
||||
|
||||
// The root splitter or view.
|
||||
QPointer<Internal::SplitterOrView> m_splitterOrView;
|
||||
|
||||
// The gadget which is currently 'active'.
|
||||
QPointer<IUAVGadget> m_currentGadget;
|
||||
|
||||
QPointer<ICore> m_core;
|
||||
|
||||
QPointer<Internal::UAVGadgetClosingCoreListener> m_coreListener;
|
||||
|
||||
// actions
|
||||
static QAction *m_showToolbarsAction;
|
||||
static QAction *m_splitAction;
|
||||
static QAction *m_splitSideBySideAction;
|
||||
static QAction *m_removeCurrentSplitAction;
|
||||
static QAction *m_removeAllSplitsAction;
|
||||
static QAction *m_gotoOtherSplitAction;
|
||||
};
|
||||
}
|
||||
|
||||
QAction *UAVGadgetManagerPrivate::m_showToolbarsAction = 0;
|
||||
QAction *UAVGadgetManagerPrivate::m_splitAction = 0;
|
||||
QAction *UAVGadgetManagerPrivate::m_splitSideBySideAction = 0;
|
||||
QAction *UAVGadgetManagerPrivate::m_removeCurrentSplitAction = 0;
|
||||
QAction *UAVGadgetManagerPrivate::m_removeAllSplitsAction = 0;
|
||||
QAction *UAVGadgetManagerPrivate::m_gotoOtherSplitAction = 0;
|
||||
|
||||
UAVGadgetManagerPrivate::UAVGadgetManagerPrivate(ICore *core, QWidget *parent) :
|
||||
UAVGadgetManager::UAVGadgetManager(ICore *core, QString name, QIcon icon, int priority, QString uniqueName, QWidget *parent) :
|
||||
m_showToolbars(true),
|
||||
m_splitterOrView(0),
|
||||
m_currentGadget(0),
|
||||
m_core(core),
|
||||
m_coreListener(0)
|
||||
{
|
||||
Q_UNUSED(parent);
|
||||
}
|
||||
|
||||
UAVGadgetManagerPrivate::~UAVGadgetManagerPrivate()
|
||||
{
|
||||
}
|
||||
|
||||
UAVGadgetManager::UAVGadgetManager(ICore *core, QWidget *parent) :
|
||||
QWidget(parent),
|
||||
m_showToolbars(false),
|
||||
m_d(new UAVGadgetManagerPrivate(core, parent)),
|
||||
m_uavGadgetMode(0)
|
||||
m_name(name),
|
||||
m_icon(icon),
|
||||
m_priority(priority),
|
||||
m_widget(new QWidget(parent))
|
||||
{
|
||||
|
||||
connect(m_d->m_core, SIGNAL(contextAboutToChange(Core::IContext *)),
|
||||
// checking that the mode name is unique gives harmless
|
||||
// warnings on the console output
|
||||
ModeManager *modeManager = ModeManager::instance();
|
||||
if (!modeManager->mode(uniqueName)) {
|
||||
m_uniqueName = uniqueName;
|
||||
} else {
|
||||
// this shouldn't happen
|
||||
m_uniqueName = uniqueName + QString::number(quint64(this));
|
||||
}
|
||||
m_uniqueNameBA = m_uniqueName.toLatin1();
|
||||
m_uniqueModeName = m_uniqueNameBA.data();
|
||||
|
||||
connect(m_core, SIGNAL(contextAboutToChange(Core::IContext *)),
|
||||
this, SLOT(handleContextChange(Core::IContext *)));
|
||||
const QList<int> uavGadgetManagerContext =
|
||||
QList<int>() << m_d->m_core->uniqueIDManager()->uniqueIdentifier(Constants::C_UAVGADGETMANAGER);
|
||||
|
||||
ActionManager *am = m_d->m_core->actionManager();
|
||||
|
||||
//Window Menu
|
||||
ActionContainer *mwindow = am->actionContainer(Constants::M_WINDOW);
|
||||
Command *cmd;
|
||||
|
||||
// The actions m_d->m_showToolbarsAction etc are common to all instances of UAVGadgetManager
|
||||
// which means that they share the menu items/signals in the Window menu.
|
||||
// That is, they all connect their slots to the same signal and have to check in the slot
|
||||
// if the current mode is their mode, otherwise they just ignore the signal.
|
||||
// The first UAVGadgetManager creates the actions, and the following just use them
|
||||
// (This also implies that they share the same context.)
|
||||
if (m_d->m_showToolbarsAction == 0)
|
||||
{
|
||||
//Window menu separators
|
||||
QAction *tmpaction = new QAction(this);
|
||||
tmpaction->setSeparator(true);
|
||||
cmd = am->registerAction(tmpaction, QLatin1String("OpenPilot.Window.Sep.Split"), uavGadgetManagerContext);
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_HIDE_TOOLBAR);
|
||||
|
||||
m_d->m_showToolbarsAction = new QAction(tr("Edit Gadgets Mode"), this);
|
||||
m_d->m_showToolbarsAction->setCheckable(true);
|
||||
cmd = am->registerAction(m_d->m_showToolbarsAction, Constants::HIDE_TOOLBARS, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("Ctrl+Shift+F10")));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_HIDE_TOOLBAR);
|
||||
|
||||
//Window menu separators
|
||||
QAction *tmpaction2 = new QAction(this);
|
||||
tmpaction2->setSeparator(true);
|
||||
cmd = am->registerAction(tmpaction2, QLatin1String("OpenPilot.Window.Sep.Split2"), uavGadgetManagerContext);
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
}
|
||||
connect(m_d->m_showToolbarsAction, SIGNAL(triggered(bool)), this, SLOT(showToolbars(bool)));
|
||||
|
||||
#ifdef Q_WS_MAC
|
||||
QString prefix = tr("Meta+Shift");
|
||||
#else
|
||||
QString prefix = tr("Ctrl+Shift");
|
||||
#endif
|
||||
|
||||
if (m_d->m_splitAction == 0)
|
||||
{
|
||||
m_d->m_splitAction = new QAction(tr("Split"), this);
|
||||
cmd = am->registerAction(m_d->m_splitAction, Constants::SPLIT, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("%1+Down").arg(prefix)));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
}
|
||||
connect(m_d->m_splitAction, SIGNAL(triggered()), this, SLOT(split()));
|
||||
|
||||
if (m_d->m_splitSideBySideAction == 0)
|
||||
{
|
||||
m_d->m_splitSideBySideAction = new QAction(tr("Split Side by Side"), this);
|
||||
cmd = am->registerAction(m_d->m_splitSideBySideAction, Constants::SPLIT_SIDE_BY_SIDE, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("%1+Right").arg(prefix)));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
}
|
||||
connect(m_d->m_splitSideBySideAction, SIGNAL(triggered()), this, SLOT(splitSideBySide()));
|
||||
|
||||
if (m_d->m_removeCurrentSplitAction == 0)
|
||||
{
|
||||
m_d->m_removeCurrentSplitAction = new QAction(tr("Close Current View"), this);
|
||||
cmd = am->registerAction(m_d->m_removeCurrentSplitAction, Constants::REMOVE_CURRENT_SPLIT, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("%1+C").arg(prefix)));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
}
|
||||
connect(m_d->m_removeCurrentSplitAction, SIGNAL(triggered()), this, SLOT(removeCurrentSplit()));
|
||||
|
||||
if (m_d->m_removeAllSplitsAction == 0)
|
||||
{
|
||||
m_d->m_removeAllSplitsAction = new QAction(tr("Close All Other Views"), this);
|
||||
cmd = am->registerAction(m_d->m_removeAllSplitsAction, Constants::REMOVE_ALL_SPLITS, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("%1+A").arg(prefix)));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
}
|
||||
connect(m_d->m_removeAllSplitsAction, SIGNAL(triggered()), this, SLOT(removeAllSplits()));
|
||||
|
||||
if (m_d->m_gotoOtherSplitAction == 0)
|
||||
{
|
||||
m_d->m_gotoOtherSplitAction = new QAction(tr("Goto Next View"), this);
|
||||
cmd = am->registerAction(m_d->m_gotoOtherSplitAction, Constants::GOTO_OTHER_SPLIT, uavGadgetManagerContext);
|
||||
cmd->setDefaultKeySequence(QKeySequence(tr("%1+N").arg(prefix)));
|
||||
mwindow->addAction(cmd, Constants::G_WINDOW_SPLIT);
|
||||
}
|
||||
connect(m_d->m_gotoOtherSplitAction, SIGNAL(triggered()), this, SLOT(gotoOtherSplit()));
|
||||
connect(modeManager, SIGNAL(currentModeChanged(Core::IMode*)),
|
||||
this, SLOT(modeChanged(Core::IMode*)));
|
||||
|
||||
// other setup
|
||||
m_d->m_splitterOrView = new SplitterOrView(this, 0);
|
||||
m_splitterOrView = new SplitterOrView(this, 0);
|
||||
|
||||
// SplitterOrView with 0 as gadget calls our setCurrentGadget, which relies on currentSplitterOrView(),
|
||||
// which needs our m_splitterorView to be set, which isn't set yet at that time.
|
||||
// So directly set our currentGadget to 0, and do it again.
|
||||
m_d->m_currentGadget = 0;
|
||||
setCurrentGadget(m_d->m_splitterOrView->view()->gadget());
|
||||
m_currentGadget = 0;
|
||||
setCurrentGadget(m_splitterOrView->view()->gadget());
|
||||
|
||||
QHBoxLayout *layout = new QHBoxLayout(this);
|
||||
QHBoxLayout *layout = new QHBoxLayout(m_widget);
|
||||
layout->setMargin(0);
|
||||
layout->setSpacing(0);
|
||||
layout->addWidget(m_d->m_splitterOrView);
|
||||
layout->addWidget(m_splitterOrView);
|
||||
|
||||
showToolbars(m_showToolbars);
|
||||
updateActions();
|
||||
}
|
||||
|
||||
UAVGadgetManager::~UAVGadgetManager()
|
||||
{
|
||||
if (m_d->m_core) {
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
if (m_d->m_coreListener) {
|
||||
pm->removeObject(m_d->m_coreListener);
|
||||
delete m_d->m_coreListener;
|
||||
}
|
||||
}
|
||||
delete m_d;
|
||||
}
|
||||
|
||||
QList<int> UAVGadgetManager::context() const
|
||||
{
|
||||
static QList<int> contexts = QList<int>() <<
|
||||
UniqueIDManager::instance()->uniqueIdentifier(Constants::C_UAVGADGETMANAGER);
|
||||
return contexts;
|
||||
}
|
||||
|
||||
void UAVGadgetManager::modeChanged(Core::IMode *mode)
|
||||
{
|
||||
if (mode != this)
|
||||
return;
|
||||
|
||||
m_currentGadget->widget()->setFocus();
|
||||
showToolbars(toolbarsShown());
|
||||
}
|
||||
|
||||
void UAVGadgetManager::init()
|
||||
{
|
||||
QList<int> context;
|
||||
context << m_d->m_core->uniqueIDManager()->uniqueIdentifier("OpenPilot.UAVGadgetManager");
|
||||
|
||||
m_d->m_coreListener = new UAVGadgetClosingCoreListener(this);
|
||||
|
||||
pluginManager()->addObject(m_d->m_coreListener);
|
||||
context << m_core->uniqueIDManager()->uniqueIdentifier("OpenPilot.UAVGadgetManager");
|
||||
}
|
||||
|
||||
void UAVGadgetManager::handleContextChange(Core::IContext *context)
|
||||
@ -311,16 +157,15 @@ void UAVGadgetManager::handleContextChange(Core::IContext *context)
|
||||
IUAVGadget *uavGadget = context ? qobject_cast<IUAVGadget*>(context) : 0;
|
||||
if (uavGadget)
|
||||
setCurrentGadget(uavGadget);
|
||||
updateActions();
|
||||
}
|
||||
|
||||
void UAVGadgetManager::setCurrentGadget(IUAVGadget *uavGadget)
|
||||
{
|
||||
if (m_d->m_currentGadget == uavGadget)
|
||||
if (m_currentGadget == uavGadget)
|
||||
return;
|
||||
|
||||
SplitterOrView *oldView = currentSplitterOrView();
|
||||
m_d->m_currentGadget = uavGadget;
|
||||
m_currentGadget = uavGadget;
|
||||
SplitterOrView *view = currentSplitterOrView();
|
||||
if (oldView != view) {
|
||||
if (oldView)
|
||||
@ -330,8 +175,6 @@ void UAVGadgetManager::setCurrentGadget(IUAVGadget *uavGadget)
|
||||
}
|
||||
uavGadget->widget()->setFocus();
|
||||
emit currentGadgetChanged(uavGadget);
|
||||
updateActions();
|
||||
// emit currentGadgetChanged(uavGadget);
|
||||
}
|
||||
|
||||
/* Contract: return current SplitterOrView.
|
||||
@ -339,17 +182,17 @@ void UAVGadgetManager::setCurrentGadget(IUAVGadget *uavGadget)
|
||||
*/
|
||||
Core::Internal::SplitterOrView *UAVGadgetManager::currentSplitterOrView() const
|
||||
{
|
||||
if (!m_d->m_splitterOrView) // this is only for startup
|
||||
if (!m_splitterOrView) // this is only for startup
|
||||
return 0;
|
||||
SplitterOrView *view = m_d->m_currentGadget ?
|
||||
m_d->m_splitterOrView->findView(m_d->m_currentGadget) :
|
||||
SplitterOrView *view = m_currentGadget ?
|
||||
m_splitterOrView->findView(m_currentGadget) :
|
||||
0;
|
||||
return view;
|
||||
}
|
||||
|
||||
IUAVGadget *UAVGadgetManager::currentGadget() const
|
||||
{
|
||||
return m_d->m_currentGadget;
|
||||
return m_currentGadget;
|
||||
}
|
||||
|
||||
void UAVGadgetManager::emptyView(Core::Internal::UAVGadgetView *view)
|
||||
@ -369,10 +212,10 @@ void UAVGadgetManager::closeView(Core::Internal::UAVGadgetView *view)
|
||||
{
|
||||
if (!view)
|
||||
return;
|
||||
SplitterOrView *splitterOrView = m_d->m_splitterOrView->findView(view);
|
||||
SplitterOrView *splitterOrView = m_splitterOrView->findView(view);
|
||||
Q_ASSERT(splitterOrView);
|
||||
Q_ASSERT(splitterOrView->view() == view);
|
||||
if (splitterOrView == m_d->m_splitterOrView)
|
||||
if (splitterOrView == m_splitterOrView)
|
||||
return;
|
||||
|
||||
IUAVGadget *gadget = view->gadget();
|
||||
@ -380,7 +223,7 @@ void UAVGadgetManager::closeView(Core::Internal::UAVGadgetView *view)
|
||||
UAVGadgetInstanceManager *im = ICore::instance()->uavGadgetInstanceManager();
|
||||
im->removeGadget(gadget);
|
||||
|
||||
SplitterOrView *splitter = m_d->m_splitterOrView->findSplitter(splitterOrView);
|
||||
SplitterOrView *splitter = m_splitterOrView->findSplitter(splitterOrView);
|
||||
Q_ASSERT(splitterOrView->hasGadget() == false);
|
||||
Q_ASSERT(splitter->isSplitter() == true);
|
||||
splitterOrView->hide();
|
||||
@ -398,7 +241,7 @@ void UAVGadgetManager::addGadgetToContext(IUAVGadget *gadget)
|
||||
{
|
||||
if (!gadget)
|
||||
return;
|
||||
m_d->m_core->addContextObject(gadget);
|
||||
m_core->addContextObject(gadget);
|
||||
|
||||
// emit uavGadgetOpened(uavGadget);
|
||||
}
|
||||
@ -407,27 +250,39 @@ void UAVGadgetManager::removeGadget(IUAVGadget *gadget)
|
||||
{
|
||||
if (!gadget)
|
||||
return;
|
||||
m_d->m_core->removeContextObject(qobject_cast<IContext*>(gadget));
|
||||
m_core->removeContextObject(qobject_cast<IContext*>(gadget));
|
||||
}
|
||||
|
||||
void UAVGadgetManager::ensureUAVGadgetManagerVisible()
|
||||
{
|
||||
if (!isVisible())
|
||||
m_d->m_core->modeManager()->activateMode(m_uavGadgetMode->uniqueModeName());
|
||||
if (!m_widget->isVisible())
|
||||
m_core->modeManager()->activateMode(this->uniqueModeName());
|
||||
}
|
||||
|
||||
void UAVGadgetManager::updateActions()
|
||||
void UAVGadgetManager::showToolbars(bool show)
|
||||
{
|
||||
if (m_d->m_core->modeManager()->currentMode() != m_uavGadgetMode)
|
||||
if (m_core->modeManager()->currentMode() != this)
|
||||
return;
|
||||
if (!m_d->m_splitterOrView) // this is only for startup
|
||||
|
||||
m_showToolbars = show;
|
||||
SplitterOrView *next = m_splitterOrView->findFirstView();
|
||||
do {
|
||||
next->view()->showToolbar(show);
|
||||
next = m_splitterOrView->findNextView(next);
|
||||
} while (next);
|
||||
|
||||
updateUavGadgetMenus();
|
||||
}
|
||||
|
||||
void UAVGadgetManager::updateUavGadgetMenus()
|
||||
{
|
||||
if (m_core->modeManager()->currentMode() != this)
|
||||
return;
|
||||
if (!m_splitterOrView) // this is only for startup
|
||||
return;
|
||||
// Splitting is only possible when the toolbars are shown
|
||||
bool shown = m_d->m_showToolbarsAction->isChecked();
|
||||
bool hasSplitter = m_d->m_splitterOrView->isSplitter();
|
||||
m_d->m_removeCurrentSplitAction->setEnabled(shown && hasSplitter);
|
||||
m_d->m_removeAllSplitsAction->setEnabled(shown && hasSplitter);
|
||||
m_d->m_gotoOtherSplitAction->setEnabled(shown && hasSplitter);
|
||||
bool hasSplitter = m_splitterOrView->isSplitter();
|
||||
emit showUavGadgetMenus(m_showToolbars, hasSplitter);
|
||||
}
|
||||
|
||||
void UAVGadgetManager::saveState(QSettings* qSettings) const
|
||||
@ -435,7 +290,7 @@ void UAVGadgetManager::saveState(QSettings* qSettings) const
|
||||
qSettings->setValue("version","UAVGadgetManagerV1");
|
||||
qSettings->setValue("showToolbars",m_showToolbars);
|
||||
qSettings->beginGroup("splitter");
|
||||
m_d->m_splitterOrView->saveState(qSettings);
|
||||
m_splitterOrView->saveState(qSettings);
|
||||
qSettings->endGroup();
|
||||
}
|
||||
|
||||
@ -444,8 +299,8 @@ bool UAVGadgetManager::restoreState(QSettings* qSettings)
|
||||
removeAllSplits();
|
||||
|
||||
UAVGadgetInstanceManager *im = ICore::instance()->uavGadgetInstanceManager();
|
||||
IUAVGadget *gadget = m_d->m_splitterOrView->view()->gadget();
|
||||
emptyView(m_d->m_splitterOrView->view());
|
||||
IUAVGadget *gadget = m_splitterOrView->view()->gadget();
|
||||
emptyView(m_splitterOrView->view());
|
||||
im->removeGadget(gadget);
|
||||
|
||||
QString version = qSettings->value("version").toString();
|
||||
@ -458,7 +313,7 @@ bool UAVGadgetManager::restoreState(QSettings* qSettings)
|
||||
QApplication::setOverrideCursor(Qt::WaitCursor);
|
||||
|
||||
qSettings->beginGroup("splitter");
|
||||
m_d->m_splitterOrView->restoreState(qSettings);
|
||||
m_splitterOrView->restoreState(qSettings);
|
||||
qSettings->endGroup();
|
||||
|
||||
QApplication::restoreOverrideCursor();
|
||||
@ -468,7 +323,7 @@ bool UAVGadgetManager::restoreState(QSettings* qSettings)
|
||||
void UAVGadgetManager::saveSettings(QSettings *qs)
|
||||
{
|
||||
qs->beginGroup("UAVGadgetManager");
|
||||
qs->beginGroup(m_uavGadgetMode->uniqueModeName());
|
||||
qs->beginGroup(this->uniqueModeName());
|
||||
|
||||
// Make sure the old tree is wiped.
|
||||
qs->remove("");
|
||||
@ -488,16 +343,15 @@ void UAVGadgetManager::readSettings(QSettings *qs)
|
||||
}
|
||||
qs->beginGroup(uavGadgetManagerRootKey);
|
||||
|
||||
if(!qs->childGroups().contains(m_uavGadgetMode->uniqueModeName())) {
|
||||
if(!qs->childGroups().contains(uniqueModeName())) {
|
||||
qs->endGroup();
|
||||
return;
|
||||
}
|
||||
qs->beginGroup(m_uavGadgetMode->uniqueModeName());
|
||||
qs->beginGroup(uniqueModeName());
|
||||
|
||||
restoreState(qs);
|
||||
|
||||
showToolbars(m_showToolbars);
|
||||
updateActions();
|
||||
|
||||
qs->endGroup();
|
||||
qs->endGroup();
|
||||
@ -505,18 +359,19 @@ void UAVGadgetManager::readSettings(QSettings *qs)
|
||||
|
||||
void UAVGadgetManager::split(Qt::Orientation orientation)
|
||||
{
|
||||
if (m_d->m_core->modeManager()->currentMode() != m_uavGadgetMode)
|
||||
if (m_core->modeManager()->currentMode() != this)
|
||||
return;
|
||||
|
||||
IUAVGadget *uavGadget = m_d->m_currentGadget;
|
||||
IUAVGadget *uavGadget = m_currentGadget;
|
||||
Q_ASSERT(uavGadget);
|
||||
SplitterOrView *view = currentSplitterOrView();
|
||||
Q_ASSERT(view);
|
||||
view->split(orientation);
|
||||
|
||||
SplitterOrView *sor = m_d->m_splitterOrView->findView(uavGadget);
|
||||
SplitterOrView *next = m_d->m_splitterOrView->findNextView(sor);
|
||||
SplitterOrView *sor = m_splitterOrView->findView(uavGadget);
|
||||
SplitterOrView *next = m_splitterOrView->findNextView(sor);
|
||||
setCurrentGadget(next->gadget());
|
||||
updateUavGadgetMenus();
|
||||
}
|
||||
|
||||
void UAVGadgetManager::split()
|
||||
@ -531,37 +386,38 @@ void UAVGadgetManager::splitSideBySide()
|
||||
|
||||
void UAVGadgetManager::removeCurrentSplit()
|
||||
{
|
||||
if (m_d->m_core->modeManager()->currentMode() != m_uavGadgetMode)
|
||||
if (m_core->modeManager()->currentMode() != this)
|
||||
return;
|
||||
|
||||
SplitterOrView *viewToClose = currentSplitterOrView();
|
||||
if (viewToClose == m_d->m_splitterOrView)
|
||||
if (viewToClose == m_splitterOrView)
|
||||
return;
|
||||
closeView(viewToClose->view());
|
||||
updateUavGadgetMenus();
|
||||
}
|
||||
|
||||
// Removes all gadgets and splits in the workspace, except the current/active gadget.
|
||||
void UAVGadgetManager::removeAllSplits()
|
||||
{
|
||||
if (m_d->m_core->modeManager()->currentMode() != m_uavGadgetMode)
|
||||
if (m_core->modeManager()->currentMode() != this)
|
||||
return;
|
||||
|
||||
if (!m_d->m_splitterOrView->isSplitter())
|
||||
if (!m_splitterOrView->isSplitter())
|
||||
return;
|
||||
|
||||
// Use a QPointer, just in case we accidently delete the gadget we want to keep.
|
||||
QPointer<IUAVGadget> currentGadget = m_d->m_currentGadget;
|
||||
QPointer<IUAVGadget> currentGadget = m_currentGadget;
|
||||
|
||||
Q_ASSERT(currentGadget);
|
||||
QList<IUAVGadget*> gadgets = m_d->m_splitterOrView->gadgets();
|
||||
QList<IUAVGadget*> gadgets = m_splitterOrView->gadgets();
|
||||
Q_ASSERT(gadgets.count(currentGadget) == 1);
|
||||
gadgets.removeOne(currentGadget);
|
||||
|
||||
// Remove all splits and their gadgets, then create a new view with the current gadget.
|
||||
m_d->m_splitterOrView->unsplitAll(currentGadget);
|
||||
m_splitterOrView->unsplitAll(currentGadget);
|
||||
|
||||
// Zeroing the current gadget means setCurrentGadget will do something when we call it.
|
||||
m_d->m_currentGadget = 0;
|
||||
m_currentGadget = 0;
|
||||
setCurrentGadget(currentGadget);
|
||||
|
||||
// Remove all other gadgets from the instance manager.
|
||||
@ -569,53 +425,21 @@ void UAVGadgetManager::removeAllSplits()
|
||||
foreach (IUAVGadget *g, gadgets) {
|
||||
im->removeGadget(g);
|
||||
}
|
||||
updateUavGadgetMenus();
|
||||
}
|
||||
|
||||
void UAVGadgetManager::gotoOtherSplit()
|
||||
{
|
||||
if (m_d->m_core->modeManager()->currentMode() != m_uavGadgetMode)
|
||||
if (m_core->modeManager()->currentMode() != this)
|
||||
return;
|
||||
|
||||
if (m_d->m_splitterOrView->isSplitter()) {
|
||||
if (m_splitterOrView->isSplitter()) {
|
||||
SplitterOrView *currentView = currentSplitterOrView();
|
||||
SplitterOrView *view = m_d->m_splitterOrView->findNextView(currentView);
|
||||
SplitterOrView *view = m_splitterOrView->findNextView(currentView);
|
||||
if (!view)
|
||||
view = m_d->m_splitterOrView->findFirstView();
|
||||
view = m_splitterOrView->findFirstView();
|
||||
if (view) {
|
||||
setCurrentGadget(view->gadget());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void UAVGadgetManager::showToolbars(bool show)
|
||||
{
|
||||
if (m_d->m_core->modeManager()->currentMode() != m_uavGadgetMode)
|
||||
return;
|
||||
|
||||
m_d->m_showToolbarsAction->setChecked(show);
|
||||
m_showToolbars = show;
|
||||
SplitterOrView *next = m_d->m_splitterOrView->findFirstView();
|
||||
do {
|
||||
next->view()->showToolbar(show);
|
||||
next = m_d->m_splitterOrView->findNextView(next);
|
||||
} while (next);
|
||||
|
||||
m_d->m_splitAction->setEnabled(show);
|
||||
m_d->m_splitSideBySideAction->setEnabled(show);
|
||||
m_d->m_removeCurrentSplitAction->setEnabled(show);
|
||||
m_d->m_removeAllSplitsAction->setEnabled(show);
|
||||
m_d->m_gotoOtherSplitAction->setEnabled(show);
|
||||
}
|
||||
//===================UAVGadgetClosingCoreListener======================
|
||||
|
||||
UAVGadgetClosingCoreListener::UAVGadgetClosingCoreListener(UAVGadgetManager *em)
|
||||
: m_em(em)
|
||||
{
|
||||
}
|
||||
|
||||
bool UAVGadgetClosingCoreListener::coreAboutToClose()
|
||||
{
|
||||
// Do not ask for files to save.
|
||||
// MainWindow::closeEvent has already done that.
|
||||
return true;
|
||||
}
|
||||
|
@ -32,14 +32,15 @@
|
||||
#include "../core_global.h"
|
||||
|
||||
#include <coreplugin/icorelistener.h>
|
||||
#include <coreplugin/imode.h>
|
||||
|
||||
#include <QtGui/QWidget>
|
||||
#include <QtCore/QList>
|
||||
#include <QtCore/QPointer>
|
||||
#include <QtCore/QSettings>
|
||||
#include <QtGui/QIcon>
|
||||
|
||||
QT_BEGIN_NAMESPACE
|
||||
class QSettings;
|
||||
class QModelIndex;
|
||||
QT_END_NAMESPACE
|
||||
|
||||
@ -48,49 +49,33 @@ namespace Core {
|
||||
class IContext;
|
||||
class ICore;
|
||||
class IUAVGadget;
|
||||
class IMode;
|
||||
|
||||
struct UAVGadgetManagerPrivate;
|
||||
|
||||
namespace Internal {
|
||||
|
||||
class UAVGadgetMode;
|
||||
class UAVGadgetView;
|
||||
class SplitterOrView;
|
||||
|
||||
class UAVGadgetClosingCoreListener;
|
||||
|
||||
|
||||
} // namespace Internal
|
||||
|
||||
class CORE_EXPORT UAVGadgetManagerPlaceHolder : public QWidget
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
UAVGadgetManagerPlaceHolder(Core::Internal::UAVGadgetMode *mode, QWidget *parent = 0);
|
||||
~UAVGadgetManagerPlaceHolder();
|
||||
// static UAVGadgetManagerPlaceHolder* current();
|
||||
private slots:
|
||||
void currentModeChanged(Core::IMode *);
|
||||
private:
|
||||
Core::IMode *m_mode;
|
||||
Core::Internal::UAVGadgetMode *m_uavGadgetMode;
|
||||
UAVGadgetManagerPlaceHolder* m_current;
|
||||
};
|
||||
|
||||
|
||||
class CORE_EXPORT UAVGadgetManager : public QWidget
|
||||
class CORE_EXPORT UAVGadgetManager : public IMode
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
|
||||
explicit UAVGadgetManager(ICore *core, QWidget *parent);
|
||||
explicit UAVGadgetManager(ICore *core, QString name, QIcon icon, int priority, QString uniqueName, QWidget *parent);
|
||||
virtual ~UAVGadgetManager();
|
||||
|
||||
// IMode
|
||||
QString name() const { return m_name; }
|
||||
QIcon icon() const { return m_icon; }
|
||||
int priority() const { return m_priority; }
|
||||
void setPriority(int priority) { m_priority = priority; }
|
||||
const char *uniqueModeName() const { return m_uniqueModeName; }
|
||||
QList<int> context() const;
|
||||
|
||||
void init();
|
||||
// setUAVGadgetMode should be called exactly once
|
||||
// right after the mode has been created, and never thereafter
|
||||
void setUAVGadgetMode(Core::Internal::UAVGadgetMode *mode) { m_uavGadgetMode = mode; }
|
||||
QWidget *widget() { return m_widget; }
|
||||
|
||||
void ensureUAVGadgetManagerVisible();
|
||||
|
||||
@ -105,10 +90,14 @@ public:
|
||||
|
||||
signals:
|
||||
void currentGadgetChanged(IUAVGadget *gadget);
|
||||
void showUavGadgetMenus(bool show, bool hasSplitter);
|
||||
void updateSplitMenus(bool hasSplitter);
|
||||
|
||||
private slots:
|
||||
void handleContextChange(Core::IContext *context);
|
||||
void updateActions();
|
||||
void updateUavGadgetMenus();
|
||||
void modeChanged(Core::IMode *mode);
|
||||
|
||||
|
||||
public slots:
|
||||
void split(Qt::Orientation orientation);
|
||||
@ -120,16 +109,25 @@ public slots:
|
||||
void showToolbars(bool show);
|
||||
|
||||
private:
|
||||
void setCurrentGadget(IUAVGadget *gadget);
|
||||
void addGadgetToContext(IUAVGadget *gadget);
|
||||
void removeGadget(IUAVGadget *gadget);
|
||||
void setCurrentGadget(IUAVGadget *gadget);
|
||||
void closeView(Core::Internal::UAVGadgetView *view);
|
||||
void emptyView(Core::Internal::UAVGadgetView *view);
|
||||
Core::Internal::SplitterOrView *currentSplitterOrView() const;
|
||||
|
||||
bool m_showToolbars;
|
||||
UAVGadgetManagerPrivate *m_d;
|
||||
Core::Internal::UAVGadgetMode *m_uavGadgetMode;
|
||||
Core::Internal::SplitterOrView *m_splitterOrView;
|
||||
Core::IUAVGadget *m_currentGadget;
|
||||
Core::ICore *m_core;
|
||||
|
||||
QString m_name;
|
||||
QIcon m_icon;
|
||||
int m_priority;
|
||||
QString m_uniqueName;
|
||||
QByteArray m_uniqueNameBA;
|
||||
const char* m_uniqueModeName;
|
||||
QWidget *m_widget;
|
||||
|
||||
friend class Core::Internal::SplitterOrView;
|
||||
friend class Core::Internal::UAVGadgetView;
|
||||
@ -137,26 +135,4 @@ private:
|
||||
|
||||
} // namespace Core
|
||||
|
||||
|
||||
//===================UAVGadgetClosingCoreListener======================
|
||||
|
||||
namespace Core {
|
||||
namespace Internal {
|
||||
|
||||
class UAVGadgetClosingCoreListener : public ICoreListener
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
UAVGadgetClosingCoreListener(UAVGadgetManager *em);
|
||||
bool uavGadgetAboutToClose(IUAVGadget *gadget);
|
||||
bool coreAboutToClose();
|
||||
|
||||
private:
|
||||
UAVGadgetManager *m_em;
|
||||
};
|
||||
|
||||
} // namespace Internal
|
||||
} // namespace Core
|
||||
|
||||
#endif // UAVGADGETMANAGER_H
|
||||
|
@ -1,135 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file uavgadgetmode.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup CorePlugin Core Plugin
|
||||
* @{
|
||||
* @brief The Core GCS 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 "uavgadgetmode.h"
|
||||
#include "uavgadgetmanager.h"
|
||||
#include "coreconstants.h"
|
||||
#include "modemanager.h"
|
||||
#include "uniqueidmanager.h"
|
||||
#include "minisplitter.h"
|
||||
#include "outputpane.h"
|
||||
#include "rightpane.h"
|
||||
#include "iuavgadget.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QtCore/QLatin1String>
|
||||
#include <QtGui/QHBoxLayout>
|
||||
#include <QtGui/QWidget>
|
||||
#include <QtGui/QSplitter>
|
||||
|
||||
using namespace Core;
|
||||
using namespace Core::Internal;
|
||||
|
||||
UAVGadgetMode::UAVGadgetMode(UAVGadgetManager *uavGadgetManager, QString name, QIcon icon, int priority, QString uniqueName) :
|
||||
m_uavGadgetManager(uavGadgetManager),
|
||||
m_name(name),
|
||||
m_icon(icon),
|
||||
m_widget(new QWidget),
|
||||
m_priority(priority),
|
||||
m_layout(new QVBoxLayout)
|
||||
{
|
||||
m_layout->setSpacing(0);
|
||||
m_layout->setMargin(0);
|
||||
m_widget->setLayout(m_layout);
|
||||
m_layout->insertWidget(0, new Core::UAVGadgetManagerPlaceHolder(this));
|
||||
|
||||
ModeManager *modeManager = ModeManager::instance();
|
||||
// checking that the mode name is unique gives harmless
|
||||
// warnings on the console output
|
||||
if (!modeManager->mode(uniqueName)) {
|
||||
m_uniqueName = uniqueName;
|
||||
} else {
|
||||
// this shouldn't happen
|
||||
m_uniqueName = uniqueName + QString::number(quint64(this));
|
||||
}
|
||||
m_uniqueNameBA = m_uniqueName.toLatin1();
|
||||
m_uniqueNameC = m_uniqueNameBA.data();
|
||||
connect(modeManager, SIGNAL(currentModeChanged(Core::IMode*)),
|
||||
this, SLOT(grabUAVGadgetManager(Core::IMode*)));
|
||||
m_widget->setFocusProxy(m_uavGadgetManager);
|
||||
}
|
||||
|
||||
UAVGadgetMode::~UAVGadgetMode()
|
||||
{
|
||||
// TODO: see if this leftover from Qt Creator still applies
|
||||
// Make sure the uavGadget manager does not get deleted
|
||||
m_uavGadgetManager->setParent(0);
|
||||
delete m_widget;
|
||||
}
|
||||
|
||||
QString UAVGadgetMode::name() const
|
||||
{
|
||||
return m_name;
|
||||
}
|
||||
|
||||
void UAVGadgetMode::setName(QString name)
|
||||
{
|
||||
m_name = name;
|
||||
}
|
||||
|
||||
QIcon UAVGadgetMode::icon() const
|
||||
{
|
||||
return m_icon;
|
||||
}
|
||||
|
||||
void UAVGadgetMode::setIcon(QIcon icon)
|
||||
{
|
||||
m_icon = icon;
|
||||
}
|
||||
|
||||
int UAVGadgetMode::priority() const
|
||||
{
|
||||
return m_priority;
|
||||
}
|
||||
|
||||
QWidget* UAVGadgetMode::widget()
|
||||
{
|
||||
return m_widget;
|
||||
}
|
||||
|
||||
const char* UAVGadgetMode::uniqueModeName() const
|
||||
{
|
||||
return m_uniqueNameC;
|
||||
}
|
||||
|
||||
QList<int> UAVGadgetMode::context() const
|
||||
{
|
||||
static QList<int> contexts = QList<int>() <<
|
||||
UniqueIDManager::instance()->uniqueIdentifier(Constants::C_UAVGADGET_MODE) <<
|
||||
UniqueIDManager::instance()->uniqueIdentifier(Constants::C_UAVGADGETMANAGER);
|
||||
return contexts;
|
||||
}
|
||||
|
||||
void UAVGadgetMode::grabUAVGadgetManager(Core::IMode *mode)
|
||||
{
|
||||
if (mode != this)
|
||||
return;
|
||||
|
||||
if (m_uavGadgetManager->currentGadget())
|
||||
m_uavGadgetManager->currentGadget()->widget()->setFocus();
|
||||
}
|
@ -1,87 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file uavgadgetmode.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup CorePlugin Core Plugin
|
||||
* @{
|
||||
* @brief The Core GCS 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 UAVGADGETMODE_H
|
||||
#define UAVGADGETMODE_H
|
||||
|
||||
#include <coreplugin/imode.h>
|
||||
|
||||
#include <QtCore/QObject>
|
||||
#include <QtGui/QIcon>
|
||||
|
||||
QT_BEGIN_NAMESPACE
|
||||
class QSplitter;
|
||||
class QWidget;
|
||||
class QIcon;
|
||||
class QVBoxLayout;
|
||||
QT_END_NAMESPACE
|
||||
|
||||
namespace Core {
|
||||
|
||||
class UAVGadgetManager;
|
||||
|
||||
namespace Internal {
|
||||
|
||||
class UAVGadgetMode : public Core::IMode
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
UAVGadgetMode(UAVGadgetManager *uavGadgetManager, QString name, QIcon icon, int priority, QString uniqueName);
|
||||
~UAVGadgetMode();
|
||||
|
||||
// IMode
|
||||
QString name() const;
|
||||
QIcon icon() const;
|
||||
int priority() const;
|
||||
QWidget* widget();
|
||||
const char* uniqueModeName() const;
|
||||
QList<int> context() const;
|
||||
UAVGadgetManager* uavGadgetManager() const { return m_uavGadgetManager; }
|
||||
void setName(QString name);
|
||||
void setIcon(QIcon icon);
|
||||
|
||||
private slots:
|
||||
void grabUAVGadgetManager(Core::IMode *mode);
|
||||
|
||||
private:
|
||||
UAVGadgetManager *m_uavGadgetManager;
|
||||
QString m_name;
|
||||
QIcon m_icon;
|
||||
QWidget *m_widget;
|
||||
int m_priority;
|
||||
QVBoxLayout *m_layout;
|
||||
QString m_uniqueName;
|
||||
QByteArray m_uniqueNameBA;
|
||||
const char *m_uniqueNameC;
|
||||
};
|
||||
|
||||
} // namespace Internal
|
||||
} // namespace Core
|
||||
|
||||
#endif // UAVGADGETMODE_H
|
@ -1,119 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file viewmanager.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup CorePlugin Core Plugin
|
||||
* @{
|
||||
* @brief The Core GCS 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 "viewmanager.h"
|
||||
|
||||
#include "coreconstants.h"
|
||||
#include "mainwindow.h"
|
||||
#include "uniqueidmanager.h"
|
||||
#include "iview.h"
|
||||
|
||||
#include <coreplugin/actionmanager/actionmanager.h>
|
||||
#include <coreplugin/actionmanager/command.h>
|
||||
#include <aggregation/aggregate.h>
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
|
||||
#include <QtCore/QSettings>
|
||||
#include <QtGui/QHBoxLayout>
|
||||
#include <QtGui/QLabel>
|
||||
#include <QtGui/QStatusBar>
|
||||
|
||||
using namespace Core;
|
||||
using namespace Core::Internal;
|
||||
|
||||
ViewManager::ViewManager(MainWindow *mainWnd)
|
||||
: QObject(mainWnd),
|
||||
m_mainWnd(mainWnd)
|
||||
{
|
||||
for (int i = 0; i < 3; ++i) {
|
||||
QWidget *w = new QWidget();
|
||||
m_mainWnd->statusBar()->insertPermanentWidget(i, w);
|
||||
w->setLayout(new QHBoxLayout);
|
||||
w->setVisible(true);
|
||||
w->layout()->setMargin(0);
|
||||
m_statusBarWidgets.append(w);
|
||||
}
|
||||
QLabel *l = new QLabel();
|
||||
m_mainWnd->statusBar()->insertPermanentWidget(3, l, 1);
|
||||
}
|
||||
|
||||
ViewManager::~ViewManager()
|
||||
{
|
||||
}
|
||||
|
||||
void ViewManager::init()
|
||||
{
|
||||
connect(ExtensionSystem::PluginManager::instance(), SIGNAL(objectAdded(QObject*)),
|
||||
this, SLOT(objectAdded(QObject*)));
|
||||
connect(ExtensionSystem::PluginManager::instance(), SIGNAL(aboutToRemoveObject(QObject*)),
|
||||
this, SLOT(aboutToRemoveObject(QObject*)));
|
||||
}
|
||||
|
||||
void ViewManager::objectAdded(QObject *obj)
|
||||
{
|
||||
IView *view = Aggregation::query<IView>(obj);
|
||||
if (!view)
|
||||
return;
|
||||
|
||||
QWidget *viewWidget = 0;
|
||||
viewWidget = view->widget();
|
||||
m_statusBarWidgets.at(view->defaultPosition())->layout()->addWidget(viewWidget);
|
||||
|
||||
m_viewMap.insert(view, viewWidget);
|
||||
viewWidget->setObjectName(view->uniqueViewName());
|
||||
m_mainWnd->addContextObject(view);
|
||||
}
|
||||
|
||||
void ViewManager::aboutToRemoveObject(QObject *obj)
|
||||
{
|
||||
IView *view = Aggregation::query<IView>(obj);
|
||||
if (!view)
|
||||
return;
|
||||
m_mainWnd->removeContextObject(view);
|
||||
}
|
||||
|
||||
void ViewManager::readSettings(QSettings *settings)
|
||||
{
|
||||
m_mainWnd->restoreState(settings->value(QLatin1String("ViewGroup_Default"), QByteArray()).toByteArray());
|
||||
}
|
||||
|
||||
void ViewManager::saveSettings(QSettings *settings)
|
||||
{
|
||||
settings->setValue(QLatin1String("ViewGroup_Default"), m_mainWnd->saveState());
|
||||
}
|
||||
|
||||
IView *ViewManager::view(const QString &id)
|
||||
{
|
||||
QList<IView *> list =
|
||||
ExtensionSystem::PluginManager::instance()->getObjects<IView>();
|
||||
foreach (IView *view, list) {
|
||||
if (view->uniqueViewName() == id)
|
||||
return view;
|
||||
}
|
||||
return 0;
|
||||
}
|
@ -1,79 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file viewmanager.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup CorePlugin Core Plugin
|
||||
* @{
|
||||
* @brief The Core GCS 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 VIEWMANAGER_H
|
||||
#define VIEWMANAGER_H
|
||||
|
||||
#include <QtCore/QMap>
|
||||
#include <QtGui/QWidget>
|
||||
|
||||
QT_BEGIN_NAMESPACE
|
||||
class QAction;
|
||||
class QSettings;
|
||||
class QMainWindow;
|
||||
class QComboBox;
|
||||
class QStackedWidget;
|
||||
QT_END_NAMESPACE
|
||||
|
||||
namespace Core {
|
||||
|
||||
class IView;
|
||||
|
||||
namespace Internal {
|
||||
|
||||
class MainWindow;
|
||||
class NavigationWidget;
|
||||
|
||||
class ViewManager : public QObject
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
ViewManager(MainWindow *mainWnd);
|
||||
~ViewManager();
|
||||
|
||||
void init();
|
||||
void readSettings(QSettings *settings);
|
||||
void saveSettings(QSettings *settings);
|
||||
|
||||
IView * view(const QString & id);
|
||||
private slots:
|
||||
void objectAdded(QObject *obj);
|
||||
void aboutToRemoveObject(QObject *obj);
|
||||
|
||||
private:
|
||||
QMap<Core::IView *, QWidget *> m_viewMap;
|
||||
|
||||
MainWindow *m_mainWnd;
|
||||
QList<QWidget *> m_statusBarWidgets;
|
||||
};
|
||||
|
||||
} // namespace Internal
|
||||
} // namespace Core
|
||||
|
||||
#endif // VIEWMANAGER_H
|
@ -28,7 +28,7 @@
|
||||
#include "workspacesettings.h"
|
||||
#include <coreplugin/icore.h>
|
||||
#include <coreplugin/modemanager.h>
|
||||
#include <coreplugin/uavgadgetmode.h>
|
||||
#include <coreplugin/uavgadgetmanager/uavgadgetmanager.h>
|
||||
#include <QtCore/QSettings>
|
||||
|
||||
#include "ui_workspacesettings.h"
|
||||
@ -95,26 +95,37 @@ QWidget *WorkspaceSettings::createPage(QWidget *parent)
|
||||
m_currentIndex = 0;
|
||||
selectWorkspace(m_currentIndex);
|
||||
|
||||
if (0 <= m_tabBarPlacementIndex && m_tabBarPlacementIndex < m_page->comboBoxTabBarPlacement->count())
|
||||
m_page->comboBoxTabBarPlacement->setCurrentIndex(m_tabBarPlacementIndex);
|
||||
m_page->checkBoxAllowTabMovement->setChecked(m_allowTabBarMovement);
|
||||
|
||||
return w;
|
||||
}
|
||||
|
||||
void WorkspaceSettings::readSettings(QSettings* qs)
|
||||
{
|
||||
m_iconNames.clear();
|
||||
m_names.clear();
|
||||
m_iconNames.clear();
|
||||
m_modeNames.clear();
|
||||
|
||||
qs->beginGroup(QLatin1String("Workspace"));
|
||||
m_numberOfWorkspaces = qs->value(QLatin1String("NumberOfWorkspaces"), 2).toInt();
|
||||
m_previousNumberOfWorkspaces = m_numberOfWorkspaces;
|
||||
for (int i = 1; i <= MAX_WORKSPACES; ++i) {
|
||||
QString numberString = QString::number(i);
|
||||
QString defaultName = "Workspace" + numberString;
|
||||
QString defaultIconName = "Icon" + numberString;
|
||||
const QString name = qs->value(defaultName, defaultName).toString();
|
||||
const QString iconName = qs->value(defaultIconName, ":/core/images/openpilot_logo_64.png").toString();
|
||||
m_iconNames.append(iconName);
|
||||
QString name = qs->value(defaultName, defaultName).toString();
|
||||
QString iconName = qs->value(defaultIconName, ":/core/images/openpilot_logo_64.png").toString();
|
||||
m_names.append(name);
|
||||
m_iconNames.append(iconName);
|
||||
m_modeNames.append(QString("Mode")+ QString::number(i));
|
||||
}
|
||||
m_tabBarPlacementIndex = qs->value(QLatin1String("TabBarPlacementIndex"), 1).toInt(); // 1 == "Bottom"
|
||||
m_allowTabBarMovement = qs->value(QLatin1String("AllowTabBarMovement"), false).toBool();
|
||||
qs->endGroup();
|
||||
QTabWidget::TabPosition pos = m_tabBarPlacementIndex == 0 ? QTabWidget::North : QTabWidget::South;
|
||||
emit tabBarSettingsApplied(pos, m_allowTabBarMovement);
|
||||
}
|
||||
|
||||
void WorkspaceSettings::saveSettings(QSettings* qs)
|
||||
@ -122,12 +133,16 @@ void WorkspaceSettings::saveSettings(QSettings* qs)
|
||||
qs->beginGroup(QLatin1String("Workspace"));
|
||||
qs->setValue(QLatin1String("NumberOfWorkspaces"), m_numberOfWorkspaces);
|
||||
for (int i = 0; i < MAX_WORKSPACES; ++i) {
|
||||
QString mode = QString("Mode")+ QString::number(i+1);
|
||||
int j = m_modeNames.indexOf(mode);
|
||||
QString numberString = QString::number(i+1);
|
||||
QString defaultName = "Workspace" + numberString;
|
||||
QString defaultIconName = "Icon" + numberString;
|
||||
qs->setValue(defaultName, m_names.at(i));
|
||||
qs->setValue(defaultIconName, m_iconNames.at(i));
|
||||
qs->setValue(defaultName, m_names.at(j));
|
||||
qs->setValue(defaultIconName, m_iconNames.at(j));
|
||||
}
|
||||
qs->setValue(QLatin1String("TabBarPlacementIndex"), m_tabBarPlacementIndex);
|
||||
qs->setValue(QLatin1String("AllowTabBarMovement"), m_allowTabBarMovement);
|
||||
qs->endGroup();
|
||||
}
|
||||
|
||||
@ -137,15 +152,23 @@ void WorkspaceSettings::apply()
|
||||
|
||||
saveSettings(Core::ICore::instance()->settings());
|
||||
|
||||
if (m_numberOfWorkspaces != m_previousNumberOfWorkspaces) {
|
||||
Core::ICore::instance()->readMainSettings(Core::ICore::instance()->settings(), true);
|
||||
m_previousNumberOfWorkspaces = m_numberOfWorkspaces;
|
||||
}
|
||||
|
||||
ModeManager* modeManager = Core::ICore::instance()->modeManager();
|
||||
for (int i = 0; i < MAX_WORKSPACES; ++i) {
|
||||
Core::Internal::UAVGadgetMode *mode =
|
||||
qobject_cast<Core::Internal::UAVGadgetMode*>(modeManager->mode(modeName(i)));
|
||||
IMode *baseMode = modeManager->mode(modeName(i));
|
||||
Core::UAVGadgetManager *mode = qobject_cast<Core::UAVGadgetManager*>(baseMode);
|
||||
if (mode) {
|
||||
modeManager->updateModeNameIcon(mode, QIcon(iconName(i)), name(i));
|
||||
}
|
||||
}
|
||||
|
||||
m_tabBarPlacementIndex = m_page->comboBoxTabBarPlacement->currentIndex();
|
||||
m_allowTabBarMovement = m_page->checkBoxAllowTabMovement->isChecked();
|
||||
QTabWidget::TabPosition pos = m_tabBarPlacementIndex == 0 ? QTabWidget::North : QTabWidget::South;
|
||||
emit tabBarSettingsApplied(pos, m_allowTabBarMovement);
|
||||
}
|
||||
|
||||
void WorkspaceSettings::finish()
|
||||
@ -186,8 +209,8 @@ void WorkspaceSettings::selectWorkspace(int index, bool store)
|
||||
// write old values of workspace not shown anymore
|
||||
m_iconNames.replace(m_currentIndex, m_page->iconPathChooser->path());
|
||||
m_names.replace(m_currentIndex, m_page->nameEdit->text());
|
||||
m_page->workspaceComboBox->setItemIcon(m_currentIndex, QIcon(m_page->iconPathChooser->path()));
|
||||
m_page->workspaceComboBox->setItemText(m_currentIndex, m_page->nameEdit->text());
|
||||
m_page->workspaceComboBox->setItemIcon(m_currentIndex, QIcon(m_iconNames.at(m_currentIndex)));
|
||||
m_page->workspaceComboBox->setItemText(m_currentIndex, m_names.at(m_currentIndex));
|
||||
}
|
||||
|
||||
// display current workspace
|
||||
@ -196,3 +219,34 @@ void WorkspaceSettings::selectWorkspace(int index, bool store)
|
||||
m_page->nameEdit->setText(m_names.at(index));
|
||||
m_currentIndex = index;
|
||||
}
|
||||
|
||||
void WorkspaceSettings::newModeOrder(QVector<IMode*> modes)
|
||||
{
|
||||
QList<int> priorities;
|
||||
QStringList modeNames;
|
||||
for (int i = 0; i < modes.count(); ++i) {
|
||||
Core::UAVGadgetManager *mode = qobject_cast<Core::UAVGadgetManager*>(modes.at(i));
|
||||
if (mode) {
|
||||
priorities.append(mode->priority());
|
||||
modeNames.append(mode->uniqueModeName());
|
||||
}
|
||||
}
|
||||
// Bubble sort
|
||||
bool swapped = false;
|
||||
do {
|
||||
swapped = false;
|
||||
for (int i = 0; i < m_names.count()-1; ++i) {
|
||||
int j = i+1;
|
||||
int p = modeNames.indexOf(m_modeNames.at(i));
|
||||
int q = modeNames.indexOf(m_modeNames.at(j));
|
||||
bool nonShowingMode = (p == -1 && q >=0);
|
||||
bool pqBothFound = (p >= 0 && q >= 0);
|
||||
if (nonShowingMode || (pqBothFound && (priorities.at(q) > priorities.at(p)))) {
|
||||
m_names.swap(i, j);
|
||||
m_iconNames.swap(i, j);
|
||||
m_modeNames.swap(i, j);
|
||||
swapped = true;
|
||||
}
|
||||
}
|
||||
} while (swapped);
|
||||
}
|
||||
|
@ -31,12 +31,14 @@
|
||||
#include <coreplugin/dialogs/ioptionspage.h>
|
||||
#include <QtCore/QObject>
|
||||
#include <QtCore/QStringList>
|
||||
#include <QtGui/QTabWidget>
|
||||
|
||||
class QSettings;
|
||||
|
||||
namespace Core {
|
||||
|
||||
class ModeManager;
|
||||
class IMode;
|
||||
|
||||
namespace Internal {
|
||||
|
||||
@ -65,24 +67,29 @@ public:
|
||||
int numberOfWorkspaces() const { return m_numberOfWorkspaces;}
|
||||
QString iconName(int i) const { return m_iconNames.at(i);}
|
||||
QString name(int i) const { return m_names.at(i);}
|
||||
QString modeName(int i) const { return QString("Mode")+ QString::number(i+1);}
|
||||
QString modeName(int i) const { return m_modeNames.at(i);}
|
||||
|
||||
signals:
|
||||
void tabBarSettingsApplied(QTabWidget::TabPosition pos, bool movable);
|
||||
|
||||
public slots:
|
||||
void selectWorkspace(int index, bool store = false);
|
||||
void numberOfWorkspacesChanged(int value);
|
||||
void textEdited(QString string);
|
||||
void iconChanged();
|
||||
void newModeOrder(QVector<IMode*> modes);
|
||||
|
||||
private:
|
||||
Ui::WorkspaceSettings *m_page;
|
||||
QStringList m_iconNames;
|
||||
QStringList m_names;
|
||||
QStringList m_modeNames;
|
||||
int m_currentIndex;
|
||||
int m_previousNumberOfWorkspaces;
|
||||
int m_numberOfWorkspaces;
|
||||
int m_tabBarPlacementIndex;
|
||||
bool m_allowTabBarMovement;
|
||||
static const int MAX_WORKSPACES;
|
||||
|
||||
|
||||
};
|
||||
|
||||
} // namespace Internal
|
||||
|
@ -6,7 +6,7 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>400</width>
|
||||
<width>414</width>
|
||||
<height>320</height>
|
||||
</rect>
|
||||
</property>
|
||||
@ -145,11 +145,71 @@ p, li { white-space: pre-wrap; }
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Note:</span> A restart is needed for changes to number of workspaces to take effect.</p></body></html></string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Sans'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Note:</span> A restart is needed for changes to number of workspaces to take effect.</p></body></html></string>
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_3">
|
||||
<property name="title">
|
||||
<string>Workspace panel</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="text">
|
||||
<string>Placement:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<widget class="QComboBox" name="comboBoxTabBarPlacement">
|
||||
<property name="currentIndex">
|
||||
<number>1</number>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Top</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>Bottom</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_7">
|
||||
<property name="text">
|
||||
<string>Allow reordering:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QCheckBox" name="checkBoxAllowTabMovement">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
|
@ -478,13 +478,13 @@ void DialGadgetWidget::setDialFont(QString fontProps)
|
||||
// this enables smooth rotation in rotateNeedles below
|
||||
void DialGadgetWidget::setNeedle1(double value) {
|
||||
if (rotateN1) {
|
||||
needle1Target = 360*(value*n1Factor-n1MinValue)/(n1MaxValue-n1MinValue);
|
||||
needle1Target = 360*(value*n1Factor)/(n1MaxValue-n1MinValue);
|
||||
}
|
||||
if (horizN1) {
|
||||
needle1Target = (value*n1Factor-n1MinValue)/(n1MaxValue-n1MinValue);
|
||||
needle1Target = (value*n1Factor)/(n1MaxValue-n1MinValue);
|
||||
}
|
||||
if (vertN1) {
|
||||
needle1Target = (value*n1Factor-n1MinValue)/(n1MaxValue-n1MinValue);
|
||||
needle1Target = (value*n1Factor)/(n1MaxValue-n1MinValue);
|
||||
}
|
||||
if (!dialTimer.isActive())
|
||||
dialTimer.start();
|
||||
@ -497,13 +497,13 @@ void DialGadgetWidget::setNeedle1(double value) {
|
||||
|
||||
void DialGadgetWidget::setNeedle2(double value) {
|
||||
if (rotateN2) {
|
||||
needle2Target = 360*(value*n2Factor-n2MinValue)/(n2MaxValue-n2MinValue);
|
||||
needle2Target = 360*(value*n2Factor)/(n2MaxValue-n2MinValue);
|
||||
}
|
||||
if (horizN2) {
|
||||
needle2Target = (value*n2Factor-n2MinValue)/(n2MaxValue-n2MinValue);
|
||||
needle2Target = (value*n2Factor)/(n2MaxValue-n2MinValue);
|
||||
}
|
||||
if (vertN2) {
|
||||
needle2Target = (value*n2Factor-n2MinValue)/(n2MaxValue-n2MinValue);
|
||||
needle2Target = (value*n2Factor)/(n2MaxValue-n2MinValue);
|
||||
}
|
||||
if (!dialTimer.isActive())
|
||||
dialTimer.start();
|
||||
@ -517,13 +517,13 @@ void DialGadgetWidget::setNeedle2(double value) {
|
||||
|
||||
void DialGadgetWidget::setNeedle3(double value) {
|
||||
if (rotateN3) {
|
||||
needle3Target = 360*(value*n3Factor-n3MinValue)/(n3MaxValue-n3MinValue);
|
||||
needle3Target = 360*(value*n3Factor)/(n3MaxValue-n3MinValue);
|
||||
}
|
||||
if (horizN3) {
|
||||
needle3Target = (value*n3Factor-n3MinValue)/(n3MaxValue-n3MinValue);
|
||||
needle3Target = (value*n3Factor)/(n3MaxValue-n3MinValue);
|
||||
}
|
||||
if (vertN3) {
|
||||
needle3Target = (value*n3Factor-n3MinValue)/(n3MaxValue-n3MinValue);
|
||||
needle3Target = (value*n3Factor)/(n3MaxValue-n3MinValue);
|
||||
}
|
||||
if (!dialTimer.isActive())
|
||||
dialTimer.start();
|
||||
|
@ -1,3 +1,3 @@
|
||||
include(ipconnection_dependencies.pri)
|
||||
|
||||
LIBS *= -l$$qtLibraryTarget(IPconnection)
|
||||
LIBS *= -l$$qtLibraryName(IPconnection)
|
||||
|
@ -76,11 +76,10 @@ QIODevice* LoggingConnection::openDevice(const QString &deviceName)
|
||||
if (logFile.isOpen()){
|
||||
logFile.close();
|
||||
}
|
||||
QFileDialog * fd = new QFileDialog();
|
||||
fd->setAcceptMode(QFileDialog::AcceptOpen);
|
||||
fd->setNameFilter("OpenPilot Log (*.opl)");
|
||||
connect(fd, SIGNAL(fileSelected(QString)), this, SLOT(startReplay(QString)));
|
||||
fd->exec();
|
||||
QString fileName = QFileDialog::getOpenFileName(NULL, tr("Open file"), QString(""), tr("OpenPilot Log (*.opl)"));
|
||||
if (!fileName.isNull()) {
|
||||
startReplay(fileName);
|
||||
}
|
||||
return &logFile;
|
||||
}
|
||||
|
||||
|
@ -291,16 +291,12 @@ void ModelViewGadgetWidget::updateAttitude()
|
||||
{
|
||||
AttitudeActual::DataFields data = attActual->getData(); // get attitude data
|
||||
GLC_StructOccurence* rootObject= m_World.rootOccurence(); // get the full 3D model
|
||||
// create quaternions rotations for each axis
|
||||
QQuaternion qX= QQuaternion::fromAxisAndAngle(QVector3D(1,0,0),data.Pitch);
|
||||
QQuaternion qY= QQuaternion::fromAxisAndAngle(QVector3D(0,1,0),data.Roll);
|
||||
QQuaternion qZ= QQuaternion::fromAxisAndAngle(QVector3D(0,0,1),data.Yaw);
|
||||
QQuaternion quat= qX * qY * qZ; // create the quaternion of all the rotations
|
||||
// pass values to simpler variables
|
||||
double x= quat.vector().x();
|
||||
double y= quat.vector().y();
|
||||
double z= quat.vector().z();
|
||||
double w= quat.scalar();
|
||||
double x= data.q3;
|
||||
double y= data.q2;
|
||||
double z= data.q4;
|
||||
double w= data.q1;
|
||||
if (w == 0.0)
|
||||
w = 1.0;
|
||||
// create and gives the product of 2 4x4 matrices to get the rotation of the 3D model's matrix
|
||||
QMatrix4x4 m1;
|
||||
m1.setRow(0, QVector4D(w,z,-y,x));
|
||||
|
@ -70,6 +70,12 @@ plugin_modelview.subdir = modelview
|
||||
plugin_modelview.depends = plugin_coreplugin
|
||||
plugin_modelview.depends += plugin_uavobjects
|
||||
SUBDIRS += plugin_modelview
|
||||
|
||||
#Notify gadget
|
||||
plugin_notify.subdir = notify
|
||||
plugin_notify.depends = plugin_coreplugin
|
||||
plugin_notify.depends += plugin_uavobjects
|
||||
SUBDIRS += plugin_notify
|
||||
}
|
||||
|
||||
#Uploader gadget
|
||||
@ -97,12 +103,6 @@ plugin_systemhealth.depends = plugin_coreplugin
|
||||
plugin_systemhealth.depends += plugin_uavobjects
|
||||
SUBDIRS += plugin_systemhealth
|
||||
|
||||
#Notify gadget
|
||||
plugin_notify.subdir = notify
|
||||
plugin_notify.depends = plugin_coreplugin
|
||||
plugin_notify.depends += plugin_uavobjects
|
||||
SUBDIRS += plugin_notify
|
||||
|
||||
#Config gadget
|
||||
plugin_config.subdir = config
|
||||
plugin_config.depends = plugin_coreplugin
|
||||
|
@ -1,3 +1,3 @@
|
||||
include(rawhid_dependencies.pri)
|
||||
|
||||
LIBS *= -l$$qtLibraryTarget(RawHID)
|
||||
LIBS *= -l$$qtLibraryName(RawHID)
|
||||
|
@ -1,3 +1,3 @@
|
||||
include(scope_dependencies.pri)
|
||||
|
||||
LIBS *= -l$$qtLibraryTarget(ScopeGadget)
|
||||
include(scope_dependencies.pri)
|
||||
|
||||
LIBS *= -l$$qtLibraryName(ScopeGadget)
|
||||
|
@ -1,3 +1,3 @@
|
||||
include(serial_dependencies.pri)
|
||||
|
||||
LIBS *= -l$$qtLibraryTarget(Serial)
|
||||
LIBS *= -l$$qtLibraryName(Serial)
|
||||
|
@ -1,6 +1,6 @@
|
||||
include(uavobjects_dependencies.pri)
|
||||
|
||||
# Add the include path to the built-in uavobject include files.
|
||||
INCLUDEPATH += $$PWD
|
||||
|
||||
LIBS *= -l$$qtLibraryTarget(UAVObjects)
|
||||
include(uavobjects_dependencies.pri)
|
||||
|
||||
# Add the include path to the built-in uavobject include files.
|
||||
INCLUDEPATH += $$PWD
|
||||
|
||||
LIBS *= -l$$qtLibraryName(UAVObjects)
|
||||
|
@ -1,6 +1,6 @@
|
||||
include(uavobjectutil_dependencies.pri)
|
||||
|
||||
# Add the include path to the built-in uavobject include files.
|
||||
INCLUDEPATH += $$PWD
|
||||
|
||||
LIBS *= -l$$qtLibraryTarget(UAVObjectUtil)
|
||||
include(uavobjectutil_dependencies.pri)
|
||||
|
||||
# Add the include path to the built-in uavobject include files.
|
||||
INCLUDEPATH += $$PWD
|
||||
|
||||
LIBS *= -l$$qtLibraryName(UAVObjectUtil)
|
||||
|
@ -1,3 +1,3 @@
|
||||
include(uavtalk_dependencies.pri)
|
||||
|
||||
LIBS *= -l$$qtLibraryTarget(UAVTalk)
|
||||
include(uavtalk_dependencies.pri)
|
||||
|
||||
LIBS *= -l$$qtLibraryName(UAVTalk)
|
||||
|
@ -1,3 +1,3 @@
|
||||
include(welcome_dependencies.pri)
|
||||
|
||||
LIBS *= -l$$qtLibraryTarget(Welcome)
|
||||
LIBS *= -l$$qtLibraryName(Welcome)
|
||||
|
@ -77,7 +77,8 @@ WelcomeModePrivate::WelcomeModePrivate()
|
||||
|
||||
// --- WelcomeMode
|
||||
WelcomeMode::WelcomeMode() :
|
||||
m_d(new WelcomeModePrivate)
|
||||
m_d(new WelcomeModePrivate),
|
||||
m_priority(Core::Constants::P_MODE_WELCOME)
|
||||
{
|
||||
m_d->m_widget = new QWidget;
|
||||
QVBoxLayout *l = new QVBoxLayout(m_d->m_widget);
|
||||
@ -122,7 +123,7 @@ QIcon WelcomeMode::icon() const
|
||||
|
||||
int WelcomeMode::priority() const
|
||||
{
|
||||
return Core::Constants::P_MODE_WELCOME;
|
||||
return m_priority;
|
||||
}
|
||||
|
||||
QWidget* WelcomeMode::widget()
|
||||
|
@ -61,6 +61,7 @@ public:
|
||||
void activated();
|
||||
QString contextHelpId() const { return QLatin1String("OpenPilot GCS"); }
|
||||
void initPlugins();
|
||||
void setPriority(int priority) { m_priority = priority; }
|
||||
|
||||
private slots:
|
||||
void slotFeedback();
|
||||
@ -69,6 +70,7 @@ private slots:
|
||||
|
||||
private:
|
||||
WelcomeModePrivate *m_d;
|
||||
int m_priority;
|
||||
};
|
||||
|
||||
} // namespace Welcome
|
||||
|
Binary file not shown.
@ -3,7 +3,12 @@
|
||||
APP="${1?}"
|
||||
PLUGINS="${APP}/Contents/Plugins"
|
||||
OP_PLUGINS="${APP}/Contents/Plugins/OpenPilot"
|
||||
QT_LIBS="QtGui QtCore QtSvg QtSql QtOpenGL QtNetwork QtXml QtDBus QtScript phonon SDL"
|
||||
QT_LIBS="QtGui QtTest QtCore QtSvg QtSql QtOpenGL QtNetwork QtXml QtDBus QtScript phonon"
|
||||
QT_DIR=$(otool -L "${APP}/Contents/MacOS/OpenPilot GCS" | sed -n -e 's/\/QtCore\.framework.*//p' | sed -n -E 's:^.::p')
|
||||
QT_EXTRA="accessible/libqtaccessiblewidgets.dylib bearer/libqgenericbearer.dylib codecs/libqcncodecs.dylib codecs/libqjpcodecs.dylib codecs/libqkrcodecs.dylib codecs/libqtwcodecs.dylib graphicssystems/libqtracegraphicssystem.dylib imageformats/libqgif.dylib imageformats/libqico.dylib imageformats/libqjpeg.dylib imageformats/libqmng.dylib imageformats/libqtiff.dylib qmltooling/libqmldbg_inspector.dylib qmltooling/libqmldbg_tcp.dylib"
|
||||
|
||||
|
||||
echo "Qt library directory is \"${QT_DIR}\""
|
||||
|
||||
echo "Processing Qt libraries in $1"
|
||||
macdeployqt "${APP}"
|
||||
@ -13,7 +18,7 @@ do
|
||||
for g in $QT_LIBS
|
||||
do
|
||||
install_name_tool -change \
|
||||
${g}.framework/Versions/4/${g} \
|
||||
"${QT_DIR}/${g}.framework/Versions/4/${g}" \
|
||||
@executable_path/../Frameworks/${g}.framework/Versions/4/${g} \
|
||||
"${f}"
|
||||
done
|
||||
@ -24,23 +29,41 @@ done
|
||||
for f in ${QT_LIBS}
|
||||
do
|
||||
echo "Copying ${f}"
|
||||
cp -r /Library/Frameworks/${f}.framework "${APP}/Contents/Frameworks/"
|
||||
cp -r "${QT_DIR}/${f}.framework" "${APP}/Contents/Frameworks/"
|
||||
|
||||
echo "Changing package identification of ${f}"
|
||||
install_name_tool -id \
|
||||
@executable_path/../Frameworks/${f}.framework/Versions/4/QtCore \
|
||||
@executable_path/../Frameworks/${f}.framework/Versions/4/${f} \
|
||||
"${APP}/Contents/Frameworks/${f}.framework/Versions/4/${f}"
|
||||
|
||||
rm "${APP}/Contents/Frameworks/${f}.framework/${f}"
|
||||
|
||||
echo "Changing package linkages"
|
||||
for g in $QT_LIBS
|
||||
do
|
||||
install_name_tool -change \
|
||||
${g}.framework/Versions/4/${g} \
|
||||
"${QT_DIR}/${g}.framework/Versions/4/${g}" \
|
||||
@executable_path/../Frameworks/${g}.framework/Versions/4/${g} \
|
||||
"${APP}/Contents/Frameworks/${f}.framework/Versions/4/${f}"
|
||||
done
|
||||
done
|
||||
|
||||
for f in ${QT_EXTRA}
|
||||
do
|
||||
echo "Changing package identification of ${f}"
|
||||
install_name_tool -id \
|
||||
@executable_path/../Plugins/${f} \
|
||||
"${PLUGINS}/${f}"
|
||||
done
|
||||
|
||||
echo "Copying SDL"
|
||||
cp -r "/Library/Frameworks/SDL.framework" "${APP}/Contents/Frameworks/"
|
||||
|
||||
echo "Changing package identification of SDL"
|
||||
install_name_tool -id \
|
||||
@executable_path/../Frameworks/SDL.framework/Versions/A/SDL \
|
||||
"${APP}/Contents/Frameworks/SDL.framework/Versions/A/SDL"
|
||||
|
||||
# deleting unnecessary files
|
||||
echo "Deleting unnecessary files"
|
||||
find "${APP}/Contents/Frameworks" -iname "current" -exec rm -rf \{\} \;
|
||||
|
@ -23,10 +23,15 @@ cp -r "${APP_PATH}" "/Volumes/${VOL_NAME}"
|
||||
#cp -r "${FW_DIR}" "/Volumes/${VOL_NAME}/firmware"
|
||||
cp "${FW_DIR}/fw_coptercontrol-${PACKAGE_LBL}.opfw" "/Volumes/${VOL_NAME}/firmware"
|
||||
|
||||
cp "${ROOT_DIR}/HISTORY.txt" "/Volumes/${VOL_NAME}"
|
||||
|
||||
"${ROOT_DIR}/package/osx/libraries" \
|
||||
"/Volumes/${VOL_NAME}/OpenPilot GCS.app" || exit 1
|
||||
|
||||
hdiutil detach ${device}
|
||||
|
||||
echo "Resizing dmg"
|
||||
hdiutil resize -size 250m ${TEMP_FILE}
|
||||
hdiutil convert "${TEMP_FILE}" -format UDZO -o "${OUT_FILE}"
|
||||
|
||||
# cleanup
|
||||
|
@ -33,6 +33,7 @@
|
||||
; Paths
|
||||
|
||||
; Tree root locations (relative to this script location)
|
||||
!define PROJECT_ROOT "..\.."
|
||||
!define NSIS_DATA_TREE "."
|
||||
!define GCS_BUILD_TREE "..\..\build\ground\openpilotgcs"
|
||||
|
||||
@ -151,6 +152,8 @@ Section "Core files" InSecCore
|
||||
SectionIn RO
|
||||
SetOutPath "$INSTDIR\bin"
|
||||
File /r "${GCS_BUILD_TREE}\bin\*"
|
||||
SetOutPath "$INSTDIR"
|
||||
File "${PROJECT_ROOT}\HISTORY.txt"
|
||||
SectionEnd
|
||||
|
||||
Section "Plugins" InSecPlugins
|
||||
@ -197,6 +200,14 @@ Section "Shortcuts" InSecShortcuts
|
||||
CreateDirectory "$SMPROGRAMS\OpenPilot"
|
||||
CreateShortCut "$SMPROGRAMS\OpenPilot\OpenPilot GCS.lnk" "$INSTDIR\bin\openpilotgcs.exe" \
|
||||
"" "$INSTDIR\bin\openpilotgcs.exe" 0 "" "" "${PRODUCT_NAME} ${PRODUCT_VERSION}. ${BUILD_DESCRIPTION}"
|
||||
CreateShortCut "$SMPROGRAMS\OpenPilot\OpenPilot ChangeLog.lnk" "$INSTDIR\HISTORY.txt" \
|
||||
"" "$INSTDIR\bin\openpilotgcs.exe" 0
|
||||
CreateShortCut "$SMPROGRAMS\OpenPilot\OpenPilot Website.lnk" "http://www.openpilot.org" \
|
||||
"" "$INSTDIR\bin\openpilotgcs.exe" 0
|
||||
CreateShortCut "$SMPROGRAMS\OpenPilot\OpenPilot Wiki.lnk" "http://wiki.openpilot.org" \
|
||||
"" "$INSTDIR\bin\openpilotgcs.exe" 0
|
||||
CreateShortCut "$SMPROGRAMS\OpenPilot\OpenPilot Forums.lnk" "http://forums.openpilot.org" \
|
||||
"" "$INSTDIR\bin\openpilotgcs.exe" 0
|
||||
CreateShortCut "$DESKTOP\OpenPilot GCS.lnk" "$INSTDIR\bin\openpilotgcs.exe" \
|
||||
"" "$INSTDIR\bin\openpilotgcs.exe" 0 "" "" "${PRODUCT_NAME} ${PRODUCT_VERSION}. ${BUILD_DESCRIPTION}"
|
||||
CreateShortCut "$SMPROGRAMS\OpenPilot\Uninstall.lnk" "$INSTDIR\Uninstall.exe" "" "$INSTDIR\Uninstall.exe" 0
|
||||
@ -247,6 +258,7 @@ Section "un.OpenPilot GCS" UnSecProgram
|
||||
RMDir /r /rebootok "$INSTDIR\lib"
|
||||
RMDir /r /rebootok "$INSTDIR\share"
|
||||
RMDir /r /rebootok "$INSTDIR\firmware"
|
||||
Delete /rebootok "$INSTDIR\HISTORY.txt"
|
||||
Delete /rebootok "$INSTDIR\Uninstall.exe"
|
||||
|
||||
; Remove directory
|
||||
|
@ -22,6 +22,8 @@
|
||||
<field name="WeakLevelingKp" units="(deg/s)/deg" type="float" elements="1" defaultvalue="0.1"/>
|
||||
<field name="MaxWeakLevelingRate" units="deg/s" type="uint8" elements="1" defaultvalue="5"/>
|
||||
|
||||
<field name="LowThrottleZeroIntegral" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user