1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-21 11:54:15 +01:00

Merge remote-tracking branch 'op-public/next' into revo-next

This commit is contained in:
Stacey Sheldon 2012-06-20 22:45:41 -04:00
commit f475088585
31 changed files with 581 additions and 255 deletions

View File

@ -65,7 +65,7 @@
#define STACK_SIZE_BYTES 924 #define STACK_SIZE_BYTES 924
#endif #endif
#define TASK_PRIORITY (tskIDLE_PRIORITY+2) #define TASK_PRIORITY (tskIDLE_PRIORITY+1)
// Private types // Private types

View File

@ -329,10 +329,14 @@ int32_t PIOS_Flash_Jedec_EraseChip()
PIOS_Flash_Jedec_ReleaseBus(); PIOS_Flash_Jedec_ReleaseBus();
// Keep polling when bus is busy too // Keep polling when bus is busy too
int i = 0;
while(PIOS_Flash_Jedec_Busy() != 0) { while(PIOS_Flash_Jedec_Busy() != 0) {
#if defined(FLASH_FREERTOS) #if defined(PIOS_INCLUDE_FREERTOS)
vTaskDelay(1); vTaskDelay(1);
#endif #endif
if ((i++) % 100 == 0)
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
} }
return 0; return 0;

View File

@ -6,8 +6,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>730</width> <width>796</width>
<height>602</height> <height>618</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
@ -74,7 +74,7 @@
<item> <item>
<widget class="QStackedWidget" name="airframesWidget"> <widget class="QStackedWidget" name="airframesWidget">
<property name="currentIndex"> <property name="currentIndex">
<number>1</number> <number>0</number>
</property> </property>
<widget class="QWidget" name="fixedWing"> <widget class="QWidget" name="fixedWing">
<property name="enabled"> <property name="enabled">

View File

@ -25,7 +25,6 @@
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/ */
#include "configccpmwidget.h" #include "configccpmwidget.h"
//#include "mixersettings.h"
#include <QDebug> #include <QDebug>
#include <QStringList> #include <QStringList>
@ -555,7 +554,7 @@ void ConfigCcpmWidget::updateThrottleCurveValue(QList<double> curveValues0,doubl
for (i=0; i<internalCurveValues.length(); i++) for (i=0; i<internalCurveValues.length(); i++)
{ {
CurrentValue=m_ccpm->CurveSettings->item(i, 1 )->text().toDouble(); CurrentValue=m_ccpm->CurveSettings->item(i, 0 )->text().toDouble();
if (CurrentValue!=internalCurveValues[i]) if (CurrentValue!=internalCurveValues[i])
{ {
m_ccpm->CurveSettings->item(i, 0)->setText(QString().sprintf("%.3f",internalCurveValues.at(i))); m_ccpm->CurveSettings->item(i, 0)->setText(QString().sprintf("%.3f",internalCurveValues.at(i)));
@ -1225,11 +1224,10 @@ void ConfigCcpmWidget::setMixer()
} }
//get the user data for the curve into the mixer settings //get the user data for the curve into the mixer settings
for (i=0;i<5;i++) for (i=0;i<5;i++) {
mixerSettingsData.ThrottleCurve1[i] = m_ccpm->CurveSettings->item(i, 0)->text().toDouble(); mixerSettingsData.ThrottleCurve1[i] = m_ccpm->CurveSettings->item(i, 0)->text().toDouble();
for (i=0;i<5;i++)
mixerSettingsData.ThrottleCurve2[i] = m_ccpm->CurveSettings->item(i, 1)->text().toDouble(); mixerSettingsData.ThrottleCurve2[i] = m_ccpm->CurveSettings->item(i, 1)->text().toDouble();
}
//mapping of collective input to curve 2... //mapping of collective input to curve 2...
//MixerSettings.Curve2Source = Throttle,Roll,Pitch,Yaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5 //MixerSettings.Curve2Source = Throttle,Roll,Pitch,Yaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5

View File

@ -182,17 +182,15 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets()
QString airframeType = "FixedWing"; QString airframeType = "FixedWing";
// Save the curve (common to all Fixed wing frames) // Save the curve (common to all Fixed wing frames)
UAVDataObject *obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings"))); UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
// Remove Feed Forward, it is pointless on a plane: // Remove Feed Forward, it is pointless on a plane:
UAVObjectField* field = obj->getField(QString("FeedForward")); UAVObjectField* field = mixer->getField(QString("FeedForward"));
field->setDouble(0); field->setDouble(0);
field = obj->getField("ThrottleCurve1"); // Set the throttle curve
QList<double> curve = m_aircraft->fixedWingThrottle->getCurve(); setThrottleCurve(mixer,VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve());
for (int i=0;i<curve.length();i++) {
field->setValue(curve.at(i),i);
}
//All airframe types must start with "FixedWing" //All airframe types must start with "FixedWing"
if (m_aircraft->fixedWingType->currentText() == "Elevator aileron rudder" ) { if (m_aircraft->fixedWingType->currentText() == "Elevator aileron rudder" ) {
@ -229,36 +227,26 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType)
setComboCurrentIndex(m_aircraft->fwRudder1ChannelBox, fixed.FixedWingYaw1); setComboCurrentIndex(m_aircraft->fwRudder1ChannelBox, fixed.FixedWingYaw1);
setComboCurrentIndex(m_aircraft->fwRudder2ChannelBox, fixed.FixedWingYaw2); setComboCurrentIndex(m_aircraft->fwRudder2ChannelBox, fixed.FixedWingYaw2);
UAVDataObject* obj; UAVDataObject* mixer= dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField *field; Q_ASSERT(mixer);
int channel;
if (frameType == "FixedWingElevon") { if (frameType == "FixedWingElevon") {
// If the airframe is elevon, restore the slider setting // If the airframe is elevon, restore the slider setting
// Find the channel number for Elevon1 (FixedWingRoll1) // Find the channel number for Elevon1 (FixedWingRoll1)
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings"))); channel = m_aircraft->fwAileron1ChannelBox->currentIndex()-1;
Q_ASSERT(obj); if (channel > -1) { // If for some reason the actuators were incoherent, we might fail here, hence the check.
int chMixerNumber = m_aircraft->fwAileron1ChannelBox->currentIndex()-1; m_aircraft->elevonSlider1->setValue(getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_ROLL)*100);
if (chMixerNumber >= 0) { // If for some reason the actuators were incoherent, we might fail here, hence the check. m_aircraft->elevonSlider2->setValue(getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_PITCH)*100);
field = obj->getField(mixerVectors.at(chMixerNumber));
int ti = field->getElementNames().indexOf("Roll");
m_aircraft->elevonSlider1->setValue(field->getDouble(ti)*100);
ti = field->getElementNames().indexOf("Pitch");
m_aircraft->elevonSlider2->setValue(field->getDouble(ti)*100);
} }
} }
if (frameType == "FixedWingVtail") { if (frameType == "FixedWingVtail") {
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings"))); channel = m_aircraft->fwElevator1ChannelBox->currentIndex()-1;
Q_ASSERT(obj); if (channel > -1) { // If for some reason the actuators were incoherent, we might fail here, hence the check.
int chMixerNumber = m_aircraft->fwElevator1ChannelBox->currentIndex()-1; m_aircraft->elevonSlider1->setValue(getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_YAW)*100);
if (chMixerNumber >=0) { m_aircraft->elevonSlider2->setValue(getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_PITCH)*100);
field = obj->getField(mixerVectors.at(chMixerNumber));
int ti = field->getElementNames().indexOf("Yaw");
m_aircraft->elevonSlider1->setValue(field->getDouble(ti)*100);
ti = field->getElementNames().indexOf("Pitch");
m_aircraft->elevonSlider2->setValue(field->getDouble(ti)*100);
} }
} }
} }
@ -312,7 +300,10 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType)
int channel; int channel;
//disable all //disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++) for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
{
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED); setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
}
//motor //motor
channel = m_aircraft->fwEngineChannelBox->currentIndex()-1; channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
@ -396,7 +387,10 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType)
double value; double value;
//disable all //disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++) for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
{
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED); setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
}
//motor //motor
channel = m_aircraft->fwEngineChannelBox->currentIndex()-1; channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
@ -478,7 +472,10 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType)
double value; double value;
//disable all //disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++) for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
{
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED); setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
}
//motor //motor
channel = m_aircraft->fwEngineChannelBox->currentIndex()-1; channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;

