1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-18 03:52:11 +01:00

Merge remote-tracking branch 'origin/next' into thread/OP-1763_CloudConfigs_outside_of_Wizard

This commit is contained in:
m_thread 2015-03-28 10:47:01 +01:00
commit 32e670b8f0
35 changed files with 626 additions and 271 deletions

View File

@ -792,18 +792,10 @@ PACKAGE_NAME := OpenPilot
PACKAGE_SEP := -
PACKAGE_FULL_NAME := $(PACKAGE_NAME)$(PACKAGE_SEP)$(PACKAGE_LBL)
# Source distribution is never dirty because it uses git archive
DIST_NAME := $(DIST_DIR)/$(subst dirty-,,$(PACKAGE_FULL_NAME)).tar
.PHONY: package
include $(ROOT_DIR)/package/$(UNAME).mk
package: all_fw all_ground uavobjects_matlab | $(PACKAGE_DIR)
ifneq ($(GCS_BUILD_CONF),release)
# We can only package release builds
$(error Packaging is currently supported for release builds only)
endif
# Source distribution is never dirty because it uses git archive
DIST_NAME := $(DIST_DIR)/$(subst dirty-,,$(PACKAGE_FULL_NAME)).tar
##############################
#

View File

@ -275,6 +275,12 @@ static void gpsTask(__attribute__((unused)) void *parameters)
ubx_autoconfig_run(&buffer, &count, status != GPSPOSITIONSENSOR_STATUS_NOGPS);
// Something to send?
if (count) {
// clear ack/nak
ubxLastAck.clsID = 0x00;
ubxLastAck.msgID = 0x00;
ubxLastNak.clsID = 0x00;
ubxLastNak.msgID = 0x00;
PIOS_COM_SendBuffer(gpsPort, (uint8_t *)buffer, count);
}
}
@ -479,6 +485,7 @@ void updateGpsSettings(__attribute__((unused)) UAVObjEvent *ev)
uint8_t ubxSbasMode;
ubx_autoconfig_settings_t newconfig;
uint8_t ubxSbasSats;
uint8_t ubxGnssMode;
GPSSettingsUbxRateGet(&newconfig.navRate);
@ -541,6 +548,41 @@ void updateGpsSettings(__attribute__((unused)) UAVObjEvent *ev)
ubxSbasSats == GPSSETTINGS_UBXSBASSATS_GAGAN ? UBX_SBAS_SATS_GAGAN :
ubxSbasSats == GPSSETTINGS_UBXSBASSATS_SDCM ? UBX_SBAS_SATS_SDCM : UBX_SBAS_SATS_AUTOSCAN;
GPSSettingsUbxGNSSModeGet(&ubxGnssMode);
switch (ubxGnssMode) {
case GPSSETTINGS_UBXGNSSMODE_GPSGLONASS:
newconfig.enableGPS = true;
newconfig.enableGLONASS = true;
newconfig.enableBeiDou = false;
break;
case GPSSETTINGS_UBXGNSSMODE_GLONASS:
newconfig.enableGPS = false;
newconfig.enableGLONASS = true;
newconfig.enableBeiDou = false;
break;
case GPSSETTINGS_UBXGNSSMODE_GPS:
newconfig.enableGPS = true;
newconfig.enableGLONASS = false;
newconfig.enableBeiDou = false;
break;
case GPSSETTINGS_UBXGNSSMODE_GPSBEIDOU:
newconfig.enableGPS = true;
newconfig.enableGLONASS = false;
newconfig.enableBeiDou = true;
break;
case GPSSETTINGS_UBXGNSSMODE_GLONASSBEIDOU:
newconfig.enableGPS = false;
newconfig.enableGLONASS = true;
newconfig.enableBeiDou = true;
break;
default:
newconfig.enableGPS = false;
newconfig.enableGLONASS = false;
newconfig.enableBeiDou = false;
break;
}
ubx_autoconfig_set(newconfig);
}
#endif /* if defined(PIOS_INCLUDE_GPS_UBX_PARSER) && !defined(PIOS_GPS_MINIMAL) */

View File