View File

@ -25,7 +25,6 @@
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/ */
#include "configmultirotorwidget.h" #include "configmultirotorwidget.h"
#include "mixersettings.h"
#include <QDebug> #include <QDebug>
#include <QStringList> #include <QStringList>
@ -297,11 +296,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
field->setDouble(m_aircraft->maxAccelSlider->value()); field->setDouble(m_aircraft->maxAccelSlider->value());
// Curve is also common to all quads: // Curve is also common to all quads:
field = obj->getField("ThrottleCurve1"); setThrottleCurve(obj, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->multiThrottleCurve->getCurve() );
QList<double> curve = m_aircraft->multiThrottleCurve->getCurve();
for (int i=0;i<curve.length();i++) {
field->setValue(curve.at(i),i);
}
if (m_aircraft->multirotorFrameType->currentText() == "Quad +") { if (m_aircraft->multirotorFrameType->currentText() == "Quad +") {
airframeType = "QuadP"; airframeType = "QuadP";
@ -1037,19 +1032,21 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3])
qDebug()<<mixerFactors[6][0]<<" "<<mixerFactors[6][1]<<" "<<mixerFactors[6][2]; qDebug()<<mixerFactors[6][0]<<" "<<mixerFactors[6][1]<<" "<<mixerFactors[6][2];
qDebug()<<mixerFactors[7][0]<<" "<<mixerFactors[7][1]<<" "<<mixerFactors[7][2]; qDebug()<<mixerFactors[7][0]<<" "<<mixerFactors[7][1]<<" "<<mixerFactors[7][2];
UAVObjectField *field;
QList<QComboBox*> mmList; QList<QComboBox*> mmList;
mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3 mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3
<< m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6 << m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6
<< m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8; << m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8;
UAVDataObject *obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
// 1. Assign the servo/motor/none for each channel UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
// Disable all Q_ASSERT(mixer);
foreach(QString mixer, mixerTypes) {
field = obj->getField(mixer); //disable all
Q_ASSERT(field); for (int channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
field->setValue("Disabled"); {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
} }
// and enable only the relevant channels: // and enable only the relevant channels:
double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100; double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100;
double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100; double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100;

View File

@ -29,6 +29,7 @@
#include "ui_airframe.h" #include "ui_airframe.h"
#include "../uavobjectwidgetutils/configtaskwidget.h" #include "../uavobjectwidgetutils/configtaskwidget.h"
#include "cfg_vehicletypes/vehicleconfig.h"
#include "extensionsystem/pluginmanager.h" #include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h" #include "uavobjectmanager.h"

View File

@ -233,6 +233,60 @@ void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, Mixer
} }
} }
void VehicleConfig::setThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList<double> curve)
{
QPointer<UAVObjectField> field;
switch (curveType)
{
case MIXER_THROTTLECURVE1:
{
field = mixer->getField("ThrottleCurve1");
break;
}
case MIXER_THROTTLECURVE2:
{
field = mixer->getField("ThrottleCurve2");
break;
}
}
if (field && field->getNumElements() == curve.length()) {
for (int i=0;i<curve.length();i++) {
field->setValue(curve.at(i),i);
}
}
}
void VehicleConfig::getThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList<double>* curve)
{
Q_ASSERT(mixer);
Q_ASSERT(curve);
QPointer<UAVObjectField> field;
switch (curveType)
{
case MIXER_THROTTLECURVE1:
{
field = mixer->getField("ThrottleCurve1");
break;
}
case MIXER_THROTTLECURVE2:
{
field = mixer->getField("ThrottleCurve2");
break;
}
}
if (field) {
curve->clear();
for (unsigned int i=0; i < field->getNumElements(); i++) {
curve->append(field->getValue(i).toDouble());
}
}
}
/** /**
Reset the contents of a field Reset the contents of a field
*/ */

View File

@ -111,6 +111,9 @@ class VehicleConfig: public ConfigTaskWidget
VehicleConfig(QWidget *parent = 0); VehicleConfig(QWidget *parent = 0);
~VehicleConfig(); ~VehicleConfig();
/* Enumeration options for ThrottleCurves */
typedef enum { MIXER_THROTTLECURVE1=0, MIXER_THROTTLECURVE2=1 } MixerThrottleCurveElem;
/* Enumeration options for field MixerType */ /* Enumeration options for field MixerType */
typedef enum { MIXERTYPE_DISABLED=0, MIXERTYPE_MOTOR=1, MIXERTYPE_SERVO=2, MIXERTYPE_CAMERAROLL=3, MIXERTYPE_CAMERAPITCH=4, MIXERTYPE_CAMERAYAW=5, MIXERTYPE_ACCESSORY0=6, MIXERTYPE_ACCESSORY1=7, MIXERTYPE_ACCESSORY2=8, MIXERTYPE_ACCESSORY3=9, MIXERTYPE_ACCESSORY4=10, MIXERTYPE_ACCESSORY5=11 } MixerTypeElem; typedef enum { MIXERTYPE_DISABLED=0, MIXERTYPE_MOTOR=1, MIXERTYPE_SERVO=2, MIXERTYPE_CAMERAROLL=3, MIXERTYPE_CAMERAPITCH=4, MIXERTYPE_CAMERAYAW=5, MIXERTYPE_ACCESSORY0=6, MIXERTYPE_ACCESSORY1=7, MIXERTYPE_ACCESSORY2=8, MIXERTYPE_ACCESSORY3=9, MIXERTYPE_ACCESSORY4=10, MIXERTYPE_ACCESSORY5=11 } MixerTypeElem;
/* Array element names for field MixerVector */ /* Array element names for field MixerVector */
@ -127,6 +130,8 @@ class VehicleConfig: public ConfigTaskWidget
void resetMixerVector(UAVDataObject* mixer, int channel); void resetMixerVector(UAVDataObject* mixer, int channel);
QString getMixerType(UAVDataObject* mixer, int channel); QString getMixerType(UAVDataObject* mixer, int channel);
void setMixerType(UAVDataObject* mixer, int channel, MixerTypeElem mixerType); void setMixerType(UAVDataObject* mixer, int channel, MixerTypeElem mixerType);
void setThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList<double> curve);
void getThrottleCurve(UAVDataObject* mixer, MixerThrottleCurveElem curveType, QList<double>* curve);
virtual void ResetActuators(GUIConfigDataUnion* configData); virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions(); virtual QStringList getChannelDescriptions();

View File

@ -46,7 +46,7 @@
#define STICK_MIN_MOVE -8 #define STICK_MIN_MOVE -8
#define STICK_MAX_MOVE 8 #define STICK_MAX_MOVE 8
ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent),wizardStep(wizardNone),loop(NULL),skipflag(false),transmitterType(heli) ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent),wizardStep(wizardNone),transmitterType(heli),loop(NULL),skipflag(false)
{ {
manualCommandObj = ManualControlCommand::GetInstance(getObjectManager()); manualCommandObj = ManualControlCommand::GetInstance(getObjectManager());
manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager()); manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager());

View File

@ -71,16 +71,10 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool))); connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool)));
firstUpdate = true;
// Configure the task widget // Configure the task widget
// Connect the help button // Connect the help button
connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
// Add custom handling of displaying things
connect(this,SIGNAL(refreshWidgetsValuesRequested()), this, SLOT(refreshOutputWidgetsValues()));
addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
// Track the ActuatorSettings object // Track the ActuatorSettings object
@ -125,7 +119,6 @@ ConfigOutputWidget::~ConfigOutputWidget()
*/ */
void ConfigOutputWidget::runChannelTests(bool state) void ConfigOutputWidget::runChannelTests(bool state)
{ {
qDebug()<<"configoutputwidget runChannelTests"<<state;
SystemAlarms * systemAlarmsObj = SystemAlarms::GetInstance(getObjectManager()); SystemAlarms * systemAlarmsObj = SystemAlarms::GetInstance(getObjectManager());
SystemAlarms::DataFields systemAlarms = systemAlarmsObj->getData(); SystemAlarms::DataFields systemAlarms = systemAlarmsObj->getData();

View File

@ -63,8 +63,6 @@ private:
UAVObject::Metadata accInitialData; UAVObject::Metadata accInitialData;
bool firstUpdate;
bool wasItMe; bool wasItMe;
private slots: private slots:
void stopTests(); void stopTests();

View File

@ -145,7 +145,7 @@ void ConfigPlugin::eraseAllSettings()
// based on UAVO meta data // based on UAVO meta data
objper->setData(data); objper->setData(data);
objper->updated(); objper->updated();
QTimer::singleShot(6000,this,SLOT(eraseFailed())); QTimer::singleShot(FLASH_ERASE_TIMEOUT_MS,this,SLOT(eraseFailed()));
} }
@ -163,7 +163,7 @@ void ConfigPlugin::eraseFailed()
data.Selection = ObjectPersistence::SELECTION_ALLSETTINGS; data.Selection = ObjectPersistence::SELECTION_ALLSETTINGS;
objper->setData(data); objper->setData(data);
objper->updated(); objper->updated();
QTimer::singleShot(1500,this,SLOT(eraseFailed())); QTimer::singleShot(FLASH_ERASE_TIMEOUT_MS,this,SLOT(eraseFailed()));
} else { } else {
disconnect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *))); disconnect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *)));
QMessageBox msgBox; QMessageBox msgBox;
@ -190,7 +190,7 @@ void ConfigPlugin::eraseDone(UAVObject * obj)
if (data.Operation == ObjectPersistence::OPERATION_COMPLETED) { if (data.Operation == ObjectPersistence::OPERATION_COMPLETED) {
settingsErased = true; settingsErased = true;
msgBox.setText(tr("Settings are now erased.")); msgBox.setText(tr("Settings are now erased."));
msgBox.setInformativeText(tr("Please now power-cycle your board to complete reset.")); msgBox.setInformativeText(tr("Please wait for the status LED to begin flashing regularly (up to a minute) then power-cycle your board to complete reset."));
} else { } else {
msgBox.setText(tr("Error trying to erase settings.")); msgBox.setText(tr("Error trying to erase settings."));
msgBox.setInformativeText(tr("Power-cycle your board after removing all blades. Settings might be inconsistent.")); msgBox.setInformativeText(tr("Power-cycle your board after removing all blades. Settings might be inconsistent."));

View File

@ -65,6 +65,8 @@ private slots:
Core::Command* cmd; Core::Command* cmd;
bool settingsErased; bool settingsErased;
static const int FLASH_ERASE_TIMEOUT_MS = 45000;
}; };
#endif // CONFIGPLUGIN_H #endif // CONFIGPLUGIN_H

View File

@ -206,14 +206,13 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
mag_z->setTransform(QTransform::fromScale(1,0),true); mag_z->setTransform(QTransform::fromScale(1,0),true);
// Connect the signals // Connect the signals
connect(m_ui->ahrsCalibStart, SIGNAL(clicked()), this, SLOT(measureNoise()));
connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration())); connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration()));
RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager());
Q_ASSERT(revoCalibration); Q_ASSERT(revoCalibration);
connect(revoCalibration, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues())); connect(revoCalibration, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues()));
connect(m_ui->ahrsSettingsSaveRAM, SIGNAL(clicked()), this, SLOT(SettingsToRam())); connect(m_ui->ahrsSettingsSaveRAM, SIGNAL(clicked()), this, SLOT(SettingsToRAM()));
connect(m_ui->ahrsSettingsSaveSD, SIGNAL(clicked()), this, SLOT(SettingsToFlash())); connect(m_ui->ahrsSettingsSaveSD, SIGNAL(clicked()), this, SLOT(SettingsToFlash()));
connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(sixPointCalibrationMode())); connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(sixPointCalibrationMode()));
connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData()));

View File