@ -107,7 +107,7 @@ struct UBX_ACK_NAK ubxLastNak;
#define UBX_PVT_TIMEOUT (1000)
// parse incoming character stream for messages in UBX binary format
int parse_ubx_stream(uint8_t *rx, uint8_t len, char *gps_rx_buffer, GPSPositionSensorData *GpsData, struct GPS_RX_STATS *gpsRxStats)
int parse_ubx_stream(uint8_t *rx, uint16_t len, char *gps_rx_buffer, GPSPositionSensorData *GpsData, struct GPS_RX_STATS *gpsRxStats)
{
int ret = PARSER_INCOMPLETE; // message not (yet) complete
enum proto_states {
@ -124,8 +124,8 @@ int parse_ubx_stream(uint8_t *rx, uint8_t len, char *gps_rx_buffer, GPSPositionS
};
uint8_t c;
static enum proto_states proto_state = START;
static uint8_t rx_count = 0;
struct UBXPacket *ubx = (struct UBXPacket *)gps_rx_buffer;
static uint16_t rx_count = 0;
struct UBXPacket *ubx = (struct UBXPacket *)gps_rx_buffer;
for (int i = 0; i < len; i++) {
c = rx[i];
@ -413,8 +413,10 @@ static void parse_ubx_nav_svinfo(struct UBXPacket *ubx, __attribute__((unused))
struct UBX_NAV_SVINFO *svinfo = &ubx->payload.nav_svinfo;
svdata.SatsInView = 0;
// First, use slots for SVs actually being received
for (chan = 0; chan < svinfo->numCh; chan++) {
if (svdata.SatsInView < GPSSATELLITES_PRN_NUMELEM) {
if (svdata.SatsInView < GPSSATELLITES_PRN_NUMELEM && svinfo->sv[chan].cno > 0) {
svdata.Azimuth[svdata.SatsInView] = svinfo->sv[chan].azim;
svdata.Elevation[svdata.SatsInView] = svinfo->sv[chan].elev;
svdata.PRN[svdata.SatsInView] = svinfo->sv[chan].svid;
@ -422,6 +424,18 @@ static void parse_ubx_nav_svinfo(struct UBXPacket *ubx, __attribute__((unused))
svdata.SatsInView++;
}
}
// Now try to add the rest
for (chan = 0; chan < svinfo->numCh; chan++) {
if (svdata.SatsInView < GPSSATELLITES_PRN_NUMELEM && 0 == svinfo->sv[chan].cno) {
svdata.Azimuth[svdata.SatsInView] = svinfo->sv[chan].azim;
svdata.Elevation[svdata.SatsInView] = svinfo->sv[chan].elev;
svdata.PRN[svdata.SatsInView] = svinfo->sv[chan].svid;
svdata.SNR[svdata.SatsInView] = svinfo->sv[chan].cno;
svdata.SatsInView++;
}
}
// fill remaining slots (if any)
for (chan = svdata.SatsInView; chan < GPSSATELLITES_PRN_NUMELEM; chan++) {
svdata.Azimuth[chan] = 0;

View File

@ -102,6 +102,7 @@ typedef enum {
UBX_ID_CFG_MSG = 0x01,
UBX_ID_CFG_CFG = 0x09,
UBX_ID_CFG_SBAS = 0x16,
UBX_ID_CFG_GNSS = 0x3E
} ubx_class_cfg_id;
typedef enum {
@ -310,7 +311,7 @@ struct UBX_NAV_SVINFO_SV {
};
// SV information message
#define MAX_SVS 16
#define MAX_SVS 32
struct UBX_NAV_SVINFO {
uint32_t iTOW; // GPS Millisecond Time of Week (ms)
@ -404,7 +405,7 @@ extern struct UBX_ACK_NAK ubxLastNak;
bool checksum_ubx_message(struct UBXPacket *);
uint32_t parse_ubx_message(struct UBXPacket *, GPSPositionSensorData *);
int parse_ubx_stream(uint8_t *rx, uint8_t len, char *, GPSPositionSensorData *, struct GPS_RX_STATS *);
int parse_ubx_stream(uint8_t *rx, uint16_t len, char *, GPSPositionSensorData *, struct GPS_RX_STATS *);
void load_mag_settings();
#endif /* UBX_H */

View File

@ -88,6 +88,10 @@ typedef struct {
int8_t navRate;
ubx_config_dynamicmodel_t dynamicModel;
bool enableGPS;
bool enableGLONASS;
bool enableBeiDou;
} ubx_autoconfig_settings_t;
// Mask for "all supported devices": battery backed RAM, Flash, EEPROM, SPI Flash
@ -164,6 +168,44 @@ typedef struct {
uint32_t scanmode1;
} __attribute__((packed)) ubx_cfg_sbas_t;
typedef enum {
UBX_GNSS_ID_GPS = 0,
UBX_GNSS_ID_SBAS = 1,
UBX_GNSS_ID_GALILEO = 2,
UBX_GNSS_ID_BEIDOU = 3,
UBX_GNSS_ID_IMES = 4,
UBX_GNSS_ID_QZSS = 5,
UBX_GNSS_ID_GLONASS = 6,
UBX_GNSS_ID_MAX
} ubx_config_gnss_id_t;
#define UBX_CFG_GNSS_FLAGS_ENABLED 0x01
#define UBX_CFG_GNSS_FLAGS_GPS_L1CA 0x010000
#define UBX_CFG_GNSS_FLAGS_SBAS_L1CA 0x010000
#define UBX_CFG_GNSS_FLAGS_BEIDOU_B1I 0x010000
#define UBX_CFG_GNSS_FLAGS_QZSS_L1CA 0x010000
#define UBX_CFG_GNSS_FLAGS_QZSS_L1SAIF 0x040000
#define UBX_CFG_GNSS_FLAGS_GLONASS_L1OF 0x010000
#define UBX_CFG_GNSS_NUMCH_VER7 22
#define UBX_CFG_GNSS_NUMCH_VER8 32
typedef struct {
uint8_t gnssId;
uint8_t resTrkCh;
uint8_t maxTrkCh;
uint8_t resvd;
uint32_t flags;
} __attribute__((packed)) ubx_cfg_gnss_cfgblock_t;
typedef struct {
uint8_t msgVer;
uint8_t numTrkChHw;
uint8_t numTrkChUse;
uint8_t numConfigBlocks;
ubx_cfg_gnss_cfgblock_t cfgBlocks[UBX_GNSS_ID_MAX];
} __attribute__((packed)) ubx_cfg_gnss_t;
typedef struct {
uint8_t prolog[2];
uint8_t class;
@ -181,6 +223,7 @@ typedef union {
ubx_cfg_nav5_t cfg_nav5;
ubx_cfg_rate_t cfg_rate;
ubx_cfg_sbas_t cfg_sbas;
ubx_cfg_gnss_t cfg_gnss;
} payload;
uint8_t resvd[2]; // added space for checksum bytes
} message;

View File

@ -224,6 +224,65 @@ void config_sbas(uint16_t *bytes_to_send)
status->requiredAck.msgID = UBX_ID_CFG_SBAS;
}
void config_gnss(uint16_t *bytes_to_send)
{
int32_t i;
memset(status->working_packet.buffer, 0, sizeof(UBXSentHeader_t) + sizeof(ubx_cfg_gnss_t));
status->working_packet.message.payload.cfg_gnss.numConfigBlocks = UBX_GNSS_ID_MAX;
status->working_packet.message.payload.cfg_gnss.numTrkChHw = (ubxHwVersion > UBX_HW_VERSION_7) ? UBX_CFG_GNSS_NUMCH_VER8 : UBX_CFG_GNSS_NUMCH_VER7;
status->working_packet.message.payload.cfg_gnss.numTrkChUse = status->working_packet.message.payload.cfg_gnss.numTrkChHw;
for (i = 0; i < UBX_GNSS_ID_MAX; i++) {
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].gnssId = i;
switch (i) {
case UBX_GNSS_ID_GPS:
if (status->currentSettings.enableGPS) {
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].flags = UBX_CFG_GNSS_FLAGS_ENABLED | UBX_CFG_GNSS_FLAGS_GPS_L1CA;
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].maxTrkCh = 16;
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].resTrkCh = 8;
}
break;
case UBX_GNSS_ID_QZSS:
if (status->currentSettings.enableGPS) {
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].flags = UBX_CFG_GNSS_FLAGS_ENABLED | UBX_CFG_GNSS_FLAGS_QZSS_L1CA;
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].maxTrkCh = 3;
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].resTrkCh = 0;
}
break;
case UBX_GNSS_ID_SBAS:
if (status->currentSettings.SBASCorrection || status->currentSettings.SBASIntegrity || status->currentSettings.SBASRanging) {
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].flags = UBX_CFG_GNSS_FLAGS_ENABLED | UBX_CFG_GNSS_FLAGS_SBAS_L1CA;
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].maxTrkCh = status->currentSettings.SBASChannelsUsed < 4 ? status->currentSettings.SBASChannelsUsed : 3;
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].resTrkCh = 1;
}
break;
case UBX_GNSS_ID_GLONASS:
if (status->currentSettings.enableGLONASS) {
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].flags = UBX_CFG_GNSS_FLAGS_ENABLED | UBX_CFG_GNSS_FLAGS_GLONASS_L1OF;
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].maxTrkCh = 14;
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].resTrkCh = 8;
}
break;
case UBX_GNSS_ID_BEIDOU:
if (status->currentSettings.enableBeiDou) {
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].flags = UBX_CFG_GNSS_FLAGS_ENABLED | UBX_CFG_GNSS_FLAGS_BEIDOU_B1I;
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].maxTrkCh = 14;
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].resTrkCh = 8;
}
break;
default:
break;
}
}
*bytes_to_send = prepare_packet(&status->working_packet, UBX_CLASS_CFG, UBX_ID_CFG_GNSS, sizeof(ubx_cfg_gnss_t));
status->requiredAck.clsID = UBX_CLASS_CFG;
status->requiredAck.msgID = UBX_ID_CFG_GNSS;
}
void config_save(uint16_t *bytes_to_send)
{
memset(status->working_packet.buffer, 0, sizeof(UBXSentHeader_t) + sizeof(ubx_cfg_cfg_t));
@ -244,13 +303,21 @@ static void configure(uint16_t *bytes_to_send)
config_nav(bytes_to_send);
break;
case LAST_CONFIG_SENT_START + 2:
if (status->currentSettings.enableGLONASS || status->currentSettings.enableGPS) {
config_gnss(bytes_to_send);
break;
} else {
// Skip and fall through to next step
status->lastConfigSent++;
}
case LAST_CONFIG_SENT_START + 3:
config_sbas(bytes_to_send);
if (!status->currentSettings.storeSettings) {
// skips saving
status->lastConfigSent = LAST_CONFIG_SENT_COMPLETED;
}
break;
case LAST_CONFIG_SENT_START + 3:
case LAST_CONFIG_SENT_START + 4:
config_save(bytes_to_send);
status->lastConfigSent = LAST_CONFIG_SENT_COMPLETED;
return;
@ -308,22 +375,12 @@ void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send, bool gps_connec
switch (status->currentStep) {
case INIT_STEP_ERROR:
if (PIOS_DELAY_DiffuS(status->lastStepTimestampRaw) > UBX_ERROR_RETRY_TIMEOUT) {
status->currentStep = INIT_STEP_START;
status->lastStepTimestampRaw = PIOS_DELAY_GetRaw();
}
return;
case INIT_STEP_DISABLED:
case INIT_STEP_DONE:
return;
case INIT_STEP_START:
case INIT_STEP_ASK_VER:
// clear ack
ubxLastAck.clsID = 0x00;
ubxLastAck.msgID = 0x00;
status->lastStepTimestampRaw = PIOS_DELAY_GetRaw();
build_request(&status->working_packet, UBX_CLASS_MON, UBX_ID_MON_VER, bytes_to_send);
status->currentStep = INIT_STEP_WAIT_VER;
@ -366,15 +423,12 @@ void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send, bool gps_connec
{
bool step_configure = (status->currentStep == INIT_STEP_CONFIGURE_WAIT_ACK);
if (ubxLastAck.clsID == status->requiredAck.clsID && ubxLastAck.msgID == status->requiredAck.msgID) {
// clear ack
ubxLastAck.clsID = 0x00;
ubxLastAck.msgID = 0x00;
// Continue with next configuration option
status->retryCount = 0;
status->lastConfigSent++;
} else if (PIOS_DELAY_DiffuS(status->lastStepTimestampRaw) > UBX_REPLY_TIMEOUT) {
// timeout, resend the message or abort
} else if (PIOS_DELAY_DiffuS(status->lastStepTimestampRaw) > UBX_REPLY_TIMEOUT ||
(ubxLastNak.clsID == status->requiredAck.clsID && ubxLastNak.msgID == status->requiredAck.msgID)) {
// timeout or NAK, resend the message or abort
status->retryCount++;
if (status->retryCount > UBX_MAX_RETRIES) {
status->currentStep = INIT_STEP_ERROR;

View File

@ -1376,7 +1376,7 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
}
// Wait 1ms if not.
PIOS_DELAY_WaitmS(1);
vTaskDelay(1 + (1 / (portTICK_RATE_MS + 1)));
}
// ****************
@ -1481,6 +1481,15 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
// x-nibbles rx preamble detection
rfm22_write(rfm22b_dev, RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3);
// Release the bus
rfm22_releaseBus(rfm22b_dev);
// Yield the CPU.
vTaskDelay(1 + (1 / (portTICK_RATE_MS + 1)));
// Claim the SPI bus.
rfm22_claimBus(rfm22b_dev);
// header control - using a 4 by header with broadcast of 0xffffffff
rfm22_write(rfm22b_dev, RFM22_header_control1,
RFM22_header_cntl1_bcen_0 |
@ -1530,6 +1539,9 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
// Release the bus
rfm22_releaseBus(rfm22b_dev);
// Yield the CPU.
vTaskDelay(1 + (1 / (portTICK_RATE_MS + 1)));
// Initialize the frequency and datarate to te default.
rfm22_setNominalCarrierFrequency(rfm22b_dev, 0);
pios_rfm22_setDatarate(rfm22b_dev);

View File

@ -44,7 +44,7 @@ UAVGadgetDecorator::UAVGadgetDecorator(IUAVGadget *gadget, QList<IUAVGadgetConfi
m_toolbar->setMinimumContentsLength(15);
foreach(IUAVGadgetConfiguration * config, *m_configurations)
m_toolbar->addItem(config->name());
connect(m_toolbar, SIGNAL(activated(int)), this, SLOT(loadConfiguration(int)));
connect(m_toolbar, SIGNAL(currentIndexChanged(int)), this, SLOT(loadConfiguration(int)));
updateToolbar();
}
@ -63,15 +63,22 @@ void UAVGadgetDecorator::loadConfiguration(int index)
void UAVGadgetDecorator::loadConfiguration(IUAVGadgetConfiguration *config)
{
if (m_activeConfiguration == config) {
return;
}
m_activeConfiguration = config;
int index = m_toolbar->findText(config->name());
m_toolbar->setCurrentIndex(index);
if (m_toolbar->currentIndex() != index) {
m_toolbar->setCurrentIndex(index);
}
m_gadget->loadConfiguration(config);
}
void UAVGadgetDecorator::configurationChanged(IUAVGadgetConfiguration *config)
{
if (config == m_activeConfiguration) {
// force a configuration reload
m_activeConfiguration = NULL;
loadConfiguration(config);
}
}
@ -133,7 +140,6 @@ void UAVGadgetDecorator::restoreState(QSettings *qSettings)
foreach(IUAVGadgetConfiguration * config, *m_configurations) {
if (config->name() == configName) {
m_activeConfiguration = config;
loadConfiguration(config);
break;
}

View File

@ -166,7 +166,7 @@ void UAVGadgetInstanceManager::readConfigs_1_1_0(QSettings *qs)
configs = qs->childGroups();
foreach(QString configName, configs) {
qDebug() << "Loading config: " << classId << "," << configName;
qDebug().nospace() << "Loading config: " << classId << ", " << configName;
qs->beginGroup(configName);
bool locked = qs->value("config.locked").toBool();
configInfo.setNameOfConfigurable(classId + "-" + configName);

View File

@ -34,7 +34,6 @@
#include <QtCore/QDebug>
#ifdef Q_WS_MAC
#include <qmacstyle_mac.h>
#endif
@ -46,22 +45,28 @@ SplitterOrView::SplitterOrView(Core::UAVGadgetManager *uavGadgetManager, Core::I
m_uavGadgetManager(uavGadgetManager),
m_splitter(0)
{
m_view = new UAVGadgetView(m_uavGadgetManager, uavGadget, this);
m_layout = new QStackedLayout(this);
m_layout->addWidget(m_view);
m_view = new UAVGadgetView(m_uavGadgetManager, uavGadget, this);
setLayout(new QStackedLayout());
layout()->addWidget(m_view);
}
SplitterOrView::SplitterOrView(SplitterOrView &splitterOrView, QWidget *parent) :
QWidget(parent),
m_uavGadgetManager(splitterOrView.m_uavGadgetManager),
m_view(splitterOrView.m_view),
m_splitter(splitterOrView.m_splitter)
{
Q_ASSERT((m_view || m_splitter) && !(m_view && m_splitter));
setLayout(new QStackedLayout());
if (m_view) {
layout()->addWidget(m_view);
} else if (m_splitter) {
layout()->addWidget(m_splitter);
}
}
SplitterOrView::~SplitterOrView()
{
if (m_view) {
delete m_view;
m_view = 0;
}
if (m_splitter) {
delete m_splitter;
m_splitter = 0;
}
}
{}
void SplitterOrView::mousePressEvent(QMouseEvent *e)
{
@ -221,7 +226,7 @@ QSplitter *SplitterOrView::takeSplitter()
QSplitter *oldSplitter = m_splitter;
if (m_splitter) {
m_layout->removeWidget(m_splitter);
layout()->removeWidget(m_splitter);
}
m_splitter = 0;
return oldSplitter;
@ -232,7 +237,7 @@ UAVGadgetView *SplitterOrView::takeView()
UAVGadgetView *oldView = m_view;
if (m_view) {
m_layout->removeWidget(m_view);
layout()->removeWidget(m_splitter);
}
m_view = 0;
return oldView;
@ -255,35 +260,6 @@ QList<IUAVGadget *> SplitterOrView::gadgets()
return g;
}
void SplitterOrView::split(Qt::Orientation orientation)
{
Q_ASSERT(m_view);
Q_ASSERT(!m_splitter);
m_splitter = new MiniSplitter(this);
m_splitter->setOrientation(orientation);
connect(m_splitter, SIGNAL(splitterMoved(int, int)), this, SLOT(onSplitterMoved(int, int)));
m_layout->addWidget(m_splitter);
Core::IUAVGadget *ourGadget = m_view->gadget();
if (ourGadget) {
// Give our gadget to the new left or top SplitterOrView.
m_view->removeGadget();
m_splitter->addWidget(new SplitterOrView(m_uavGadgetManager, ourGadget));
m_splitter->addWidget(new SplitterOrView(m_uavGadgetManager));
} else {
m_splitter->addWidget(new SplitterOrView(m_uavGadgetManager));
m_splitter->addWidget(new SplitterOrView(m_uavGadgetManager));
}
m_layout->setCurrentWidget(m_splitter);
if (m_view) {
m_uavGadgetManager->emptyView(m_view);
delete m_view;
m_view = 0;
}
}
void SplitterOrView::onSplitterMoved(int pos, int index)
{
Q_UNUSED(pos);
@ -292,66 +268,107 @@ void SplitterOrView::onSplitterMoved(int pos, int index)
m_sizes = m_splitter->sizes();
}
void SplitterOrView::unsplitAll(IUAVGadget *currentGadget)
void SplitterOrView::split(Qt::Orientation orientation)
{
Q_ASSERT(m_splitter);
Q_ASSERT(!m_view);
m_splitter->hide();
m_layout->removeWidget(m_splitter); // workaround Qt bug
unsplitAll_helper();
delete m_splitter;
m_splitter = 0;
Q_ASSERT(m_view);
Q_ASSERT(!m_splitter);
m_view = new UAVGadgetView(m_uavGadgetManager, currentGadget, this);
m_layout->addWidget(m_view);
MiniSplitter *splitter = new MiniSplitter(this);
splitter->setOrientation(orientation);
layout()->addWidget(splitter);
// [OP-1586] make sure that the view never becomes parent less otherwise a rendering bug happens
// in osgearth QML views (not all kind of scenes are affected but those containing terrain are)
// Making the view parent less will destroy the OpenGL context used by the QQuickFramebufferObject used OSGViewport
// A new OpenGL context will be created but for some reason, osgearth does not switch to it gracefully.
// Enabling the stats overlay (by pressing the 's' key in the view) will restore proper rendering (?).
// Note : avoiding to make the view parent less is a workaround... the real cause of the rendering bug needs to be
// understood and fixed (the same workaround is also need in unsplit and unsplitAll)
// Important : the changes also apparently make splitting and un-splitting more reactive and less jumpy!
// Give our view to the new left or top SplitterOrView.
splitter->addWidget(new SplitterOrView(*this, splitter));
splitter->addWidget(new SplitterOrView(m_uavGadgetManager));
m_view = 0;
m_splitter = splitter;
connect(m_splitter, SIGNAL(splitterMoved(int, int)), this, SLOT(onSplitterMoved(int, int)));
}
void SplitterOrView::unsplitAll_helper()
{
if (m_view) {
m_uavGadgetManager->emptyView(m_view);
}
if (m_splitter) {
for (int i = 0; i < m_splitter->count(); ++i) {
if (SplitterOrView * splitterOrView = qobject_cast<SplitterOrView *>(m_splitter->widget(i))) {
splitterOrView->unsplitAll_helper();
}
}
}
}
void SplitterOrView::unsplit()
void SplitterOrView::unsplit(IUAVGadget *gadget)
{
if (!m_splitter) {
return;
}
Q_ASSERT(m_splitter->count() == 1);
SplitterOrView *childSplitterOrView = qobject_cast<SplitterOrView *>(m_splitter->widget(0));
QSplitter *oldSplitter = m_splitter;
m_splitter = 0;
if (childSplitterOrView->isSplitter()) {
Q_ASSERT(childSplitterOrView->view() == 0);
m_splitter = childSplitterOrView->takeSplitter();
m_layout->addWidget(m_splitter);
m_layout->setCurrentWidget(m_splitter);
} else {
UAVGadgetView *childView = childSplitterOrView->view();
Q_ASSERT(childView);
if (m_view) {
if (IUAVGadget * e = childView->gadget()) {
childView->removeGadget();
m_view->setGadget(e);
}
m_uavGadgetManager->emptyView(childView);
} else {
m_view = childSplitterOrView->takeView();
m_layout->addWidget(m_view);
}
m_layout->setCurrentWidget(m_view);
SplitterOrView *view = findView(gadget);
if (!view || view == this) {
return;
}
// find the other gadgets
// TODO handle case where m_splitter->count() > 2
SplitterOrView *splitterOrView = NULL;
for (int i = 0; i < m_splitter->count(); ++i) {
splitterOrView = qobject_cast<SplitterOrView *>(m_splitter->widget(i));
if (splitterOrView && (splitterOrView != view)) {
break;
}
}
if (splitterOrView) {
if (splitterOrView->isView()) {
layout()->addWidget(splitterOrView->m_view);
} else {
layout()->addWidget(splitterOrView->m_splitter);
}
layout()->removeWidget(m_splitter);
m_uavGadgetManager->emptyView(view->m_view);
delete view;
delete m_splitter;
m_view = splitterOrView->m_view;
m_splitter = splitterOrView->m_splitter;
}
}
void SplitterOrView::unsplitAll(Core::IUAVGadget *gadget)
{
Q_ASSERT(m_splitter);
Q_ASSERT(!m_view);
SplitterOrView *splitterOrView = findView(gadget);
if (!splitterOrView || splitterOrView == this) {
return;
}
// first re-parent the gadget (see split for an explanation)
m_view = splitterOrView->m_view;
layout()->addWidget(m_view);
layout()->removeWidget(m_splitter);
// make sure the old m_view is not emptied...
splitterOrView->m_view = NULL;
// cleanup
unsplitAll_helper(m_uavGadgetManager, m_splitter);
delete m_splitter;
m_splitter = 0;
}
void SplitterOrView::unsplitAll_helper(UAVGadgetManager *uavGadgetManager, QSplitter *splitter)
{
for (int i = 0; i < splitter->count(); ++i) {
if (SplitterOrView * splitterOrView = qobject_cast<SplitterOrView *>(splitter->widget(i))) {
if (splitterOrView->m_view) {
uavGadgetManager->emptyView(splitterOrView->m_view);
}
if (splitterOrView->m_splitter) {
unsplitAll_helper(uavGadgetManager, splitterOrView->m_splitter);
}
delete splitterOrView;
}
}
delete oldSplitter;
m_uavGadgetManager->setCurrentGadget(findFirstView()->gadget());
}
void SplitterOrView::saveState(QSettings *qSettings) const

View File

@ -43,7 +43,11 @@ public:
~SplitterOrView();
void split(Qt::Orientation orientation);
void unsplit();
void unsplit(IUAVGadget *gadget);
// un-split all and keep only the specified gadget
void unsplitAll(IUAVGadget *gadget);
inline bool isView() const
{
@ -95,10 +99,7 @@ public:
}
QSize minimumSizeHint() const;
void unsplitAll(IUAVGadget *currentGadget);
protected:
// void paintEvent(QPaintEvent *);
void mousePressEvent(QMouseEvent *e);
private slots:
@ -106,19 +107,19 @@ private slots:
void onSplitterMoved(int pos, int index);
private:
void unsplitAll_helper();
// private "copy" constructor
SplitterOrView(SplitterOrView &splitterOrView, QWidget *parent);
static void unsplitAll_helper(UAVGadgetManager *uavGadgetManager, QSplitter *splitter);
SplitterOrView *findNextView_helper(SplitterOrView *view, bool *found);
// The gadget manager that controls us.
QPointer<UAVGadgetManager> m_uavGadgetManager;
// Our layout, we use stacked so we can change stuff without visual artifacts (I think...)
QPointer<QStackedLayout> m_layout;
// Our view, if we are a view (showing 1 gadget) and not a splitter.
QPointer<UAVGadgetView> m_view;
// Out splitter, if we are a splitter.
// Our splitter, if we are a splitter.
QPointer<QSplitter> m_splitter;
// The splitter sizes. We keep our own copy of these, since after loading they can't realiably be retrieved.

View File

@ -108,7 +108,7 @@ UAVGadgetManager::UAVGadgetManager(ICore *core, QString name, QIcon icon, int pr
this, SLOT(modeChanged(Core::IMode *)));
// other setup
m_splitterOrView = new SplitterOrView(this, 0);
m_splitterOrView = new SplitterOrView(this);
// 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.
@ -209,10 +209,10 @@ void UAVGadgetManager::emptyView(Core::Internal::UAVGadgetView *view)
}
IUAVGadget *uavGadget = view->gadget();
// emit uavGadgetAboutToClose(uavGadget);
// emit uavGadgetAboutToClose(uavGadget);
removeGadget(uavGadget);
view->removeGadget();
// emit uavGadgetsClosed(uavGadgets);
// emit uavGadgetsClosed(uavGadgets);
}
@ -221,27 +221,22 @@ void UAVGadgetManager::closeView(Core::Internal::UAVGadgetView *view)
if (!view) {
return;
}
SplitterOrView *splitterOrView = m_splitterOrView->findView(view);
Q_ASSERT(splitterOrView);
Q_ASSERT(splitterOrView->view() == view);
if (splitterOrView == m_splitterOrView) {
return;
}
IUAVGadget *gadget = view->gadget();
emptyView(view);
// find SplitterOrView splitter that contains the view to delete
SplitterOrView *splitter = m_splitterOrView->findSplitter(gadget);
if (!splitter) {
return;
}
Q_ASSERT(splitter->isSplitter() == true);
splitter->unsplit(gadget);
UAVGadgetInstanceManager *im = ICore::instance()->uavGadgetInstanceManager();
im->removeGadget(gadget);
SplitterOrView *splitter = m_splitterOrView->findSplitter(splitterOrView);
Q_ASSERT(splitterOrView->hasGadget() == false);
Q_ASSERT(splitter->isSplitter() == true);
splitterOrView->hide();
delete splitterOrView;
splitter->unsplit();
SplitterOrView *newCurrent = splitter->findFirstView();
SplitterOrView *newCurrent = splitter->findFirstView();
Q_ASSERT(newCurrent);
if (newCurrent) {
setCurrentGadget(newCurrent->gadget());
@ -254,8 +249,7 @@ void UAVGadgetManager::addGadgetToContext(IUAVGadget *gadget)
return;
}
m_core->addContextObject(gadget);
// emit uavGadgetOpened(uavGadget);
// emit uavGadgetOpened(uavGadget);
}
void UAVGadgetManager::removeGadget(IUAVGadget *gadget)

View File

@ -129,13 +129,25 @@ void GpsConstellationWidget::updateSat(int index, int prn, int elevation, int az
-satIcons[index]->boundingRect().center().y());
satIcons[index]->setTransform(QTransform::fromTranslate(opd.x(), opd.y()), false);
// Show normal GPS or SBAS (120 - 158 range)
if (prn > 119 && prn < 159) {
// Show normal GPS, SBAS/QZSS (120-158,193-197 range), BeiDou (33-64, 159-163) or GLONASS (65-96, 255 if unidentified)
if ((prn > 119 && prn < 159) || (prn > 192 && prn < 198)) {
if (snr) {
satIcons[index]->setElementId("satellite-sbas");
} else {
satIcons[index]->setElementId("sat-sbas-notSeen");
}
} else if ((prn > 64 && prn < 97) || 255 == prn) {
if (snr) {
satIcons[index]->setElementId("satellite-glonass");
} else {
satIcons[index]->setElementId("sat-glonass-notSeen");
}
} else if ((prn > 32 && prn < 65) || (prn > 158 && prn < 164)) {
if (snr) {
satIcons[index]->setElementId("satellite-beidou");
} else {
satIcons[index]->setElementId("sat-beidou-notSeen");
}
} else {
if (snr) {
satIcons[index]->setElementId("satellite");

View File

@ -127,7 +127,7 @@
</palette>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Displays the SNR for each detected sat. Satellite number (PRN) is displayed inside the green bar (GPS) or orange bar (SBAS). Sat SNR is displayed above (in dBHz)&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Displays the SNR for each detected sat. GPS satellites are shown in green, GLONASS in cyan, BeiDou in red and SBAS/QZSS in orange. Satellite number (PRN) is displayed inside the bar. Sat SNR is displayed above (in dBHz)&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="autoFillBackground">
<bool>false</bool>

View File

@ -104,9 +104,14 @@ void GpsSnrWidget::drawSat(int index)
QRectF boxRect = boxes[index]->boundingRect();
// Change color for SBAS sat (Egnos, etc..) 120 - 158 range
if (prn > 119 && prn < 159) {
// Change color for SBAS & QZSS 120-158, 193-197 range
// GLONASS range 65-96 or 255, BeiDou 33-64 or 159-163
if ((prn > 119 && prn < 159) || (prn > 192 && prn < 198)) {
boxes[index]->setBrush(QColor("#fd700b"));
} else if ((prn > 64 && prn < 97) || 255 == prn) {
boxes[index]->setBrush(QColor("Cyan"));
} else if ((prn > 32 && prn < 65) || (prn > 158 && prn < 164)) {
boxes[index]->setBrush(QColor("Red"));
} else {
boxes[index]->setBrush(QColor("Green"));
}

View File

@ -14,8 +14,8 @@
height="691.54303"
id="svg2"
version="1.1"
inkscape:version="0.48.5 r10040"
sodipodi:docname="gpsEarth_work.svg">
inkscape:version="0.48.4 r9939"
sodipodi:docname="gpsEarth.svg">
<defs
id="defs4">
<linearGradient
@ -618,7 +618,7 @@
<linearGradient
id="linearGradient3845-3">
<stop
style="stop-color:#ffe054;stop-opacity:1;"
style="stop-color:#00e054;stop-opacity:1;"
offset="0"
id="stop3847-6" />
<stop
@ -907,6 +907,102 @@
y1="353.18066"
x2="148.63506"
y2="481.89807" />
<radialGradient
inkscape:collect="always"
xlink:href="#linearGradient3815-6-7"
id="radialGradient3937-6-0"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(-0.11243486,0.51064271,-0.68854473,-0.15160586,748.65596,-75.556107)"
cx="559.92383"
cy="182.67093"
fx="559.92383"
fy="182.67093"
r="21.496641" />
<linearGradient
id="linearGradient3815-6-7">
<stop
style="stop-color:#f1f4fc;stop-opacity:1;"
offset="0"
id="stop3817-4-6" />
<stop
style="stop-color:#f1f4fc;stop-opacity:0;"
offset="1"
id="stop3819-6-4" />
</linearGradient>
<filter
inkscape:collect="always"
id="filter3985-6-8"
color-interpolation-filters="sRGB">
<feGaussianBlur
inkscape:collect="always"
stdDeviation="0.8285714"
id="feGaussianBlur3987-7-5" />
</filter>
<radialGradient
r="21.496641"
fy="182.67093"
fx="559.92383"
cy="182.67093"
cx="559.92383"
gradientTransform="matrix(-0.11243486,0.51064271,-0.68854473,-0.15160586,748.65596,-75.556107)"
gradientUnits="userSpaceOnUse"
id="radialGradient3207"
xlink:href="#linearGradient3815-6-7"
inkscape:collect="always" />
<radialGradient
inkscape:collect="always"
xlink:href="#linearGradient3815-6-9"
id="radialGradient4015-9-9"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(-0.11243486,0.51064271,-0.68854473,-0.15160586,748.65596,-75.556107)"
cx="559.92383"
cy="182.67093"
fx="559.92383"
fy="182.67093"
r="21.496641" />
<linearGradient
inkscape:collect="always"
id="linearGradient3815-6-9">
<stop
style="stop-color:#f1f4fc;stop-opacity:1;"
offset="0"
id="stop3817-4-7" />
<stop
style="stop-color:#f1f4fc;stop-opacity:0;"
offset="1"
id="stop3819-6-3" />
</linearGradient>
<filter
inkscape:collect="always"
id="filter3985-6-6"
color-interpolation-filters="sRGB">
<feGaussianBlur
inkscape:collect="always"
stdDeviation="0.8285714"
id="feGaussianBlur3987-7-8" />
</filter>
<radialGradient
r="21.496641"
fy="182.67093"
fx="559.92383"
cy="182.67093"
cx="559.92383"
gradientTransform="matrix(-0.11243486,0.51064271,-0.68854473,-0.15160586,748.65596,-75.556107)"
gradientUnits="userSpaceOnUse"
id="radialGradient4023"
xlink:href="#linearGradient3815-6-9"
inkscape:collect="always" />
<radialGradient
inkscape:collect="always"
xlink:href="#linearGradient3815-6-7"
id="radialGradient4050"
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(-0.11243486,0.51064271,-0.68854473,-0.15160586,748.65596,-75.556107)"
cx="559.92383"
cy="182.67093"
fx="559.92383"
fy="182.67093"
r="21.496641" />
</defs>
<sodipodi:namedview
id="base"
@ -915,16 +1011,16 @@
borderopacity="1.0"
inkscape:pageopacity="0.0"
inkscape:pageshadow="2"
inkscape:zoom="0.43130409"
inkscape:cx="302.55734"
inkscape:cy="389.84143"
inkscape:zoom="1.2199122"
inkscape:cx="466.74374"
inkscape:cy="457.17106"
inkscape:document-units="px"
inkscape:current-layer="layer10"
inkscape:current-layer="layer13"
showgrid="false"
inkscape:window-width="1280"
inkscape:window-height="928"
inkscape:window-width="2560"
inkscape:window-height="1414"
inkscape:window-x="0"
inkscape:window-y="27"
inkscape:window-y="18"
inkscape:window-maximized="1"
inkscape:snap-object-midpoints="true"
inkscape:object-nodes="false"
@ -943,7 +1039,7 @@
<dc:format>image/svg+xml</dc:format>
<dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
<dc:title></dc:title>
<dc:title />
</cc:Work>
</rdf:RDF>
</metadata>
@ -1007,7 +1103,7 @@
style="opacity:0.69172932;color:#000000;fill:#616a60;fill-opacity:1;fill-rule:nonzero;stroke:#6a6c69;stroke-width:2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker:none;visibility:visible;display:inline;overflow:visible;filter:url(#filter5048);enable-background:accumulate" />
<path
transform="translate(-16.439758,-3.266917)"
d="M 598.0103,404.8544 A 227.28432,227.28432 0 1 1 143.44167,404.8544 A 227.28432,227.28432 0 1 1 598.0103,404.8544 z"
d="m 598.0103,404.8544 c 0,125.52566 -101.75866,227.28432 -227.28432,227.28432 -125.52566,0 -227.28431,-101.75866 -227.28431,-227.28432 0,-125.52566 101.75865,-227.28432 227.28431,-227.28432 125.52566,0 227.28432,101.75866 227.28432,227.28432 z"
sodipodi:ry="227.28432"
sodipodi:rx="227.28432"
sodipodi:cy="404.8544"
@ -1017,7 +1113,7 @@
sodipodi:type="arc" />
<path
transform="matrix(1.0229478,0,0,0.27614188,-24.947098,289.79023)"
d="M 598.0103,404.8544 A 227.28432,227.28432 0 1 1 143.44167,404.8544 A 227.28432,227.28432 0 1 1 598.0103,404.8544 z"
d="m 598.0103,404.8544 c 0,125.52566 -101.75866,227.28432 -227.28432,227.28432 -125.52566,0 -227.28431,-101.75866 -227.28431,-227.28432 0,-125.52566 101.75865,-227.28432 227.28431,-227.28432 125.52566,0 227.28432,101.75866 227.28432,227.28432 z"
sodipodi:ry="227.28432"
sodipodi:rx="227.28432"
sodipodi:cy="404.8544"
@ -1056,14 +1152,14 @@
sodipodi:cy="410.41025"
sodipodi:rx="89.398499"
sodipodi:ry="89.398499"
d="M 451.71402,343.4835 A 89.398499,89.398499 0 1 1 437.72993,333.33041"
d="m 451.71402,343.4835 c 36.96262,32.73378 40.39077,89.23387 7.657,126.19649 -32.73378,36.96262 -89.23387,40.39078 -126.19649,7.657 -36.96262,-32.73377 -40.39077,-89.23386 -7.657,-126.19648 28.33719,-31.99805 75.3601,-39.46142 112.2124,-17.8101"
transform="matrix(1.2638612,0,0,1.2638612,-124.40402,-114.71229)"
sodipodi:start="5.4371862"
sodipodi:end="11.526764"
sodipodi:open="true" />
<path
transform="matrix(1.9716104,0,0,1.9716104,-399.86707,-407.46887)"
d="M 451.12161,342.96352 A 89.398499,89.398499 0 1 1 442.12815,336.08929"
d="m 451.12161,342.96352 c 37.2498,32.4066 41.17599,88.87427 8.76939,126.12407 -32.4066,37.2498 -88.87426,41.17599 -126.12407,8.76939 -37.2498,-32.4066 -41.17598,-88.87427 -8.76938,-126.12407 29.53979,-33.95454 79.71538,-40.65585 117.1306,-15.64362"
sodipodi:ry="89.398499"
sodipodi:rx="89.398499"
sodipodi:cy="410.41025"
@ -1148,7 +1244,7 @@
sodipodi:cy="404.8544"
sodipodi:rx="227.28432"
sodipodi:ry="227.28432"
d="M 598.0103,404.8544 A 227.28432,227.28432 0 1 1 143.44167,404.8544 A 227.28432,227.28432 0 1 1 598.0103,404.8544 z"
d="m 598.0103,404.8544 c 0,125.52566 -101.75866,227.28432 -227.28432,227.28432 -125.52566,0 -227.28431,-101.75866 -227.28431,-227.28432 0,-125.52566 101.75865,-227.28432 227.28431,-227.28432 125.52566,0 227.28432,101.75866 227.28432,227.28432 z"
transform="matrix(1.0185,0,0,1.0185,-23.298188,-10.756724)" />
<path
style="color:#000000;fill:url(#linearGradient5561);fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:2;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate"
@ -1238,13 +1334,13 @@
inkscape:label="#g3722">
<path
transform="translate(0.08444214,2.2540576e-8)"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
sodipodi:ry="20.714285"
sodipodi:rx="20.714285"
sodipodi:cy="195.93361"
sodipodi:cx="569.28571"
id="path3712"
style="fill:url(#linearGradient3859-7);fill-opacity:1;stroke:#fcaa21;stroke-width:1.56471384;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
style="fill:url(#linearGradient3859-7);fill-opacity:1;stroke:#029909;stroke-width:1.56471384000000002;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
sodipodi:type="arc" />
<path
sodipodi:type="arc"
@ -1254,7 +1350,7 @@
sodipodi:cy="195.93361"
sodipodi:rx="20.714285"
sodipodi:ry="20.714285"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
transform="translate(0.08444218,2.2540576e-8)" />
</g>
<g
@ -1264,17 +1360,17 @@
style="opacity:0.4">
<path
sodipodi:type="arc"
style="fill:#ffe054;fill-opacity:1;stroke:#fcaa21;stroke-width:1.56471384;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
style="fill:#54ff95;fill-opacity:1;stroke:#03ba3a;stroke-width:1.56471384000000002;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="path3891"
sodipodi:cx="569.28571"
sodipodi:cy="195.93361"
sodipodi:rx="20.714285"
sodipodi:ry="20.714285"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
transform="translate(0.08444214,2.2540576e-8)" />
<path
transform="translate(0.08444218,2.2540576e-8)"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
sodipodi:ry="20.714285"
sodipodi:rx="20.714285"
sodipodi:cy="195.93361"
@ -1295,11 +1391,11 @@
sodipodi:cy="195.93361"
sodipodi:rx="20.714285"
sodipodi:ry="20.714285"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
transform="translate(0.08444214,2.2540576e-8)" />
<path
transform="translate(0.08444218,-2.2540576e-8)"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
sodipodi:ry="20.714285"
sodipodi:rx="20.714285"
sodipodi:cy="195.93361"
@ -1315,7 +1411,7 @@
style="opacity:0.4">
<path
transform="translate(0.08444214,2.2540576e-8)"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
sodipodi:ry="20.714285"
sodipodi:rx="20.714285"
sodipodi:cy="195.93361"
@ -1331,7 +1427,7 @@
sodipodi:cy="195.93361"
sodipodi:rx="20.714285"
sodipodi:ry="20.714285"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
transform="translate(0.08444218,-2.2540576e-8)" />
</g>
<g
@ -1340,7 +1436,7 @@
inkscape:label="#g3722">
<path
transform="translate(0.08444214,2.2540576e-8)"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
sodipodi:ry="20.714285"
sodipodi:rx="20.714285"
sodipodi:cy="195.93361"
@ -1356,7 +1452,7 @@
sodipodi:cy="195.93361"
sodipodi:rx="20.714285"
sodipodi:ry="20.714285"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
transform="translate(0.08444218,2.2540576e-8)" />
</g>
<g
@ -1372,11 +1468,11 @@
sodipodi:cy="195.93361"
sodipodi:rx="20.714285"
sodipodi:ry="20.714285"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
transform="translate(0.08444214,2.2540576e-8)" />
<path
transform="translate(0.08444218,2.2540576e-8)"
d="M 589.99999,195.93361 C 589.99999,207.37379 580.72589,216.64789 569.28571,216.64789 C 557.84552,216.64789 548.57142,207.37379 548.57142,195.93361 C 548.57142,184.49343 557.84552,175.21932 569.28571,175.21932 C 580.72589,175.21932 589.99999,184.49343 589.99999,195.93361 z"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
sodipodi:ry="20.714285"
sodipodi:rx="20.714285"
sodipodi:cy="195.93361"
@ -1385,6 +1481,58 @@
style="fill:url(#radialGradient4055-2);fill-opacity:1;stroke:none;filter:url(#filter3985-6)"
sodipodi:type="arc" />
</g>
<g
style="display:inline"
inkscape:label="#g3722"
transform="matrix(0.93879118,0,0,0.93879118,-73.44061,-70.698335)"
id="satellite-beidou">
<path
sodipodi:type="arc"
style="fill:#ff0000;fill-opacity:1;stroke:#ff5721;stroke-width:1.56471384;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
id="path3915-7"
sodipodi:cx="569.28571"
sodipodi:cy="195.93361"
sodipodi:rx="20.714285"
sodipodi:ry="20.714285"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
transform="translate(0.08444214,2.2540576e-8)" />
<path
transform="translate(0.08444218,-2.2540576e-8)"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
sodipodi:ry="20.714285"
sodipodi:rx="20.714285"
sodipodi:cy="195.93361"
sodipodi:cx="569.28571"
id="path3921-2"
style="fill:url(#radialGradient4050);fill-opacity:1;stroke:none;filter:url(#filter3985-6-8)"
sodipodi:type="arc" />
</g>
<g
id="sat-beidou-notSeen"
transform="matrix(0.93879118,0,0,0.93879118,-10.549949,-69.249241)"
inkscape:label="#g3722"
style="opacity:0.4;display:inline">
<path
transform="translate(0.08444214,2.2540576e-8)"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
sodipodi:ry="20.714285"
sodipodi:rx="20.714285"
sodipodi:cy="195.93361"
sodipodi:cx="569.28571"
id="path4003-9"
style="fill:#ff0000;fill-opacity:1;stroke:#ff5721;stroke-width:1.56471384;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
sodipodi:type="arc" />
<path
sodipodi:type="arc"
style="fill:url(#radialGradient4023);fill-opacity:1;stroke:none;filter:url(#filter3985-6-6)"
id="path4009-9"
sodipodi:cx="569.28571"
sodipodi:cy="195.93361"
sodipodi:rx="20.714285"
sodipodi:ry="20.714285"
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
transform="translate(0.08444218,-2.2540576e-8)" />
</g>
</g>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 79 KiB

After

Width:  |  Height:  |  Size: 85 KiB

View File

@ -1296,8 +1296,9 @@ int HID_API_EXPORT_CALL hid_get_indexed_string(hid_device *dev, int string_index
}
HID_API_EXPORT const wchar_t * HID_API_CALL hid_error(hid_device *dev)
HID_API_EXPORT const wchar_t * HID_API_CALL hid_error(hid_device *dev)
{
(void)dev; // avoid unused arg warning
return NULL;
}

View File

@ -166,6 +166,7 @@ static void free_hid_device(hid_device *dev)
static void register_error(hid_device *device, const char *op)
{
(void)op; // avoid unused arg warning
WCHAR *ptr, *msg;
FormatMessageW(FORMAT_MESSAGE_ALLOCATE_BUFFER |
@ -232,7 +233,7 @@ static HANDLE open_device(const char *path, BOOL enumerate)
OPEN_EXISTING,
FILE_FLAG_OVERLAPPED,/*FILE_ATTRIBUTE_NORMAL,*/
0);
DWORD error = GetLastError();
/*DWORD error =*/ GetLastError();
return handle;
}

View File

@ -27,9 +27,9 @@
#ifndef OPHID_CONST_H
#define OPHID_CONST_H
#include "QtDebug"
#define OPHID_DEBUG_ON 1
#include <QDebug>
#ifdef OPHID_DEBUG_ON
#define OPHID_DEBUG(fmt, args ...) qDebug("[DEBUG] "fmt,##args)
#define OPHID_TRACE(fmt, args ...) qDebug("[TRACE] %s:%s:%d: "fmt, __FILE__, __func__, __LINE__,##args)
@ -42,7 +42,6 @@
#define OPHID_WARNING(fmt, args ...)
#endif
// USB
#define USB_MAX_DEVICES 10
#define USB_VID 0x20A0

View File

@ -30,7 +30,6 @@
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <QDebug>
#include <QString>
#include <QMutex>
#include "../hidapi/hidapi.h"

View File

@ -1,24 +1,31 @@
TEMPLATE = lib
TARGET = opHID
DEFINES += OPHID_LIBRARY
//DEFINES += OPHID_DEBUG_ON
include(../../openpilotgcsplugin.pri)
include(ophid_dependencies.pri)
HEADERS += inc/ophid_global.h \
inc/ophid_plugin.h \
inc/ophid.h \
inc/ophid_hidapi.h \
inc/ophid_const.h \
inc/ophid_usbmon.h \
inc/ophid_usbsignal.h \
hidapi/hidapi.h
SOURCES += src/ophid_plugin.cpp \
src/ophid.cpp \
src/ophid_usbsignal.cpp \
src/ophid_hidapi.cpp
HEADERS += \
inc/ophid_global.h \
inc/ophid_plugin.h \
inc/ophid.h \
inc/ophid_hidapi.h \
inc/ophid_const.h \
inc/ophid_usbmon.h \
inc/ophid_usbsignal.h \
hidapi/hidapi.h
SOURCES += \
src/ophid_plugin.cpp \
src/ophid.cpp \
src/ophid_usbsignal.cpp \
src/ophid_hidapi.cpp
FORMS +=
RESOURCES +=
DEFINES += OPHID_LIBRARY
OTHER_FILES += opHID.pluginspec
INCLUDEPATH += ./inc
@ -26,25 +33,30 @@ INCLUDEPATH += ./inc
# Platform Specific
win32 {
SOURCES += src/ophid_usbmon_win.cpp \
hidapi/windows/hid.c
SOURCES += \
src/ophid_usbmon_win.cpp \
hidapi/windows/hid.c
LIBS += -lhid -lsetupapi
}
macx {
SOURCES += src/ophid_usbmon_mac.cpp \
hidapi/mac/hid.c
LIBS += -framework CoreFoundation \
-framework IOKit
SOURCES += \
src/ophid_usbmon_mac.cpp \
hidapi/mac/hid.c
LIBS += -framework CoreFoundation -framework IOKit
}
linux {
SOURCES += src/ophid_usbmon_linux.cpp
SOURCES += \
src/ophid_usbmon_linux.cpp
LIBS += -ludev -lrt -lpthread
# hidapi library
## rawhid
# SOURCES += hidapi/linux/hid.c
#SOURCES += hidapi/linux/hid.c
## libusb
SOURCES += hidapi/libusb/hid.c

View File

@ -146,7 +146,7 @@ RawHIDReadThread::~RawHIDReadThread()
m_running = false;
// wait for the thread to terminate
if (wait(10000) == false) {
qDebug() << "Cannot terminate RawHIDReadThread";
qWarning() << "Cannot terminate RawHIDReadThread";
}
}
@ -219,7 +219,7 @@ RawHIDWriteThread::~RawHIDWriteThread()
m_running = false;
// wait for the thread to terminate
if (wait(10000) == false) {
qDebug() << "Cannot terminate RawHIDReadThread";
qWarning() << "Cannot terminate RawHIDReadThread";
}
}
@ -264,9 +264,9 @@ void RawHIDWriteThread::run()
} else if (ret < 0) { // < 0 => error
// TODO! make proper error handling, this only quick hack for unplug freeze
m_running = false;
qDebug() << "Error writing to device (" << ret << ")";
qCritical() << "Error writing to device (" << ret << ")";
} else {
qDebug() << "No data written to device ??";
qCritical() << "No data written to device ??";
}
}
}

View File

@ -129,6 +129,10 @@ int opHID_hidapi::enumerate(struct hid_device_info * *current_device_pptr, int *
*/
int opHID_hidapi::open(int max, int vid, int pid, int usage_page, int usage)
{
Q_UNUSED(max);
Q_UNUSED(usage_page);
Q_UNUSED(usage);
int devices_found = false;
struct hid_device_info *current_device_ptr = NULL;
struct hid_device_info *tmp_device_ptr = NULL;

View File

@ -35,7 +35,6 @@
#include "ophid_hidapi.h"
#include "ophid_const.h"
/**
* \brief Constructor
*
@ -95,7 +94,7 @@ void RawHIDConnection::onDeviceConnected()
*/
void RawHIDConnection::onDeviceDisconnected()
{
qDebug() << "onDeviceDisconnected()";
OPHID_DEBUG("onDeviceDisconnected()");
if (enablePolling) {
emit availableDevChanged(this);
}

View File

@ -26,7 +26,6 @@
*/
#include "ophid_usbmon.h"
#include <QDebug>
#include "ophid_const.h"
@ -41,6 +40,8 @@
*/
void printPortInfo(struct udev_device *dev)
{
Q_UNUSED(dev);
OPHID_DEBUG(" Node: %s", udev_device_get_devnode(dev));
OPHID_DEBUG(" Subsystem: %s", udev_device_get_subsystem(dev));
OPHID_DEBUG(" Devtype: %s", udev_device_get_devtype(dev));
@ -73,7 +74,7 @@ void USBMonitor::deviceEventReceived()
// this->monitorNotifier->setEnabled(0);
QString action = QString(udev_device_get_action(dev));
QString devtype = QString(udev_device_get_devtype(dev));
qDebug() << "[DEBUG] Action: " << action << " device: " << devtype;
OPHID_DEBUG("Action: %s device: %s", qPrintable(action), qPrintable(devtype));
if (action == "add" && devtype == "usb_device") {
printPortInfo(dev);
emit deviceDiscovered(makePortInfo(dev));

View File

@ -32,7 +32,6 @@
#include <CoreFoundation/CFString.h>
#include <CoreFoundation/CFArray.h>
#include <QMutexLocker>
#include <QDebug>
#include "ophid_const.h"
// Local helper functions
@ -72,7 +71,7 @@ USBMonitor::~USBMonitor()
*/
void USBMonitor::deviceEventReceived()
{
qDebug() << "Device event";
OPHID_DEBUG("Device event");
}
/**
@ -119,7 +118,7 @@ void USBMonitor::detach_callback(void *context, IOReturn r, void *hid_mgr, IOHID
Q_UNUSED(r);
Q_UNUSED(hid_mgr);
qDebug() << "USBMonitor: Device detached event";
OPHID_DEBUG("USBMonitor: Device detached event");
instance()->removeDevice(dev);
}
@ -156,7 +155,7 @@ void USBMonitor::attach_callback(void *context, IOReturn r, void *hid_mgr, IOHID
deviceInfo.dev_handle = dev;
qDebug() << "USBMonitor: Device attached event";
OPHID_DEBUG("USBMonitor: Device attached event");
// Populate the device info structure
got_properties &= HID_GetIntProperty(dev, CFSTR(kIOHIDVendorIDKey), &deviceInfo.vendorID);
@ -171,7 +170,7 @@ void USBMonitor::attach_callback(void *context, IOReturn r, void *hid_mgr, IOHID
// Currently only enumerating objects that have the complete list of properties
if (got_properties) {
qDebug() << "USBMonitor: Adding device";
OPHID_DEBUG("USBMonitor: Adding device");
instance()->addDevice(deviceInfo);
}
}

View File

@ -31,7 +31,6 @@
#include <QEventLoop>
#include <QTimer>
#include "ophid_usbmon.h"
#include <QDebug>
#include "ophid_const.h"
/* Gordon Schumacher's macros for TCHAR -> QString conversions and vice versa */
@ -122,11 +121,9 @@ QList<USBPortInfo> USBMonitor::availableDevices(int vid, int pid, int bcdDeviceM
OPHID_TRACE("IN");
// Print the list
qDebug() << "List off (" << knowndevices.length() << ") devices that are tracked:";
OPHID_DEBUG("List off (%d) devices that are tracked:", knowndevices.length());
foreach(USBPortInfo info, knowndevices /*thePortsWeWant*/) {
qDebug() << "product:" << info.product
<< " bcdDevice:" << info.bcdDevice
<< " devicePath:" << info.devicePath;
OPHID_DEBUG("product: %s bcdDevice: %d devicePath: %s", qPrintable(info.product), info.bcdDevice, qPrintable(info.devicePath));
// Filter to return only the one request (if exists)
if ((info.vendorID == vid || vid == -1) &&
@ -249,7 +246,7 @@ bool USBMonitor::matchAndDispatchChangedDevice(const QString & deviceID, const G
{
OPHID_TRACE("IN");
qDebug() << "[STATUS CHANGE] from device ID: " << deviceID;
OPHID_DEBUG("[STATUS CHANGE] from device ID: %s", qPrintable(deviceID));
bool rc;
SP_DEVINFO_DATA spDevInfoData;
DWORD dwFlag = (DBT_DEVICEARRIVAL == wParam) ? DIGCF_PRESENT : 0 /*DIGCF_ALLCLASSES*/;
@ -263,13 +260,13 @@ bool USBMonitor::matchAndDispatchChangedDevice(const QString & deviceID, const G
DWORD nSize = 0;
TCHAR buf[MAX_PATH];
rc = SetupDiGetDeviceInstanceId(devInfo, &spDevInfoData, buf, MAX_PATH, &nSize);
qDebug() << "Found:" << TCHARToQString(buf);
OPHID_DEBUG("Found: %s", qPrintable(TCHARToQString(buf)));
if (rc && deviceID.contains(TCHARToQString(buf))) {
qDebug() << "[MATCH] " << TCHARToQString(buf);
OPHID_DEBUG("[MATCH] %s", qPrintable(TCHARToQString(buf)));
USBPortInfo info;
info.devicePath = deviceID;
if (wParam == DBT_DEVICEARRIVAL) {
qDebug() << "[INSERTED]";
OPHID_DEBUG("[INSERTED]");
if (infoFromHandle(guid, info, devInfo, i) != OPHID_NO_ERROR) {
OPHID_ERROR("Not found");
break;
@ -290,18 +287,14 @@ bool USBMonitor::matchAndDispatchChangedDevice(const QString & deviceID, const G
break;
}
knowndevices.append(info);
qDebug() << "[SIGNAL] Device discovered on device:"
<< info.product
<< info.bcdDevice;
OPHID_DEBUG("[SIGNAL] Device discovered on device: %s %d", qPrintable(info.product), info.bcdDevice);
emit deviceDiscovered(info);
break;
} else if (wParam == DBT_DEVICEREMOVECOMPLETE) {
for (int x = 0; x < knowndevices.count(); ++x) {
USBPortInfo temp = knowndevices.at(x);
knowndevices.removeAt(x);
qDebug() << "[SIGNAL] Device removed on device:"
<< temp.product
<< temp.bcdDevice;
OPHID_DEBUG("[SIGNAL] Device removed on device: %s %d", qPrintable(temp.product), temp.bcdDevice);
}
emit deviceRemoved(info);
break;
@ -362,7 +355,7 @@ void USBMonitor::enumerateDevicesWin(const GUID & guid)
}
SetupDiDestroyDeviceInfoList(devInfo);
}
OPHID_DEBUG("Added %d device(s).", j);
OPHID_DEBUG("Added %lu device(s).", j);
OPHID_TRACE("OUT");
}
@ -429,7 +422,7 @@ int USBMonitor::infoFromHandle(const GUID & guid, USBPortInfo & info, HDEVINFO &
goto leave;
}
qDebug() << "Found device with valid PATH: " << qDevicePath;
OPHID_DEBUG("Found device with valid PATH: %s", qPrintable(qDevicePath));
h = CreateFile(details->DevicePath,
GENERIC_READ | GENERIC_WRITE,
FILE_SHARE_READ | FILE_SHARE_WRITE,
@ -449,8 +442,7 @@ int USBMonitor::infoFromHandle(const GUID & guid, USBPortInfo & info, HDEVINFO &
goto leave;
}
qDebug() << "Problem opening handle, path: "
<< QString().fromWCharArray(details->DevicePath);
OPHID_DEBUG("Problem opening handle, path: %s", qPrintable(QString::fromWCharArray(details->DevicePath)));
free(details);
ret = OPHID_ERROR_RET;

View File

@ -26,8 +26,7 @@
*/
#include "ophid_usbsignal.h"
#include <QDebug>
#include "ophid_const.h"
/**
* \brief trigger device discovered signal
@ -42,7 +41,7 @@ void USBSignalFilter::m_deviceDiscovered(USBPortInfo port)
(port.productID == m_pid || m_pid == -1) &&
((port.bcdDevice >> 8) == m_boardModel || m_boardModel == -1) &&
((port.bcdDevice & 0x00ff) == m_runState || m_runState == -1)) {
qDebug() << "USBSignalFilter emit device discovered";
OPHID_DEBUG("USBSignalFilter emit device discovered");
emit deviceDiscovered();
}
}

View File

@ -7,7 +7,11 @@ ifndef OPENPILOT_IS_COOL
endif
.PHONY: package
package:
package: openpilotgcs uavobjects_matlab | $(PACKAGE_DIR)
ifneq ($(GCS_BUILD_CONF),release)
# We can only package release builds
$(error Packaging is currently supported for release builds only)
endif
( \
ROOT_DIR="$(ROOT_DIR)" \
BUILD_DIR="$(BUILD_DIR)" \

View File

@ -42,12 +42,10 @@ PACKAGE_DEPS_SED := s/python.*/python/;s/{misc:Depends}.*/{misc:Depends}/;
.PHONY: package
package: debian
@$(ECHO) "Building Linux package, please wait..."
# Override clean and build because OP has already performed them.
$(V1) printf "override_dh_auto_clean:\noverride_dh_auto_build:\n\t#\n" >> debian/rules
$(V1) sed -i -e "$(PACKAGE_DEPS_SED)" debian/control
$(V1) dpkg-buildpackage -b -us -uc
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(PACKAGE_DIR)
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(PACKAGE_DIR)
$(V1) dpkg-buildpackage -b -us -uc -nc
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(BUILD_DIR)
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(BUILD_DIR)
$(V1) rm -r debian
.PHONY: debian

View File

@ -15,7 +15,11 @@ NSIS_TEMPLATE := $(NSIS_WINX86)/openpilotgcs.tpl
NSIS_HEADER := $(OPGCSSYNTHDIR)/openpilotgcs.nsh
.PHONY: package
package:
package: openpilotgcs uavobjects_matlab | $(PACKAGE_DIR)
ifneq ($(GCS_BUILD_CONF),release)
# We can only package release builds
$(error Packaging is currently supported for release builds only)
endif
$(V1) mkdir -p "$(dir $(NSIS_HEADER))"
$(VERSION_CMD) \
--template='$(NSIS_TEMPLATE)' \

View File

@ -1,5 +1,5 @@
openpilot (<VERSION>) <DIST>; urgency=low
* Release from upstream Git (testing - unstable)
* Release from upstream Git repository
-- James Duley <james@openpilot.org> <DATE>

View File

@ -12,7 +12,7 @@ export DH_OPTIONS
dh $@
override_dh_auto_build:
dh_auto_build -- all
dh_auto_build -- opfw_resource openpilotgcs
override_dh_auto_install:
dh_auto_install -- prefix=/usr

View File

@ -2,7 +2,7 @@
<object name="GPSSatellites" singleinstance="true" settings="false" category="Sensors">
<description>Contains information about the GPS satellites in view from @ref GPSModule.</description>
<field name="SatsInView" units="" type="int8" elements="1"/>
<field name="PRN" units="" type="int8" elements="16"/>
<field name="PRN" units="" type="uint8" elements="16"/>
<field name="Elevation" units="degrees" type="int8" elements="16"/>
<field name="Azimuth" units="degrees" type="int16" elements="16"/>
<field name="SNR" units="" type="int8" elements="16"/>

View File

@ -16,6 +16,8 @@
<field name="UbxSBASMode" units="" type="enum" elements="1" options="Disabled,Ranging,Correction,Integrity,Ranging+Correction,Ranging+Integrity,Ranging+Correction+Integrity,Correction+Integrity" defaultvalue="Ranging" />
<field name="UbxSBASChannelsUsed" units="" type="uint8" elements="1" defaultvalue="3"/>
<field name="UbxSBASSats" units="" type="enum" elements="1" options="AutoScan,WAAS,EGNOS,MSAS,GAGAN,SDCM" defaultvalue="Auto-Scan" />
<!-- Ubx GNSS configuration, only applies to Ublox generation 7+ and concurrent GNSS only to generation 8 -->
<field name="UbxGNSSMode" units="" type="enum" elements="1" options="Default,GPS,GLONASS,GPS+GLONASS,GPS+BeiDou,GLONASS+BeiDou" defaultvalue="Default" />
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>