@ -36,10 +36,11 @@
#include <math.h> #include <math.h>
#include <QDesktopServices> #include <QDesktopServices>
#include <QUrl> #include <QUrl>
#include <QEventLoop>
#include "systemsettings.h" #include "systemsettings.h"
#include "mixersettings.h" #include "mixersettings.h"
#include "actuatorsettings.h" #include "actuatorsettings.h"
#include <QEventLoop>
/** /**
Helper delegate for the custom mixer editor table. Helper delegate for the custom mixer editor table.
@ -120,6 +121,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
m_aircraft->aircraftType->addItems(airframeTypes); m_aircraft->aircraftType->addItems(airframeTypes);
m_aircraft->aircraftType->setCurrentIndex(0); //Set default vehicle to Fixed Wing m_aircraft->aircraftType->setCurrentIndex(0); //Set default vehicle to Fixed Wing
m_aircraft->airframesWidget->setCurrentIndex(0); // Force the tab index to match
QStringList fixedWingTypes; QStringList fixedWingTypes;
fixedWingTypes << "Elevator aileron rudder" << "Elevon" << "Vtail"; fixedWingTypes << "Elevator aileron rudder" << "Elevon" << "Vtail";
@ -781,76 +783,64 @@ void ConfigVehicleTypeWidget::resetField(UAVObjectField * field)
*/ */
void ConfigVehicleTypeWidget::updateCustomAirframeUI() void ConfigVehicleTypeWidget::updateCustomAirframeUI()
{ {
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
VehicleConfig* vconfig = new VehicleConfig();
QList<double> curveValues; QList<double> curveValues;
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings"))); // setup throttlecurve 1
Q_ASSERT(obj); vconfig->getThrottleCurve(mixer,VehicleConfig::MIXER_THROTTLECURVE1,&curveValues);
UAVObjectField* field = obj->getField(QString("ThrottleCurve1")); int total = 0;
if (field) for (int i=0; i<curveValues.length(); i++)
{ total += curveValues.at(i);
// If the 1st element of the curve is <= -10, then the curve
// is a straight line (that's how the mixer works on the mainboard): if (curveValues.at(0) <= -10 || total == 0) {
if (field->getValue(0).toInt() <= -10) { m_aircraft->customThrottle1Curve->initLinearCurve(curveValues.length(),(double)1);
m_aircraft->customThrottle1Curve->initLinearCurve(field->getNumElements(),(double)1);
} else {
double temp=0;
double value;
for (unsigned int i=0; i < field->getNumElements(); i++) {
value=field->getValue(i).toDouble();
temp+=value;
curveValues.append(value);
} }
if(temp==0) else {
m_aircraft->customThrottle1Curve->initLinearCurve(field->getNumElements(),(double)1);
else
m_aircraft->customThrottle1Curve->initCurve(curveValues); m_aircraft->customThrottle1Curve->initCurve(curveValues);
} }
}
curveValues.clear(); // setup throttlecurve 2
vconfig->getThrottleCurve(mixer,VehicleConfig::MIXER_THROTTLECURVE2,&curveValues);
field = obj->getField(QString("ThrottleCurve2")); total = 0;
if (field) for (int i=0; i<curveValues.length(); i++)
{ total += curveValues.at(i);
// If the 1st element of the curve is <= -10, then the curve
// is a straight line (that's how the mixer works on the mainboard): if (curveValues.at(0) <= -10 || total == 0) {
if (field->getValue(0).toInt() <= -10) { m_aircraft->customThrottle2Curve->initLinearCurve(curveValues.length(),(double)1);
m_aircraft->customThrottle2Curve->initLinearCurve(field->getNumElements(),(double)1);
} else {
for (unsigned int i=0; i < field->getNumElements(); i++) {
curveValues.append(field->getValue(i).toDouble());
} }
else {
m_aircraft->customThrottle2Curve->initCurve(curveValues); m_aircraft->customThrottle2Curve->initCurve(curveValues);
} }
}
// Update the table:
for (int i=0; i<8; i++) { // Update the mixer table:
field = obj->getField(mixerTypes.at(i)); for (int channel=0; channel<8; channel++) {
UAVObjectField* field = mixer->getField(mixerTypes.at(channel));
if (field) if (field)
{ {
QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,i); QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,channel);
if (q) if (q)
{ {
QString s = field->getValue().toString(); QString s = field->getValue().toString();
setComboCurrentIndex(q, q->findText(s)); setComboCurrentIndex(q, q->findText(s));
} }
field = obj->getField(mixerVectors.at(i)); m_aircraft->customMixerTable->item(1,channel)->setText(
if (field) QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1)));
{ m_aircraft->customMixerTable->item(2,channel)->setText(
int ti = field->getElementNames().indexOf("ThrottleCurve1"); QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE2)));
m_aircraft->customMixerTable->item(1,i)->setText(field->getValue(ti).toString()); m_aircraft->customMixerTable->item(3,channel)->setText(
ti = field->getElementNames().indexOf("ThrottleCurve2"); QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_ROLL)));
m_aircraft->customMixerTable->item(2,i)->setText(field->getValue(ti).toString()); m_aircraft->customMixerTable->item(4,channel)->setText(
ti = field->getElementNames().indexOf("Roll"); QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_PITCH)));
m_aircraft->customMixerTable->item(3,i)->setText(field->getValue(ti).toString()); m_aircraft->customMixerTable->item(5,channel)->setText(
ti = field->getElementNames().indexOf("Pitch"); QString::number(vconfig->getMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_YAW)));
m_aircraft->customMixerTable->item(4,i)->setText(field->getValue(ti).toString());
ti = field->getElementNames().indexOf("Yaw");
m_aircraft->customMixerTable->item(5,i)->setText(field->getValue(ti).toString());
}
} }
} }
} }
@ -865,9 +855,6 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI()
*/ */
void ConfigVehicleTypeWidget::updateObjectsFromWidgets() void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
{ {
UAVDataObject* obj;
UAVObjectField* field;
QString airframeType = "Custom"; //Sets airframe type default to "Custom" QString airframeType = "Custom"; //Sets airframe type default to "Custom"
if (m_aircraft->aircraftType->currentText() == "Fixed Wing") { if (m_aircraft->aircraftType->currentText() == "Fixed Wing") {
airframeType = m_fixedwing->updateConfigObjectsFromWidgets(); airframeType = m_fixedwing->updateConfigObjectsFromWidgets();
@ -882,44 +869,41 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
airframeType = m_groundvehicle->updateConfigObjectsFromWidgets(); airframeType = m_groundvehicle->updateConfigObjectsFromWidgets();
} }
else { else {
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
field = obj->getField(QString("FeedForward"));
// Curve is also common to all quads: UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
field = obj->getField("ThrottleCurve1"); Q_ASSERT(mixer);
QList<double> curve = m_aircraft->customThrottle1Curve->getCurve();
for (int i=0;i<curve.length();i++) {
field->setValue(curve.at(i),i);
}
field = obj->getField("ThrottleCurve2"); VehicleConfig* vconfig = new VehicleConfig();
curve.clear();
curve = m_aircraft->customThrottle2Curve->getCurve(); vconfig->setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->customThrottle1Curve->getCurve());
for (int i=0;i<curve.length();i++) { vconfig->setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, m_aircraft->customThrottle2Curve->getCurve());
field->setValue(curve.at(i),i);
}
// Update the table: // Update the table:
for (int i=0; i<8; i++) { for (int channel=0; channel<8; channel++) {
field = obj->getField(mixerTypes.at(i)); QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,channel);
QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,i);
field->setValue(q->currentText()); vconfig->setMixerType(mixer,channel,
field = obj->getField(mixerVectors.at(i)); q->currentText() == "Servo" ? VehicleConfig::MIXERTYPE_SERVO : VehicleConfig::MIXERTYPE_MOTOR);
int ti = field->getElementNames().indexOf("ThrottleCurve1");
field->setValue(m_aircraft->customMixerTable->item(1,i)->text(),ti); vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1,
ti = field->getElementNames().indexOf("ThrottleCurve2"); m_aircraft->customMixerTable->item(1,channel)->text().toDouble());
field->setValue(m_aircraft->customMixerTable->item(2,i)->text(),ti); vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE2,
ti = field->getElementNames().indexOf("Roll"); m_aircraft->customMixerTable->item(2,channel)->text().toDouble());
field->setValue(m_aircraft->customMixerTable->item(3,i)->text(),ti); vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_ROLL,
ti = field->getElementNames().indexOf("Pitch"); m_aircraft->customMixerTable->item(3,channel)->text().toDouble());
field->setValue(m_aircraft->customMixerTable->item(4,i)->text(),ti); vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_PITCH,
ti = field->getElementNames().indexOf("Yaw"); m_aircraft->customMixerTable->item(4,channel)->text().toDouble());
field->setValue(m_aircraft->customMixerTable->item(5,i)->text(),ti); vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_YAW,
m_aircraft->customMixerTable->item(5,channel)->text().toDouble());
} }
} }
// set the airframe type // set the airframe type
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings"))); UAVDataObject* system = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
field = obj->getField(QString("AirframeType")); Q_ASSERT(system);
QPointer<UAVObjectField> field = system->getField(QString("AirframeType"));
if (field)
field->setValue(airframeType); field->setValue(airframeType);
updateCustomAirframeUI(); updateCustomAirframeUI();

View File

@ -38,6 +38,7 @@
#include "cfg_vehicletypes/configfixedwingwidget.h" #include "cfg_vehicletypes/configfixedwingwidget.h"
#include "cfg_vehicletypes/configmultirotorwidget.h" #include "cfg_vehicletypes/configmultirotorwidget.h"
#include "cfg_vehicletypes/configgroundvehiclewidget.h" #include "cfg_vehicletypes/configgroundvehiclewidget.h"
#include "cfg_vehicletypes/vehicleconfig.h"
#include <QtGui/QWidget> #include <QtGui/QWidget>
#include <QList> #include <QList>

View File

@ -495,7 +495,7 @@
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>0</x> <x>0</x>
<y>-114</y> <y>0</y>
<width>673</width> <width>673</width>
<height>790</height> <height>790</height>
</rect> </rect>
@ -11797,7 +11797,7 @@ border-radius: 4;
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="3">
<widget class="QPushButton" name="pushButton_4"> <widget class="QPushButton" name="pushButton_4">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed"> <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
@ -11850,7 +11850,7 @@ border-radius: 4;
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="0" colspan="3"> <item row="1" column="0" colspan="4">
<widget class="QGroupBox" name="RateStabilizationGroup_9"> <widget class="QGroupBox" name="RateStabilizationGroup_9">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -14693,6 +14693,19 @@ value as the Kp.</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="0" column="2">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</widget> </widget>
</item> </item>
@ -15272,7 +15285,7 @@ value as the Kp.</string>
<bool>false</bool> <bool>false</bool>
</property> </property>
<layout class="QGridLayout" name="gridLayout_4"> <layout class="QGridLayout" name="gridLayout_4">
<item row="1" column="0" colspan="3"> <item row="1" column="0" colspan="4">
<widget class="QGroupBox" name="RateStabilizationGroup_5"> <widget class="QGroupBox" name="RateStabilizationGroup_5">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -17936,7 +17949,7 @@ border-radius: 5;</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="0" column="2"> <item row="0" column="3">
<widget class="QPushButton" name="pushButton_2"> <widget class="QPushButton" name="pushButton_2">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed"> <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
@ -17999,6 +18012,19 @@ border-radius: 4;
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</widget> </widget>
</item> </item>

View File

@ -1,5 +1,5 @@
TEMPLATE = lib TEMPLATE = lib
TARGET = HITLV2 TARGET = HITLv2
QT += network QT += network
include(../../openpilotgcsplugin.pri) include(../../openpilotgcsplugin.pri)
include(hitlv2_dependencies.pri) include(hitlv2_dependencies.pri)

View File

@ -128,7 +128,7 @@ QList <Core::IConnection::device> SerialConnection::availableDevices()
foreach( QextPortInfo port, ports ) { foreach( QextPortInfo port, ports ) {
device d; device d;
d.displayName=port.friendName; d.displayName=port.friendName;
d.name=port.friendName; d.name=port.physName;
list.append(d); list.append(d);
} }
} }
@ -143,7 +143,7 @@ QIODevice *SerialConnection::openDevice(const QString &deviceName)
} }
QList<QextPortInfo> ports = QextSerialEnumerator::getPorts(); QList<QextPortInfo> ports = QextSerialEnumerator::getPorts();
foreach( QextPortInfo port, ports ) { foreach( QextPortInfo port, ports ) {
if(port.friendName == deviceName) if(port.physName == deviceName)
{ {
//we need to handle port settings here... //we need to handle port settings here...
PortSettings set; PortSettings set;

View File

@ -27,6 +27,77 @@
#include "treeitem.h" #include "treeitem.h"
/* Constructor */
HighLightManager::HighLightManager(long checkingInterval)
{
// Start the timer and connect it to the callback
m_expirationTimer.start(checkingInterval);
connect(&m_expirationTimer, SIGNAL(timeout()), this, SLOT(checkItemsExpired()));
}
/*
* Called to add item to list. Item is only added if absent.
* Returns true if item was added, otherwise false.
*/
bool HighLightManager::add(TreeItem *itemToAdd)
{
// Lock to ensure thread safety
QMutexLocker locker(&m_listMutex);
// Check so that the item isn't already in the list
if(!m_itemsList.contains(itemToAdd))
{
m_itemsList.append(itemToAdd);
return true;
}
return false;
}
/*
* Called to remove item from list.
* Returns true if item was removed, otherwise false.
*/
bool HighLightManager::remove(TreeItem *itemToRemove)
{
// Lock to ensure thread safety
QMutexLocker locker(&m_listMutex);
// Remove item and return result
return m_itemsList.removeOne(itemToRemove);
}
/*
* Callback called periodically by the timer.
* This method checks for expired highlights and
* removes them if they are expired.
* Expired highlights are restored.
*/
void HighLightManager::checkItemsExpired()
{
// Lock to ensure thread safety
QMutexLocker locker(&m_listMutex);
// Get a mutable iterator for the list
QMutableLinkedListIterator<TreeItem*> iter(m_itemsList);
// This is the timestamp to compare with
QTime now = QTime::currentTime();
// Loop over all items, check if they expired.
while(iter.hasNext())
{
TreeItem* item = iter.next();
if(item->getHiglightExpires() < now)
{
// If expired, call removeHighlight
item->removeHighlight();
// Remove from list since it is restored.
iter.remove();
}
}
}
int TreeItem::m_highlightTimeMs = 500; int TreeItem::m_highlightTimeMs = 500;
TreeItem::TreeItem(const QList<QVariant> &data, TreeItem *parent) : TreeItem::TreeItem(const QList<QVariant> &data, TreeItem *parent) :
@ -36,7 +107,6 @@ TreeItem::TreeItem(const QList<QVariant> &data, TreeItem *parent) :
m_highlight(false), m_highlight(false),
m_changed(false) m_changed(false)
{ {
connect(&m_timer, SIGNAL(timeout()), this, SLOT(removeHighlight()));
} }
TreeItem::TreeItem(const QVariant &data, TreeItem *parent) : TreeItem::TreeItem(const QVariant &data, TreeItem *parent) :
@ -46,7 +116,6 @@ TreeItem::TreeItem(const QVariant &data, TreeItem *parent) :
m_changed(false) m_changed(false)
{ {
m_data << data << "" << ""; m_data << data << "" << "";
connect(&m_timer, SIGNAL(timeout()), this, SLOT(removeHighlight()));
} }
TreeItem::~TreeItem() TreeItem::~TreeItem()
@ -108,21 +177,50 @@ void TreeItem::apply() {
child->apply(); child->apply();
} }
/*
* Called after a value has changed to trigger highlightning of tree item.
*/
void TreeItem::setHighlight(bool highlight) { void TreeItem::setHighlight(bool highlight) {
m_highlight = highlight; m_highlight = highlight;
m_changed = false; m_changed = false;
if (highlight) { if (highlight) {
if (m_timer.isActive()) { // Update the expires timestamp
m_timer.stop(); m_highlightExpires = QTime::currentTime().addMSecs(m_highlightTimeMs);
}
m_timer.setSingleShot(true); // Add to highlightmanager
m_timer.start(m_highlightTimeMs); if(m_highlightManager->add(this))
} {
// Only emit signal if it was added
emit updateHighlight(this); emit updateHighlight(this);
} }
}
else if(m_highlightManager->remove(this))
{
// Only emit signal if it was removed
emit updateHighlight(this);
}
// If we have a parent, call recursively to update highlight status of parents.
// This will ensure that the root of a leaf that is changed also is highlighted.
// Only updates that really changes values will trigger highlight of parents.
if(m_parent)
{
m_parent->setHighlight(highlight);
}
}
void TreeItem::removeHighlight() { void TreeItem::removeHighlight() {
m_highlight = false; m_highlight = false;
update(); //update();
emit updateHighlight(this); emit updateHighlight(this);
} }
void TreeItem::setHighlightManager(HighLightManager *mgr)
{
m_highlightManager = mgr;
}
QTime TreeItem::getHiglightExpires()
{
return m_highlightExpires;
}

View File

@ -32,10 +32,58 @@
#include "uavmetaobject.h" #include "uavmetaobject.h"
#include "uavobjectfield.h" #include "uavobjectfield.h"
#include <QtCore/QList> #include <QtCore/QList>
#include <QtCore/QLinkedList>
#include <QtCore/QVariant> #include <QtCore/QVariant>
#include <QtCore/QTime>
#include <QtCore/QTimer> #include <QtCore/QTimer>
#include <QtCore/QObject> #include <QtCore/QObject>
#include <QtCore/QDebug>
class TreeItem;
/*
* Small utility class that handles the higlighting of
* tree grid items.
* Basicly it maintains all items due to be restored to
* non highlighted state in a linked list.
* A timer traverses this list periodically to find out
* if any of the items should be restored. All items are
* updated withan expiration timestamp when they expires.
* An item that is beeing restored is removed from the
* list and its removeHighlight() method is called. Items
* that are not expired are left in the list til next time.
* Items that are updated during the expiration time are
* left untouched in the list. This reduces unwanted emits
* of signals to the repaint/update function.
*/
class HighLightManager : public QObject
{
Q_OBJECT
public:
// Constructor taking the checking interval in ms.
HighLightManager(long checkingInterval);
// This is called when an item has been set to
// highlighted = true.
bool add(TreeItem* itemToAdd);
//This is called when an item is set to highlighted = false;
bool remove(TreeItem* itemToRemove);
private slots:
// Timer callback method.
void checkItemsExpired();
private:
// The timer checking highlight expiration.
QTimer m_expirationTimer;
// The list holding all items due to be updated.
QLinkedList<TreeItem*> m_itemsList;
//Mutex to lock when accessing list.
QMutex m_listMutex;
};
class TreeItem : public QObject class TreeItem : public QObject
{ {
@ -77,11 +125,16 @@ public:
inline bool changed() { return m_changed; } inline bool changed() { return m_changed; }
inline void setChanged(bool changed) { m_changed = changed; } inline void setChanged(bool changed) { m_changed = changed; }
virtual void setHighlightManager(HighLightManager* mgr);
QTime getHiglightExpires();
virtual void removeHighlight();
signals: signals:
void updateHighlight(TreeItem*); void updateHighlight(TreeItem*);
private slots: private slots:
void removeHighlight();
private: private:
QList<TreeItem*> m_children; QList<TreeItem*> m_children;
@ -91,7 +144,8 @@ private:
TreeItem *m_parent; TreeItem *m_parent;
bool m_highlight; bool m_highlight;
bool m_changed; bool m_changed;
QTimer m_timer; QTime m_highlightExpires;
HighLightManager* m_highlightManager;
public: public:
static const int dataColumn = 1; static const int dataColumn = 1;
private: private:

View File

@ -47,6 +47,8 @@ UAVObjectTreeModel::UAVObjectTreeModel(QObject *parent) :
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>(); UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
// Create highlight manager, let it run every 300 ms.
m_highlightManager = new HighLightManager(300);
connect(objManager, SIGNAL(newObject(UAVObject*)), this, SLOT(newObject(UAVObject*))); connect(objManager, SIGNAL(newObject(UAVObject*)), this, SLOT(newObject(UAVObject*)));
connect(objManager, SIGNAL(newInstance(UAVObject*)), this, SLOT(newObject(UAVObject*))); connect(objManager, SIGNAL(newInstance(UAVObject*)), this, SLOT(newObject(UAVObject*)));
@ -56,6 +58,7 @@ UAVObjectTreeModel::UAVObjectTreeModel(QObject *parent) :
UAVObjectTreeModel::~UAVObjectTreeModel() UAVObjectTreeModel::~UAVObjectTreeModel()
{ {
delete m_highlightManager;
delete m_rootItem; delete m_rootItem;
} }
@ -67,9 +70,12 @@ void UAVObjectTreeModel::setupModelData(UAVObjectManager *objManager)
m_rootItem = new TreeItem(rootData); m_rootItem = new TreeItem(rootData);
m_settingsTree = new TopTreeItem(tr("Settings"), m_rootItem); m_settingsTree = new TopTreeItem(tr("Settings"), m_rootItem);
m_settingsTree->setHighlightManager(m_highlightManager);
m_rootItem->appendChild(m_settingsTree); m_rootItem->appendChild(m_settingsTree);
m_nonSettingsTree = new TopTreeItem(tr("Data Objects"), m_rootItem); m_nonSettingsTree = new TopTreeItem(tr("Data Objects"), m_rootItem);
m_nonSettingsTree->setHighlightManager(m_highlightManager);
m_rootItem->appendChild(m_nonSettingsTree); m_rootItem->appendChild(m_nonSettingsTree);
m_rootItem->setHighlightManager(m_highlightManager);
connect(m_settingsTree, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*))); connect(m_settingsTree, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
connect(m_nonSettingsTree, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*))); connect(m_nonSettingsTree, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
@ -96,6 +102,7 @@ void UAVObjectTreeModel::addDataObject(UAVDataObject *obj)
addInstance(obj, root->child(index)); addInstance(obj, root->child(index));
} else { } else {
DataObjectTreeItem *data = new DataObjectTreeItem(obj->getName() + " (" + QString::number(obj->getNumBytes()) + " bytes)"); DataObjectTreeItem *data = new DataObjectTreeItem(obj->getName() + " (" + QString::number(obj->getNumBytes()) + " bytes)");
data->setHighlightManager(m_highlightManager);
connect(data, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*))); connect(data, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
int index = root->nameIndex(obj->getName()); int index = root->nameIndex(obj->getName());
root->insert(index, data); root->insert(index, data);
@ -110,6 +117,7 @@ void UAVObjectTreeModel::addMetaObject(UAVMetaObject *obj, TreeItem *parent)
{ {
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(highlightUpdatedObject(UAVObject*))); connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(highlightUpdatedObject(UAVObject*)));
MetaObjectTreeItem *meta = new MetaObjectTreeItem(obj, tr("Meta Data")); MetaObjectTreeItem *meta = new MetaObjectTreeItem(obj, tr("Meta Data"));
meta->setHighlightManager(m_highlightManager);
connect(meta, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*))); connect(meta, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
foreach (UAVObjectField *field, obj->getFields()) { foreach (UAVObjectField *field, obj->getFields()) {
if (field->getNumElements() > 1) { if (field->getNumElements() > 1) {
@ -132,6 +140,7 @@ void UAVObjectTreeModel::addInstance(UAVObject *obj, TreeItem *parent)
} else { } else {
QString name = tr("Instance") + " " + QString::number(obj->getInstID()); QString name = tr("Instance") + " " + QString::number(obj->getInstID());
item = new InstanceTreeItem(obj, name); item = new InstanceTreeItem(obj, name);
item->setHighlightManager(m_highlightManager);
connect(item, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*))); connect(item, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
parent->appendChild(item); parent->appendChild(item);
} }
@ -148,6 +157,7 @@ void UAVObjectTreeModel::addInstance(UAVObject *obj, TreeItem *parent)
void UAVObjectTreeModel::addArrayField(UAVObjectField *field, TreeItem *parent) void UAVObjectTreeModel::addArrayField(UAVObjectField *field, TreeItem *parent)
{ {
TreeItem *item = new ArrayFieldTreeItem(field->getName()); TreeItem *item = new ArrayFieldTreeItem(field->getName());
item->setHighlightManager(m_highlightManager);
connect(item, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*))); connect(item, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
for (uint i = 0; i < field->getNumElements(); ++i) { for (uint i = 0; i < field->getNumElements(); ++i) {
addSingleField(i, field, item); addSingleField(i, field, item);
@ -192,6 +202,7 @@ void UAVObjectTreeModel::addSingleField(int index, UAVObjectField *field, TreeIt
default: default:
Q_ASSERT(false); Q_ASSERT(false);
} }
item->setHighlightManager(m_highlightManager);
connect(item, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*))); connect(item, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*)));
parent->appendChild(item); parent->appendChild(item);
} }
@ -352,7 +363,6 @@ void UAVObjectTreeModel::highlightUpdatedObject(UAVObject *obj)
Q_ASSERT(obj); Q_ASSERT(obj);
ObjectTreeItem *item = findObjectTreeItem(obj); ObjectTreeItem *item = findObjectTreeItem(obj);
Q_ASSERT(item); Q_ASSERT(item);
item->setHighlight(true);
item->update(); item->update();
QModelIndex itemIndex = index(item); QModelIndex itemIndex = index(item);
Q_ASSERT(itemIndex != QModelIndex()); Q_ASSERT(itemIndex != QModelIndex());

View File

@ -97,6 +97,9 @@ private:
int m_recentlyUpdatedTimeout; int m_recentlyUpdatedTimeout;
QColor m_recentlyUpdatedColor; QColor m_recentlyUpdatedColor;
QColor m_manuallyChangedColor; QColor m_manuallyChangedColor;
// Highlight manager to handle highlighting of tree items.
HighLightManager *m_highlightManager;
}; };
#endif // UAVOBJECTTREEMODEL_H #endif // UAVOBJECTTREEMODEL_H

View File

@ -84,7 +84,7 @@ public:
}; };
ConfigTaskWidget(QWidget *parent = 0); ConfigTaskWidget(QWidget *parent = 0);
~ConfigTaskWidget(); virtual ~ConfigTaskWidget();
void disableMouseWheelEvents(); void disableMouseWheelEvents();
bool eventFilter( QObject * obj, QEvent * evt ); bool eventFilter( QObject * obj, QEvent * evt );

View File

@ -43,6 +43,7 @@ Node::Node(MixerCurveWidget *graphWidget)
setCacheMode(DeviceCoordinateCache); setCacheMode(DeviceCoordinateCache);
setZValue(-1); setZValue(-1);
vertical = false; vertical = false;
value = 0;
} }
void Node::addEdge(Edge *edge) void Node::addEdge(Edge *edge)
@ -98,6 +99,15 @@ void Node::verticalMove(bool flag){
vertical = flag; vertical = flag;
} }
double Node::getValue() {
return value;
}
void Node::setValue(double val) {
value = val;
}
QVariant Node::itemChange(GraphicsItemChange change, const QVariant &value) QVariant Node::itemChange(GraphicsItemChange change, const QVariant &value)
{ {
@ -117,11 +127,19 @@ QVariant Node::itemChange(GraphicsItemChange change, const QVariant &value)
newPos.setY(h); newPos.setY(h);
return newPos; return newPos;
} }
case ItemPositionHasChanged: case ItemPositionHasChanged: {
foreach (Edge *edge, edgeList) foreach (Edge *edge, edgeList)
edge->adjust(); edge->adjust();
graph->itemMoved((h-newPos.y())/h);
double min = graph->getMin();
double range = graph->getMax() - min;
double ratio = (h - newPos.y()) / h;
double val = (range * ratio ) + min;
setValue(val);
graph->itemMoved(val);
break; break;
}
default: default:
break; break;
}; };

View File

@ -48,12 +48,16 @@ public:
enum { Type = UserType + 1 }; enum { Type = UserType + 1 };
int type() const { return Type; } int type() const { return Type; }
void verticalMove(bool flag); void verticalMove(bool flag);
QRectF boundingRect() const; QRectF boundingRect() const;
QPainterPath shape() const; QPainterPath shape() const;
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget);
void setValue(double val);
double getValue();
protected: protected:
QVariant itemChange(GraphicsItemChange change, const QVariant &value); QVariant itemChange(GraphicsItemChange change, const QVariant &value);
@ -61,6 +65,8 @@ protected:
void mouseReleaseEvent(QGraphicsSceneMouseEvent *event); void mouseReleaseEvent(QGraphicsSceneMouseEvent *event);
private: private:
double value;
QList<Edge *> edgeList; QList<Edge *> edgeList;
QPointF newPos; QPointF newPos;
MixerCurveWidget *graph; MixerCurveWidget *graph;

View File

@ -32,8 +32,6 @@
#include <QtGui> #include <QtGui>
#include <QDebug> #include <QDebug>
/* /*
* Initialize the widget * Initialize the widget
*/ */
@ -74,11 +72,48 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent)
scene->setSceneRect(plot->boundingRect()); scene->setSceneRect(plot->boundingRect());
setScene(scene); setScene(scene);
initNodes(MixerCurveWidget::NODE_NUMELEM);
} }
MixerCurveWidget::~MixerCurveWidget() MixerCurveWidget::~MixerCurveWidget()
{ {
for (int i=0; i<nodePool.count(); i++)
delete nodePool.at(i);
for (int i=0; i<edgePool.count(); i++)
delete edgePool.at(i);
}
Node* MixerCurveWidget::getNode(int index)
{
Node* node;
if (index >= 0 && index < nodePool.count())
{
node = nodePool.at(index);
}
else {
node = new Node(this);
nodePool.append(node);
}
return node;
}
Edge* MixerCurveWidget::getEdge(int index, Node* sourceNode, Node* destNode)
{
Edge* edge;
if (index >= 0 && index < edgePool.count())
{
edge = edgePool.at(index);
edge->setSourceNode(sourceNode);
edge->setDestNode(destNode);
}
else {
edge = new Edge(sourceNode,destNode);
edgePool.append(edge);
}
return edge;
} }
/** /**
@ -89,60 +124,62 @@ MixerCurveWidget::~MixerCurveWidget()
*/ */
void MixerCurveWidget::initCurve(QList<double> points) void MixerCurveWidget::initCurve(QList<double> points)
{ {
if (points.length() < 2) if (points.length() < 2)
return; // We need at least 2 points on a curve! return; // We need at least 2 points on a curve!
// First of all, reset the list if (nodeList.count() != points.count())
// TODO: one edge might not get deleted properly, small mem leak maybe... initNodes(points.count());
// finally, set node positions
setCurve(points);
}
void MixerCurveWidget::initNodes(int numPoints)
{
// First of all, clear any existing list
if (nodeList.count()) {
foreach (Node *node, nodeList ) { foreach (Node *node, nodeList ) {
QList<Edge*> edges = node->edges(); QList<Edge*> edges = node->edges();
foreach(Edge *edge, edges) { foreach(Edge *edge, edges) {
if (scene()->items().contains(edge)) if (edge->destNode() == node) {
scene()->removeItem(edge);
else
delete edge; delete edge;
} }
else {
scene()->removeItem(edge);
}
}
scene()->removeItem(node); scene()->removeItem(node);
delete node;
} }
nodeList.clear(); nodeList.clear();
}
// Create the nodes and edges
Node* prevNode = 0;
for (int i=0; i<numPoints; i++) {
Node *node = getNode(i);
// Create the nodes
qreal w = plot->boundingRect().width()/(points.length()-1);
qreal h = plot->boundingRect().height();
for (int i=0; i<points.length(); i++) {
Node *node = new Node(this);
scene()->addItem(node);
nodeList.append(node); nodeList.append(node);
double val = points.at(i); scene()->addItem(node);
if (val>curveMax)
val=curveMax; if (prevNode) {
if (val<curveMin) scene()->addItem(getEdge(i, prevNode, node));
val=curveMin;
val+=curveMin;
val/=(curveMax-curveMin);
node->setPos(w*i,h-val*h);
node->verticalMove(true);
} }
// ... and link them together: prevNode = node;
for (int i=0; i<(points.length()-1); i++) {
scene()->addItem(new Edge(nodeList.at(i),nodeList.at(i+1)));
} }
} }
/** /**
Returns the current curve settings Returns the current curve settings
*/ */
QList<double> MixerCurveWidget::getCurve() { QList<double> MixerCurveWidget::getCurve() {
QList<double> list; QList<double> list;
qreal h = plot->boundingRect().height();
foreach(Node *node, nodeList) { foreach(Node *node, nodeList) {
list.append(((curveMax-curveMin)*(h-node->pos().y())/h)+curveMin); list.append(node->getValue());
} }
return list; return list;
@ -150,11 +187,15 @@ QList<double> MixerCurveWidget::getCurve() {
/** /**
Sets a linear graph Sets a linear graph
*/ */
void MixerCurveWidget::initLinearCurve(quint32 numPoints, double maxValue) void MixerCurveWidget::initLinearCurve(quint32 numPoints, double maxValue, double minValue)
{ {
Q_UNUSED(maxValue);
Q_UNUSED(minValue);
QList<double> points; QList<double> points;
for (double i=0; i<numPoints;i++) { for (double i=0; i<numPoints;i++) {
points.append(maxValue*(i/(numPoints-1))); double val = ((curveMax - curveMin) * (i/(numPoints-1))) + curveMin;
points.append(val);
} }
initCurve(points); initCurve(points);
} }
@ -163,25 +204,35 @@ void MixerCurveWidget::initLinearCurve(quint32 numPoints, double maxValue)
*/ */
void MixerCurveWidget::setCurve(QList<double> points) void MixerCurveWidget::setCurve(QList<double> points)
{ {
if (nodeList.length()<1) curveUpdating = true;
{
initCurve(points); if (nodeList.count() != points.count())
} initNodes(points.count());
else
{ double min = curveMin + 10;
qreal w = plot->boundingRect().width()/(points.length()-1); double max = curveMax + 10;
qreal w = plot->boundingRect().width()/(points.count()-1);
qreal h = plot->boundingRect().height(); qreal h = plot->boundingRect().height();
for (int i=0; i<points.length(); i++) { for (int i=0; i<points.count(); i++) {
double val = points.at(i); double val = points.at(i);
if (val>curveMax)
val=curveMax;
if (val < curveMin) if (val < curveMin)
val = curveMin; val = curveMin;
val-=curveMin; if (val > curveMax)
val/=(curveMax-curveMin); val = curveMax;
nodeList.at(i)->setPos(w*i,h-val*h);
} val += 10;
val -= min;
val /= (max - min);
nodeList.at(i)->setPos(w*i, h - (val*h));
nodeList.at(i)->verticalMove(true);
} }
curveUpdating = false;
emit curveUpdated(points, (double)0);
} }
@ -205,9 +256,11 @@ void MixerCurveWidget::resizeEvent(QResizeEvent* event)
void MixerCurveWidget::itemMoved(double itemValue) void MixerCurveWidget::itemMoved(double itemValue)
{ {
if (!curveUpdating) {
QList<double> list = getCurve(); QList<double> list = getCurve();
emit curveUpdated(list, itemValue); emit curveUpdated(list, itemValue);
} }
}
void MixerCurveWidget::setMin(double value) void MixerCurveWidget::setMin(double value)
{ {
@ -217,6 +270,14 @@ void MixerCurveWidget::setMax(double value)
{ {
curveMax = value; curveMax = value;
} }
double MixerCurveWidget::getMin()
{
return curveMin;
}
double MixerCurveWidget::getMax()
{
return curveMax;
}
void MixerCurveWidget::setRange(double min, double max) void MixerCurveWidget::setRange(double min, double max)
{ {
curveMin = min; curveMin = min;

View File

@ -31,6 +31,7 @@
#include <QGraphicsView> #include <QGraphicsView>
#include <QtSvg/QSvgRenderer> #include <QtSvg/QSvgRenderer>
#include <QtSvg/QGraphicsSvgItem> #include <QtSvg/QGraphicsSvgItem>
#include <QtCore/QPointer>
#include "mixercurvepoint.h" #include "mixercurvepoint.h"
#include "mixercurveline.h" #include "mixercurveline.h"
#include "uavobjectwidgetutils_global.h" #include "uavobjectwidgetutils_global.h"
@ -45,12 +46,16 @@ public:
void itemMoved(double itemValue); // Callback when a point is moved, to be updated void itemMoved(double itemValue); // Callback when a point is moved, to be updated
void initCurve (QList<double> points); void initCurve (QList<double> points);
QList<double> getCurve(); QList<double> getCurve();
void initLinearCurve(quint32 numPoints, double maxValue); void initLinearCurve(quint32 numPoints, double maxValue = 1, double minValue = 0);
void setCurve(QList<double>); void setCurve(QList<double>);
void setMin(double value); void setMin(double value);
double getMin();
void setMax(double value); void setMax(double value);
double getMax();
void setRange(double min, double max); void setRange(double min, double max);
static const int NODE_NUMELEM = 5;
signals: signals:
void curveUpdated(QList<double>, double ); void curveUpdated(QList<double>, double );
@ -58,9 +63,19 @@ private slots:
private: private:
QGraphicsSvgItem *plot; QGraphicsSvgItem *plot;
QList<Node*> nodePool;
QList<Edge*> edgePool;
QList<Node*> nodeList; QList<Node*> nodeList;
QList<double> points;
double curveMin; double curveMin;
double curveMax; double curveMax;
bool curveUpdating;
void initNodes(int numPoints);
Node* getNode(int index);
Edge* getEdge(int index, Node* sourceNode, Node* destNode);
protected: protected:
void showEvent(QShowEvent *event); void showEvent(QShowEvent *event);

View File

@ -112,12 +112,14 @@ void UAVTalk::processInputStream()
{ {
quint8 tmp; quint8 tmp;
if (io && io->isReadable()) {
while (io->bytesAvailable() > 0) while (io->bytesAvailable() > 0)
{ {
io->read((char*)&tmp, 1); io->read((char*)&tmp, 1);
processInputByte(tmp); processInputByte(tmp);
} }
} }
}
/** /**
* Request an update for the specified object, on success the object data would have been * Request an update for the specified object, on success the object data would have been
@ -719,9 +721,8 @@ bool UAVTalk::transmitNack(quint32 objId)
qToLittleEndian<quint16>(dataOffset, &txBuffer[2]); qToLittleEndian<quint16>(dataOffset, &txBuffer[2]);
// Send buffer, check that the transmit backlog does not grow above limit // Send buffer, check that the transmit backlog does not grow above limit
if ( io->bytesToWrite() < TX_BUFFER_SIZE ) if (io && io->isWritable() && io->bytesToWrite() < TX_BUFFER_SIZE )
{ {
io->write((const char*)txBuffer, dataOffset+CHECKSUM_LENGTH); io->write((const char*)txBuffer, dataOffset+CHECKSUM_LENGTH);
} }
@ -811,7 +812,7 @@ bool UAVTalk::transmitSingleObject(UAVObject* obj, quint8 type, bool allInstance
txBuffer[dataOffset+length] = updateCRC(0, txBuffer, dataOffset + length); txBuffer[dataOffset+length] = updateCRC(0, txBuffer, dataOffset + length);
// Send buffer, check that the transmit backlog does not grow above limit // Send buffer, check that the transmit backlog does not grow above limit
if ( io->bytesToWrite() < TX_BUFFER_SIZE ) if (io && io->isWritable() && io->bytesToWrite() < TX_BUFFER_SIZE )
{ {
io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH);
} }

View File

@ -27,6 +27,7 @@
#ifndef UAVTALK_H #ifndef UAVTALK_H
#define UAVTALK_H #define UAVTALK_H
#include <QtCore>
#include <QIODevice> #include <QIODevice>
#include <QMutex> #include <QMutex>
#include <QMutexLocker> #include <QMutexLocker>
@ -93,7 +94,7 @@ private:
typedef enum {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS} RxStateType; typedef enum {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS} RxStateType;
// Variables // Variables
QIODevice* io; QPointer<QIODevice> io;
UAVObjectManager* objMngr; UAVObjectManager* objMngr;
QMutex* mutex; QMutex* mutex;
UAVObject* respObj; UAVObject* respObj;