1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-02 10:24:11 +01:00

Merge remote-tracking branch 'origin/next' into laurent/OP-1337_French_translations_updates

This commit is contained in:
Laurent Lalanne 2014-09-20 10:42:26 +02:00
commit 7ca288901f
22 changed files with 5154 additions and 7443 deletions

View File

@ -138,6 +138,12 @@
<property name="columnCount">
<number>12</number>
</property>
<property name="editTriggers">
<set>QAbstractItemView::NoEditTriggers</set>
</property>
<property name="selectionMode">
<enum>QAbstractItemView::NoSelection</enum>
</property>
<attribute name="horizontalHeaderDefaultSectionSize">
<number>50</number>
</attribute>

View File

@ -101,7 +101,7 @@ SixPointCalibrationModel::SixPointCalibrationModel(QObject *parent) :
revoCalibration = RevoCalibration::GetInstance(getObjectManager());
Q_ASSERT(revoCalibration);
auxMagSettings = AuxMagSettings::GetInstance(getObjectManager());
auxMagSettings = AuxMagSettings::GetInstance(getObjectManager());
Q_ASSERT(auxMagSettings);
accelGyroSettings = AccelGyroSettings::GetInstance(getObjectManager());
@ -440,7 +440,7 @@ void SixPointCalibrationModel::compute()
double Be_length;
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
AuxMagSettings::DataFields auxCalibrationData = auxMagSettings->getData();
AuxMagSettings::DataFields auxCalibrationData = auxMagSettings->getData();
AccelGyroSettings::DataFields accelGyroSettingsData = accelGyroSettings->getData();
HomeLocation::DataFields homeLocationData = homeLocation->getData();
@ -521,8 +521,8 @@ void SixPointCalibrationModel::compute()
if (good_calibration) {
m_dirty = true;
if (calibratingMag) {
result.revoCalibrationData = revoCalibrationData;
result.auxMagSettingsData = auxCalibrationData;
result.revoCalibrationData = revoCalibrationData;
result.auxMagSettingsData = auxCalibrationData;
displayInstructions(tr("Magnetometer calibration completed successfully."), WizardModel::Success);
}
if (calibratingAccel) {

View File

@ -92,14 +92,14 @@ public:
UAVObject::Metadata accelStateMetadata;
UAVObject::Metadata magSensorMetadata;
UAVObject::Metadata auxMagSensorMetadata;
AuxMagSettings::DataFields auxMagSettings;
AuxMagSettings::DataFields auxMagSettings;
RevoCalibration::DataFields revoCalibrationData;
AccelGyroSettings::DataFields accelGyroSettingsData;
} Memento;
typedef struct {
RevoCalibration::DataFields revoCalibrationData;
AuxMagSettings::DataFields auxMagSettingsData;
AuxMagSettings::DataFields auxMagSettingsData;
AccelGyroSettings::DataFields accelGyroSettingsData;
} Result;

View File

@ -1,13 +1,13 @@
/**
******************************************************************************
*
* @file configmultirotorwidget.cpp
* @file configcustomwidget.cpp
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief ccpm configuration panel
* @brief custom configuration panel
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
@ -45,6 +45,84 @@ QStringList ConfigCustomWidget::getChannelDescriptions()
for (int i = 0; i < (int)VehicleConfig::CHANNEL_NUMELEM; i++) {
channelDesc.append(QString("-"));
}
// get the gui config data
GUIConfigDataUnion configData = getConfigData();
customGUISettingsStruct custom = configData.custom;
if (custom.Motor1 > 0 && custom.Motor1 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Motor1 - 1] = QString("Motor1");
}
if (custom.Motor2 > 0 && custom.Motor2 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Motor2 - 1] = QString("Motor2");
}
if (custom.Motor3 > 0 && custom.Motor3 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Motor3 - 1] = QString("Motor3");
}
if (custom.Motor4 > 0 && custom.Motor4 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Motor4 - 1] = QString("Motor4");
}
if (custom.Motor5 > 0 && custom.Motor5 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Motor5 - 1] = QString("Motor5");
}
if (custom.Motor6 > 0 && custom.Motor6 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Motor6 - 1] = QString("Motor6");
}
if (custom.Motor7 > 0 && custom.Motor7 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Motor7 - 1] = QString("Motor7");
}
if (custom.Motor8 > 0 && custom.Motor8 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Motor8 - 1] = QString("Motor8");
}
if (custom.RevMotor1 > 0 && custom.RevMotor1 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.RevMotor1 - 1] = QString("RevMotor1");
}
if (custom.RevMotor2 > 0 && custom.RevMotor2 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.RevMotor2 - 1] = QString("RevMotor2");
}
if (custom.RevMotor3 > 0 && custom.RevMotor3 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.RevMotor3 - 1] = QString("RevMotor3");
}
if (custom.RevMotor4 > 0 && custom.RevMotor4 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.RevMotor4 - 1] = QString("RevMotor4");
}
if (custom.RevMotor5 > 0 && custom.RevMotor5 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.RevMotor5 - 1] = QString("RevMotor5");
}
if (custom.RevMotor6 > 0 && custom.RevMotor6 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.RevMotor6 - 1] = QString("RevMotor6");
}
if (custom.RevMotor7 > 0 && custom.RevMotor7 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.RevMotor7 - 1] = QString("RevMotor7");
}
if (custom.RevMotor8 > 0 && custom.RevMotor8 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.RevMotor8 - 1] = QString("RevMotor8");
}
if (custom.Servo1 > 0 && custom.Servo1 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Servo1 - 1] = QString("Servo1");
}
if (custom.Servo2 > 0 && custom.Servo2 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Servo2 - 1] = QString("Servo2");
}
if (custom.Servo3 > 0 && custom.Servo3 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Servo3 - 1] = QString("Servo3");
}
if (custom.Servo4 > 0 && custom.Servo4 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Servo4 - 1] = QString("Servo4");
}
if (custom.Servo5 > 0 && custom.Servo5 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Servo5 - 1] = QString("Servo5");
}
if (custom.Servo6 > 0 && custom.Servo6 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Servo6 - 1] = QString("Servo6");
}
if (custom.Servo7 > 0 && custom.Servo7 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Servo7 - 1] = QString("Servo7");
}
if (custom.Servo8 > 0 && custom.Servo8 <= VehicleConfig::CHANNEL_NUMELEM) {
channelDesc[custom.Servo8 - 1] = QString("Servo8");
}
return channelDesc;
}
@ -52,6 +130,7 @@ ConfigCustomWidget::ConfigCustomWidget(QWidget *parent) :
VehicleConfig(parent), m_aircraft(new Ui_CustomConfigWidget())
{
m_aircraft->setupUi(this);
m_aircraft->customMixerTable->setEditTriggers(QAbstractItemView::NoEditTriggers);
// Put combo boxes in line one of the custom mixer table:
UAVDataObject *mixer = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(QString("MixerSettings")));
@ -93,7 +172,30 @@ void ConfigCustomWidget::registerWidgets(ConfigTaskWidget &parent)
void ConfigCustomWidget::resetActuators(GUIConfigDataUnion *configData)
{
Q_UNUSED(configData);
configData->custom.Motor1 = 0;
configData->custom.Motor2 = 0;
configData->custom.Motor3 = 0;
configData->custom.Motor4 = 0;
configData->custom.Motor5 = 0;
configData->custom.Motor6 = 0;
configData->custom.Motor7 = 0;
configData->custom.Motor8 = 0;
configData->custom.RevMotor1 = 0;
configData->custom.RevMotor2 = 0;
configData->custom.RevMotor3 = 0;
configData->custom.RevMotor4 = 0;
configData->custom.RevMotor5 = 0;
configData->custom.RevMotor6 = 0;
configData->custom.RevMotor7 = 0;
configData->custom.RevMotor8 = 0;
configData->custom.Servo1 = 0;
configData->custom.Servo2 = 0;
configData->custom.Servo3 = 0;
configData->custom.Servo4 = 0;
configData->custom.Servo5 = 0;
configData->custom.Servo6 = 0;
configData->custom.Servo7 = 0;
configData->custom.Servo8 = 0;
}
/**
@ -105,9 +207,23 @@ void ConfigCustomWidget::refreshWidgetsValues(QString frameType)
setupUI(frameType);
UAVDataObject *system = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(QString("SystemSettings")));
Q_ASSERT(system);
QPointer<UAVObjectField> field = system->getField(QString("AirframeType"));
// Do not allow table edit until AirframeType == Custom
// First save set AirframeType to 'Custom' and next modify.
if (field->getValue().toString() != "Custom") {
m_aircraft->customMixerTable->setEditTriggers(QAbstractItemView::NoEditTriggers);
} else {
m_aircraft->customMixerTable->setEditTriggers(QAbstractItemView::AllEditTriggers);
}
UAVDataObject *mixer = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
getChannelDescriptions();
QList<double> curveValues;
getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, &curveValues);
@ -162,60 +278,125 @@ void ConfigCustomWidget::refreshWidgetsValues(QString frameType)
}
}
/**
Helper function to
*/
QString ConfigCustomWidget::updateConfigObjectsFromWidgets()
{
UAVDataObject *mixer = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(QString("MixerSettings")));
UAVDataObject *system = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(QString("SystemSettings")));
Q_ASSERT(mixer);
Q_ASSERT(system);
setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->customThrottle1Curve->getCurve());
setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, m_aircraft->customThrottle2Curve->getCurve());
QPointer<UAVObjectField> field = system->getField(QString("AirframeType"));
// Update the table:
for (int channel = 0; channel < (int)VehicleConfig::CHANNEL_NUMELEM; channel++) {
QComboBox *q = (QComboBox *)m_aircraft->customMixerTable->cellWidget(0, channel);
if (q->currentText() == "Disabled") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_DISABLED);
} else if (q->currentText() == "Motor") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR);
} else if (q->currentText() == "ReversableMotor") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_REVERSABLEMOTOR);
} else if (q->currentText() == "Servo") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
} else if (q->currentText() == "CameraRoll") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_CAMERAROLL);
} else if (q->currentText() == "CameraPitch") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_CAMERAPITCH);
} else if (q->currentText() == "CameraYaw") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_CAMERAYAW);
} else if (q->currentText() == "Accessory0") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY0);
} else if (q->currentText() == "Accessory1") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY1);
} else if (q->currentText() == "Accessory2") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY2);
} else if (q->currentText() == "Accessory3") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY3);
} else if (q->currentText() == "Accessory4") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY4);
} else if (q->currentText() == "Accessory5") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY5);
// Do not allow changes until AirframeType == Custom
// If user want to save custom mixer : first set AirframeType to 'Custom' without changes and next modify.
if (field->getValue().toString() == "Custom") {
UAVDataObject *mixer = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->customThrottle1Curve->getCurve());
setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, m_aircraft->customThrottle2Curve->getCurve());
GUIConfigDataUnion configData = getConfigData();
resetActuators(&configData);
// Update the table:
for (int channel = 0; channel < (int)VehicleConfig::CHANNEL_NUMELEM; channel++) {
QComboBox *q = (QComboBox *)m_aircraft->customMixerTable->cellWidget(0, channel);
if (q->currentText() == "Disabled") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_DISABLED);
} else if (q->currentText() == "Motor") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR);
if (configData.custom.Motor1 == 0) {
configData.custom.Motor1 = channel + 1;
} else if (configData.custom.Motor2 == 0) {
configData.custom.Motor2 = channel + 1;
} else if (configData.custom.Motor3 == 0) {
configData.custom.Motor3 = channel + 1;
} else if (configData.custom.Motor4 == 0) {
configData.custom.Motor4 = channel + 1;
} else if (configData.custom.Motor5 == 0) {
configData.custom.Motor5 = channel + 1;
} else if (configData.custom.Motor6 == 0) {
configData.custom.Motor6 = channel + 1;
} else if (configData.custom.Motor7 == 0) {
configData.custom.Motor7 = channel + 1;
} else if (configData.custom.Motor8 == 0) {
configData.custom.Motor8 = channel + 1;
}
} else if (q->currentText() == "ReversableMotor") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_REVERSABLEMOTOR);
if (configData.custom.RevMotor1 == 0) {
configData.custom.RevMotor1 = channel + 1;
} else if (configData.custom.RevMotor2 == 0) {
configData.custom.RevMotor2 = channel + 1;
} else if (configData.custom.RevMotor3 == 0) {
configData.custom.RevMotor3 = channel + 1;
} else if (configData.custom.RevMotor4 == 0) {
configData.custom.RevMotor4 = channel + 1;
} else if (configData.custom.RevMotor5 == 0) {
configData.custom.RevMotor5 = channel + 1;
} else if (configData.custom.RevMotor6 == 0) {
configData.custom.RevMotor6 = channel;
} else if (configData.custom.RevMotor7 == 0) {
configData.custom.RevMotor7 = channel;
} else if (configData.custom.RevMotor8 == 0) {
configData.custom.RevMotor8 = channel;
}
} else if (q->currentText() == "Servo") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
if (configData.custom.Servo1 == 0) {
configData.custom.Servo1 = channel + 1;
} else if (configData.custom.Servo2 == 0) {
configData.custom.Servo2 = channel + 1;
} else if (configData.custom.Servo3 == 0) {
configData.custom.Servo3 = channel + 1;
} else if (configData.custom.Servo4 == 0) {
configData.custom.Servo4 = channel + 1;
} else if (configData.custom.Servo5 == 0) {
configData.custom.Servo5 = channel + 1;
} else if (configData.custom.Servo6 == 0) {
configData.custom.Servo6 = channel + 1;
} else if (configData.custom.Servo7 == 0) {
configData.custom.Servo7 = channel + 1;
} else if (configData.custom.Servo8 == 0) {
configData.custom.Servo8 = channel + 1;
}
} else if (q->currentText() == "CameraRoll") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_CAMERAROLL);
} else if (q->currentText() == "CameraPitch") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_CAMERAPITCH);
} else if (q->currentText() == "CameraYaw") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_CAMERAYAW);
} else if (q->currentText() == "Accessory0") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY0);
} else if (q->currentText() == "Accessory1") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY1);
} else if (q->currentText() == "Accessory2") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY2);
} else if (q->currentText() == "Accessory3") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY3);
} else if (q->currentText() == "Accessory4") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY4);
} else if (q->currentText() == "Accessory5") {
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_ACCESSORY5);
}
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1,
m_aircraft->customMixerTable->item(1, channel)->text().toDouble());
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2,
m_aircraft->customMixerTable->item(2, channel)->text().toDouble());
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL,
m_aircraft->customMixerTable->item(3, channel)->text().toDouble());
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH,
m_aircraft->customMixerTable->item(4, channel)->text().toDouble());
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW,
m_aircraft->customMixerTable->item(5, channel)->text().toDouble());
}
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1,
m_aircraft->customMixerTable->item(1, channel)->text().toDouble());
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2,
m_aircraft->customMixerTable->item(2, channel)->text().toDouble());
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL,
m_aircraft->customMixerTable->item(3, channel)->text().toDouble());
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH,
m_aircraft->customMixerTable->item(4, channel)->text().toDouble());
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW,
m_aircraft->customMixerTable->item(5, channel)->text().toDouble());
setConfigData(configData);
}
return "Custom";
}

View File

@ -1,13 +1,13 @@
/**
******************************************************************************
*
* @file configairframetwidget.h
* @file configcustomwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief Airframe configuration panel
* @brief custom configuration panel
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify

View File

@ -1,13 +1,13 @@
/**
******************************************************************************
*
* @file configfixedwidget.cpp
* @file configfixedwingwidget.cpp
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief ccpm configuration panel
* @brief fixed wing configuration panel
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify

View File

@ -1,13 +1,13 @@
/**
******************************************************************************
*
* @file configairframetwidget.h
* @file configfixedwingwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief Airframe configuration panel
* @brief fixed wing configuration panel
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify

View File

@ -7,7 +7,7 @@
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief ccpm configuration panel
* @brief ground vehicle configuration panel
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify

View File

@ -1,13 +1,13 @@
/**
******************************************************************************
*
* @file configairframetwidget.h
* @file configgroundvehiclewidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief Airframe configuration panel
* @brief ground vehicle configuration panel
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify

View File

@ -50,11 +50,10 @@ typedef struct {
uint VTOLMotorSSW : 4;
uint VTOLMotorWSW : 4;
uint VTOLMotorWNW : 4;
uint VTOLMotorNNW : 4; // 32 bits
uint VTOLMotorNNW : 4; // 64 bits
uint TRIYaw : 4;
quint32 padding : 28; // 64 bits
quint32 padding1;
quint32 padding2; // 128 bits
quint32 padding : 28; // 96 bits
quint32 padding1; // 128 bits
} __attribute__((packed)) multiGUISettingsStruct;
typedef struct {
@ -102,12 +101,42 @@ typedef struct {
quint32 padding3; // 128 bits
} __attribute__((packed)) groundGUISettingsStruct;
typedef struct {
uint Motor1 : 4;
uint Motor2 : 4;
uint Motor3 : 4;
uint Motor4 : 4;
uint Motor5 : 4;
uint Motor6 : 4;
uint Motor7 : 4;
uint Motor8 : 4; // 32 bits
uint Servo1 : 4;
uint Servo2 : 4;
uint Servo3 : 4;
uint Servo4 : 4;
uint Servo5 : 4;
uint Servo6 : 4;
uint Servo7 : 4;
uint Servo8 : 4; // 64 bits
uint RevMotor1 : 4;
uint RevMotor2 : 4;
uint RevMotor3 : 4;
uint RevMotor4 : 4;
uint RevMotor5 : 4;
uint RevMotor6 : 4;
uint RevMotor7 : 4;
uint RevMotor8 : 4; // 96 bits
quint32 padding; // 128 bits
} __attribute__((packed)) customGUISettingsStruct;
typedef union {
uint UAVObject[4]; // 32 bits * 4
uint UAVObject[5]; // 32 bits * 5
heliGUISettingsStruct heli; // 128 bits
fixedGUISettingsStruct fixedwing;
multiGUISettingsStruct multi;
groundGUISettingsStruct ground;
customGUISettingsStruct custom;
} GUIConfigDataUnion;
class ConfigTaskWidget;

View File

@ -55,7 +55,10 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
transmitterType(acro),
//
loop(NULL),
skipflag(false)
skipflag(false),
nextDelayedTimer(),
nextDelayedTick(0),
nextDelayedLatestActivityTick(0)
{
manualCommandObj = ManualControlCommand::GetInstance(getObjectManager());
manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager());
@ -395,6 +398,13 @@ void ConfigInputWidget::goToWizard()
flightModeSettingsData.Arming = FlightModeSettings::ARMING_ALWAYSDISARMED;
flightModeSettingsObj->setData(flightModeSettingsData);
accessoryDesiredObj0 = AccessoryDesired::GetInstance(getObjectManager(), 0);
accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(), 1);
accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(), 2);
// Use faster input update rate.
fastMdata();
// start the wizard
wizardSetUpStep(wizardWelcome);
ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio);
@ -412,7 +422,13 @@ void ConfigInputWidget::disableWizardButton(int value)
void ConfigInputWidget::wzCancel()
{
dimOtherControls(false);
manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata());
// Cancel any ongoing delayd next trigger.
wzNextDelayedCancel();
// Restore original input update rate.
restoreMdata();
ui->stackedWidget->setCurrentIndex(0);
if (wizardStep != wizardNone) {
@ -426,8 +442,45 @@ void ConfigInputWidget::wzCancel()
flightModeSettingsObj->setData(previousFlightModeSettingsData);
}
void ConfigInputWidget::registerControlActivity()
{
nextDelayedLatestActivityTick = nextDelayedTick;
}
void ConfigInputWidget::wzNextDelayed()
{
nextDelayedTick++;
// Call next after the full 2500 ms timeout has been reached,
// or if no input activity has occurred the last 500 ms.
if (nextDelayedTick == 25 ||
nextDelayedTick - nextDelayedLatestActivityTick >= 5) {
wzNext();
}
}
void ConfigInputWidget::wzNextDelayedStart()
{
// Call wzNextDelayed every 100 ms, to see if it's time to go to the next page.
connect(&nextDelayedTimer, SIGNAL(timeout()), this, SLOT(wzNextDelayed()));
nextDelayedTimer.start(100);
}
// Cancel the delayed next timer, if it's active.
void ConfigInputWidget::wzNextDelayedCancel()
{
nextDelayedTick = 0;
nextDelayedLatestActivityTick = 0;
if (nextDelayedTimer.isActive()) {
nextDelayedTimer.stop();
disconnect(&nextDelayedTimer, SIGNAL(timeout()), this, SLOT(wzNextDelayed()));
}
}
void ConfigInputWidget::wzNext()
{
wzNextDelayedCancel();
// In identify sticks mode the next button can indicate
// channel advance
if (wizardStep != wizardNone &&
@ -464,6 +517,10 @@ void ConfigInputWidget::wzNext()
break;
case wizardFinish:
wizardStep = wizardNone;
// Restore original input update rate.
restoreMdata();
// Leave setting the throttle neutral until the final Next press,
// else the throttle scaling causes the graphical stick movement to not
// match the tx stick
@ -492,6 +549,8 @@ void ConfigInputWidget::wzNext()
void ConfigInputWidget::wzBack()
{
wzNextDelayedCancel();
if (wizardStep != wizardNone &&
wizardStep != wizardIdentifySticks) {
wizardTearDownStep(wizardStep);
@ -623,12 +682,8 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
break;
case wizardIdentifyLimits:
{
accessoryDesiredObj0 = AccessoryDesired::GetInstance(getObjectManager(), 0);
accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(), 1);
accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(), 2);
setTxMovement(nothing);
ui->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions.\n\nPress Next when ready.")));
fastMdata();
manualSettingsData = manualSettingsObj->getData();
for (uint i = 0; i < ManualControlSettings::CHANNELMAX_NUMELEM; ++i) {
// Preserve the inverted status
@ -665,7 +720,6 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
}
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveSticks()));
ui->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement. Press Next when ready.")));
fastMdata();
break;
case wizardFinish:
dimOtherControls(false);
@ -675,7 +729,6 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
ui->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n\n"
"IMPORTANT: These new settings have not been saved to the board yet. After pressing Next you will go to the Arming Settings "
"tab where you can set your desired arming sequence and save the configuration.")));
fastMdata();
break;
default:
Q_ASSERT(0);
@ -732,7 +785,6 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveSticks()));
disconnect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveSticks()));
manualSettingsObj->setData(manualSettingsData);
restoreMdata();
setTxMovement(nothing);
break;
case wizardIdentifyInverted:
@ -747,7 +799,6 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
}
extraWidgets.clear();
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveSticks()));
restoreMdata();
break;
case wizardFinish:
dimOtherControls(false);
@ -755,23 +806,33 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveSticks()));
disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveSticks()));
disconnect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveSticks()));
restoreMdata();
break;
default:
Q_ASSERT(0);
}
}
static void fastMdataSingle(UAVDataObject *object, UAVObject::Metadata *savedMdata)
{
*savedMdata = object->getMetadata();
UAVObject::Metadata mdata = *savedMdata;
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
mdata.flightTelemetryUpdatePeriod = 150;
object->setMetadata(mdata);
}
static void restoreMdataSingle(UAVDataObject *object, UAVObject::Metadata *savedMdata)
{
object->setMetadata(*savedMdata);
}
/**
* Set manual control command to fast updates
*/
void ConfigInputWidget::fastMdata()
{
manualControlMdata = manualCommandObj->getMetadata();
UAVObject::Metadata mdata = manualControlMdata;
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
mdata.flightTelemetryUpdatePeriod = 150;
manualCommandObj->setMetadata(mdata);
fastMdataSingle(manualCommandObj, &manualControlMdata);
fastMdataSingle(accessoryDesiredObj0, &accessoryDesiredMdata0);
}
/**
@ -779,7 +840,8 @@ void ConfigInputWidget::fastMdata()
*/
void ConfigInputWidget::restoreMdata()
{
manualCommandObj->setMetadata(manualControlMdata);
restoreMdataSingle(manualCommandObj, &manualControlMdata);
restoreMdataSingle(accessoryDesiredObj0, &accessoryDesiredMdata0);
}
/**
@ -849,7 +911,7 @@ void ConfigInputWidget::prevChannel()
for (int i = 1; i < order.length(); i++) {
if (order[i] == currentChannelNum) {
if (!usedChannels.isEmpty() &&
usedChannels.back().channelIndex == currentChannelNum) {
usedChannels.back().channelIndex == order[i - 1]) {
usedChannels.removeLast();
}
setChannel(order[i - 1]);
@ -861,41 +923,66 @@ void ConfigInputWidget::prevChannel()
void ConfigInputWidget::identifyControls()
{
static const int DEBOUNCE_COUNT = 4;
static int debounce = 0;
receiverActivityData = receiverActivityObj->getData();
if (receiverActivityData.ActiveChannel == 255) {
return;
}
if (channelDetected) {
registerControlActivity();
return;
} else {
receiverActivityData = receiverActivityObj->getData();
currentChannel.group = receiverActivityData.ActiveGroup;
currentChannel.number = receiverActivityData.ActiveChannel;
if (currentChannel == lastChannel) {
++debounce;
}
}
receiverActivityData = receiverActivityObj->getData();
currentChannel.group = receiverActivityData.ActiveGroup;
currentChannel.number = receiverActivityData.ActiveChannel;
if (debounce == 0) {
// Register a channel to be debounced.
lastChannel.group = currentChannel.group;
lastChannel.number = currentChannel.number;
lastChannel.channelIndex = currentChannelNum;
if (!usedChannels.contains(lastChannel) && debounce > 1) {
channelDetected = true;
debounce = 0;
usedChannels.append(lastChannel);
manualSettingsData = manualSettingsObj->getData();
manualSettingsData.ChannelGroups[currentChannelNum] = currentChannel.group;
manualSettingsData.ChannelNumber[currentChannelNum] = currentChannel.number;
manualSettingsObj->setData(manualSettingsData);
} else {
return;
}
++debounce;
return;
}
if (currentChannel != lastChannel) {
// A new channel was seen. Only register it if we count down to 0.
--debounce;
return;
}
if (debounce < DEBOUNCE_COUNT) {
// We still haven't seen enough enough activity on this channel yet.
++debounce;
return;
}
// Channel has been debounced and it's enough record it.
if (usedChannels.contains(lastChannel)) {
// Channel is already recorded.
return;
}
// Record the channel.
channelDetected = true;
debounce = 0;
usedChannels.append(lastChannel);
manualSettingsData = manualSettingsObj->getData();
manualSettingsData.ChannelGroups[currentChannelNum] = currentChannel.group;
manualSettingsData.ChannelNumber[currentChannelNum] = currentChannel.number;
manualSettingsObj->setData(manualSettingsData);
// m_config->wzText->clear();
setTxMovement(nothing);
QTimer::singleShot(2500, this, SLOT(wzNext()));
wzNextDelayedStart();
}
void ConfigInputWidget::identifyLimits()

View File

@ -82,6 +82,10 @@ private:
{
return (group == rhs.group) && (number == rhs.number);
}
bool operator !=(const channelsStruct & rhs) const
{
return !operator==(rhs);
}
int group;
int number;
int channelIndex;
@ -92,24 +96,34 @@ private:
QEventLoop *loop;
bool skipflag;
// Variables to support delayed transitions when detecting input controls.
QTimer nextDelayedTimer;
int nextDelayedTick;
int nextDelayedLatestActivityTick;
int currentChannelNum;
QList<int> heliChannelOrder;
QList<int> acroChannelOrder;
UAVObject::Metadata manualControlMdata;
ManualControlCommand *manualCommandObj;
ManualControlCommand::DataFields manualCommandData;
FlightStatus *flightStatusObj;
FlightStatus::DataFields flightStatusData;
UAVObject::Metadata accessoryDesiredMdata0;
AccessoryDesired *accessoryDesiredObj0;
AccessoryDesired *accessoryDesiredObj1;
AccessoryDesired *accessoryDesiredObj2;
AccessoryDesired::DataFields accessoryDesiredData0;
AccessoryDesired::DataFields accessoryDesiredData1;
AccessoryDesired::DataFields accessoryDesiredData2;
UAVObject::Metadata manualControlMdata;
ManualControlSettings *manualSettingsObj;
ManualControlSettings::DataFields manualSettingsData;
ManualControlSettings::DataFields previousManualSettingsData;
FlightModeSettings *flightModeSettingsObj;
FlightModeSettings::DataFields flightModeSettingsData;
FlightModeSettings::DataFields previousFlightModeSettingsData;
@ -152,8 +166,14 @@ private:
void wizardSetUpStep(enum wizardSteps);
void wizardTearDownStep(enum wizardSteps);
void registerControlActivity();
void wzNextDelayedStart();
void wzNextDelayedCancel();
private slots:
void wzNext();
void wzNextDelayed();
void wzBack();
void wzCancel();
void goToWizard();

View File

@ -57,7 +57,6 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
// Set up fake tab widget stuff for pid banks support
m_pidTabBars.append(ui->basicPIDBankTabBar);
m_pidTabBars.append(ui->advancedPIDBankTabBar);
m_pidTabBars.append(ui->expertPIDBankTabBar);
foreach(QTabBar * tabBar, m_pidTabBars) {
for (int i = 0; i < m_pidBankCount; i++) {
tabBar->addTab(tr("PID Bank %1").arg(i + 1));
@ -94,8 +93,6 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
addWidget(ui->realTimeUpdates_12);
connect(ui->realTimeUpdates_7, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool)));
addWidget(ui->realTimeUpdates_7);
connect(ui->realTimeUpdates_9, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool)));
addWidget(ui->realTimeUpdates_9);
connect(ui->checkBox_7, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
addWidget(ui->checkBox_7);
@ -111,7 +108,11 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
addWidget(ui->pushButton_4);
addWidget(ui->pushButton_5);
addWidget(ui->pushButton_6);
addWidget(ui->pushButton_7);
addWidget(ui->pushButton_8);
addWidget(ui->pushButton_9);
addWidget(ui->pushButton_10);
addWidget(ui->pushButton_11);
addWidget(ui->pushButton_20);
addWidget(ui->pushButton_22);
addWidget(ui->pushButton_23);
@ -150,7 +151,6 @@ void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value)
ui->realTimeUpdates_8->setChecked(value);
ui->realTimeUpdates_12->setChecked(value);
ui->realTimeUpdates_7->setChecked(value);
ui->realTimeUpdates_9->setChecked(value);
if (value && !realtimeUpdates->isActive()) {
realtimeUpdates->start(AUTOMATIC_UPDATE_RATE);
@ -193,14 +193,10 @@ void ConfigStabilizationWidget::processLinkedWidgets(QWidget *widget)
ui->RatePitchKp->setValue(ui->RateRollKp_2->value());
} else if (widget == ui->RateRollKi_2) {
ui->RatePitchKi->setValue(ui->RateRollKi_2->value());
} else if (widget == ui->RateRollILimit_2) {
ui->RatePitchILimit->setValue(ui->RateRollILimit_2->value());
} else if (widget == ui->RatePitchKp) {
ui->RateRollKp_2->setValue(ui->RatePitchKp->value());
} else if (widget == ui->RatePitchKi) {
ui->RateRollKi_2->setValue(ui->RatePitchKi->value());
} else if (widget == ui->RatePitchILimit) {
ui->RateRollILimit_2->setValue(ui->RatePitchILimit->value());
} else if (widget == ui->RollRateKd) {
ui->PitchRateKd->setValue(ui->RollRateKd->value());
} else if (widget == ui->PitchRateKd) {
@ -213,14 +209,10 @@ void ConfigStabilizationWidget::processLinkedWidgets(QWidget *widget)
ui->AttitudePitchKp_2->setValue(ui->AttitudeRollKp->value());
} else if (widget == ui->AttitudeRollKi) {
ui->AttitudePitchKi_2->setValue(ui->AttitudeRollKi->value());
} else if (widget == ui->AttitudeRollILimit) {
ui->AttitudePitchILimit_2->setValue(ui->AttitudeRollILimit->value());
} else if (widget == ui->AttitudePitchKp_2) {
ui->AttitudeRollKp->setValue(ui->AttitudePitchKp_2->value());
} else if (widget == ui->AttitudePitchKi_2) {
ui->AttitudeRollKi->setValue(ui->AttitudePitchKi_2->value());
} else if (widget == ui->AttitudePitchILimit_2) {
ui->AttitudeRollILimit->setValue(ui->AttitudePitchILimit_2->value());
}
}
@ -240,7 +232,7 @@ void ConfigStabilizationWidget::onBoardConnected()
Q_ASSERT(utilMngr);
boardModel = utilMngr->getBoardModel();
// If Revolution board enable misc tab, otherwise disable it
// If Revolution board enable Althold tab, otherwise disable it
ui->AltitudeHold->setEnabled((boardModel & 0xff00) == 0x0900);
}

View File

@ -198,12 +198,27 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *o)
// is not ideal, but there you go.
QString frameType = field->getValue().toString();
int category = frameCategory(frameType);
// Always update custom tab from others airframe settings : debug/learn hardcoded mixers
int category = frameCategory("Custom");
m_aircraft->aircraftType->setCurrentIndex(category);
VehicleConfig *vehicleConfig = getVehicleConfigWidget(category);
if (vehicleConfig) {
vehicleConfig->refreshWidgetsValues(frameType);
vehicleConfig->refreshWidgetsValues("Custom");
}
// Switch to Airframe currently used
category = frameCategory(frameType);
if (frameType != "Custom") {
m_aircraft->aircraftType->setCurrentIndex(category);
VehicleConfig *vehicleConfig = getVehicleConfigWidget(category);
if (vehicleConfig) {
vehicleConfig->refreshWidgetsValues(frameType);
}
}
updateFeedForwardUI();
@ -252,7 +267,8 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
vconfig->setMixerValue(mixer, "DecelTime", m_aircraft->decelTime->value());
vconfig->setMixerValue(mixer, "MaxAccel", m_aircraft->maxAccelSlider->value());
// TODO call refreshWidgetsValues() to reflect actual saved values ?
// call refreshWidgetsValues() to reflect actual saved values
refreshWidgetsValues();
updateFeedForwardUI();
}

File diff suppressed because it is too large Load Diff

View File

@ -26,7 +26,9 @@
*/
#include "modeluavoproxy.h"
#include "extensionsystem/pluginmanager.h"
#include "uavobjecthelper.h"
#include <QProgressDialog>
#include <math.h>
ModelUavoProxy::ModelUavoProxy(QObject *parent, flightDataModel *model) : QObject(parent), myModel(model)
@ -37,91 +39,126 @@ ModelUavoProxy::ModelUavoProxy(QObject *parent, flightDataModel *model) : QObjec
objMngr = pm->getObject<UAVObjectManager>();
Q_ASSERT(objMngr != NULL);
completionCountdown = 0;
successCountdown = 0;
}
void ModelUavoProxy::sendPathPlan()
{
modelToObjects();
PathPlan *pathPlan = PathPlan::GetInstance(objMngr, 0);
connect(pathPlan, SIGNAL(transactionCompleted(UAVObject *, bool)),
this, SLOT(pathPlanElementSent(UAVObject *, bool)), Qt::UniqueConnection);
PathPlan *pathPlan = PathPlan::GetInstance(objMngr);
Waypoint *waypoint = Waypoint::GetInstance(objMngr, 0);
connect(waypoint, SIGNAL(transactionCompleted(UAVObject *, bool)),
this, SLOT(pathPlanElementSent(UAVObject *, bool)), Qt::UniqueConnection);
const int waypointCount = pathPlan->getWaypointCount();
const int actionCount = pathPlan->getPathActionCount();
PathAction *action = PathAction::GetInstance(objMngr, 0);
connect(action, SIGNAL(transactionCompleted(UAVObject *, bool)),
this, SLOT(pathPlanElementSent(UAVObject *, bool)), Qt::UniqueConnection);
QProgressDialog progress(tr("Sending the path plan to the board... "), "", 0, 1 + waypointCount + actionCount);
progress.setWindowModality(Qt::WindowModal);
progress.setCancelButton(NULL);
progress.show();
// we will start 3 update all
completionCountdown = 3;
successCountdown = completionCountdown;
UAVObjectUpdaterHelper updateHelper;
pathPlan->updated();
waypoint->updatedAll();
action->updatedAll();
}
// send PathPlan
bool success = (updateHelper.doObjectAndWait(pathPlan) == UAVObjectUpdaterHelper::SUCCESS);
progress.setValue(1);
void ModelUavoProxy::pathPlanElementSent(UAVObject *obj, bool success)
{
obj->disconnect(this);
completionCountdown--;
successCountdown -= success ? 1 : 0;
if (completionCountdown == 0) {
qDebug() << "ModelUavoProxy::pathPlanSent - completed" << (successCountdown == 0);
if (successCountdown == 0) {
QMessageBox::information(NULL, tr("Path Plan Upload Successful"), tr("Path plan upload was successful."));
} else {
QMessageBox::critical(NULL, tr("Path Plan Upload Failed"), tr("Failed to upload the path plan !"));
if (success) {
// send Waypoint instances
qDebug() << "sending" << waypointCount << "waypoints";
for (int i = 0; i < waypointCount; ++i) {
Waypoint *waypoint = Waypoint::GetInstance(objMngr, i);
success = (updateHelper.doObjectAndWait(waypoint) == UAVObjectUpdaterHelper::SUCCESS);
if (!success) {
break;
}
progress.setValue(progress.value() + 1);
}
}
if (success) {
// send PathAction instances
qDebug() << "sending" << actionCount << "path actions";
for (int i = 0; i < actionCount; ++i) {
PathAction *action = PathAction::GetInstance(objMngr, i);
success = (updateHelper.doObjectAndWait(action) == UAVObjectUpdaterHelper::SUCCESS);
if (!success) {
break;
}
progress.setValue(progress.value() + 1);
}
}
qDebug() << "ModelUavoProxy::pathPlanSent - completed" << success;
if (!success) {
QMessageBox::critical(NULL, tr("Sending Path Plan Failed!"), tr("Failed to send the path plan to the board."));
}
progress.close();
}
void ModelUavoProxy::receivePathPlan()
{
PathPlan *pathPlan = PathPlan::GetInstance(objMngr, 0);
QProgressDialog progress(tr("Receiving the path plan from the board... "), "", 0, 0);
progress.setWindowModality(Qt::WindowModal);
progress.setCancelButton(NULL);
progress.show();
connect(pathPlan, SIGNAL(transactionCompleted(UAVObject *, bool)), this, SLOT(pathPlanElementReceived(UAVObject *, bool)));
UAVObjectRequestHelper requestHelper;
Waypoint *waypoint = Waypoint::GetInstance(objMngr, 0);
connect(waypoint, SIGNAL(transactionCompleted(UAVObject *, bool)), this, SLOT(pathPlanElementReceived(UAVObject *, bool)));
PathPlan *pathPlan = PathPlan::GetInstance(objMngr);
bool success = (requestHelper.doObjectAndWait(pathPlan) == UAVObjectUpdaterHelper::SUCCESS);
PathAction *action = PathAction::GetInstance(objMngr, 0);
connect(action, SIGNAL(transactionCompleted(UAVObject *, bool)), this, SLOT(pathPlanElementReceived(UAVObject *, bool)));
const int waypointCount = pathPlan->getWaypointCount();
const int actionCount = pathPlan->getPathActionCount();
// we will start 3 update requests
completionCountdown = 3;
successCountdown = completionCountdown;
progress.setMaximum(1 + waypointCount + actionCount);
progress.setValue(1);
pathPlan->requestUpdate();
waypoint->requestUpdateAll();
action->requestUpdateAll();
}
void ModelUavoProxy::pathPlanElementReceived(UAVObject *obj, bool success)
{
obj->disconnect(this);
completionCountdown--;
successCountdown -= success ? 1 : 0;
if (completionCountdown == 0) {
qDebug() << "ModelUavoProxy::pathPlanReceived - completed" << (successCountdown == 0);
if (successCountdown == 0) {
if (objectsToModel()) {
QMessageBox::information(NULL, tr("Path Plan Download Successful"), tr("Path plan download was successful."));
if (success && (waypointCount > objMngr->getNumInstances(Waypoint::OBJID))) {
// allocate needed Waypoint instances
Waypoint *waypoint = new Waypoint;
waypoint->initialize(waypointCount - 1, waypoint->getMetaObject());
success = objMngr->registerObject(waypoint);
}
if (success) {
// request Waypoint instances
qDebug() << "requesting" << waypointCount << "waypoints";
for (int i = 0; i < waypointCount; ++i) {
Waypoint *waypoint = Waypoint::GetInstance(objMngr, i);
success = (requestHelper.doObjectAndWait(waypoint) == UAVObjectRequestHelper::SUCCESS);
if (!success) {
break;
}
} else {
QMessageBox::critical(NULL, tr("Path Plan Download Failed"), tr("Failed to download the path plan !"));
progress.setValue(progress.value() + 1);
}
}
if (success && (actionCount > objMngr->getNumInstances(PathAction::OBJID))) {
// allocate needed PathAction instances
PathAction *action = new PathAction;
action->initialize(actionCount - 1, action->getMetaObject());
success = objMngr->registerObject(action);
}
if (success) {
// request PathAction isntances
qDebug() << "requesting" << actionCount << "path actions";
for (int i = 0; i < actionCount; ++i) {
PathAction *action = PathAction::GetInstance(objMngr, i);
success = (requestHelper.doObjectAndWait(action) == UAVObjectRequestHelper::SUCCESS);
if (!success) {
break;
}
progress.setValue(progress.value() + 1);
}
}
qDebug() << "ModelUavoProxy::pathPlanReceived - completed" << success;
if (success) {
objectsToModel();
} else {
QMessageBox::critical(NULL, tr("Receiving Path Plan Failed!"), tr("Failed to receive the path plan from the board."));
}
progress.close();
}
// update waypoint and path actions UAV objects

View File

@ -49,9 +49,6 @@ private:
UAVObjectManager *objMngr;
flightDataModel *myModel;
uint completionCountdown;
uint successCountdown;
bool modelToObjects();
bool objectsToModel();
@ -67,10 +64,6 @@ private:
void pathActionToModel(int i, PathAction::DataFields &data);
quint8 computePathPlanCrc(int waypointCount, int actionCount);
private slots:
void pathPlanElementSent(UAVObject *, bool success);
void pathPlanElementReceived(UAVObject *, bool success);
};
#endif // MODELUAVOPROXY_H

View File

@ -43,7 +43,10 @@ public:
virtual ~AbstractUAVObjectHelper();
enum Result { SUCCESS, FAIL, TIMEOUT };
Result doObjectAndWait(UAVObject *object, int timeout);
// default timeout = 3 x 250ms + 50ms safety margin = 800ms
// where 3 is the number of UAVTalk retries and 250ms is the UAVTalk timeout
Result doObjectAndWait(UAVObject *object, int timeout = 800);
protected:
virtual void doObjectAndWaitImpl() = 0;

View File

@ -48,10 +48,12 @@ Telemetry::Telemetry(UAVTalk *utalk, UAVObjectManager *objMngr) : objMngr(objMng
}
// Listen to new object creations
connect(objMngr, SIGNAL(newObject(UAVObject *)), this, SLOT(newObject(UAVObject *)));
connect(objMngr, SIGNAL(newInstance(UAVObject *)), this, SLOT(newInstance(UAVObject *)));
// connection must be direct, if not, it is not possible to create and send (or request) an object in one go
connect(objMngr, SIGNAL(newObject(UAVObject *)), this, SLOT(newObject(UAVObject *)), Qt::DirectConnection);
connect(objMngr, SIGNAL(newInstance(UAVObject *)), this, SLOT(newInstance(UAVObject *)), Qt::DirectConnection);
// Listen to transaction completions
// these slots will be executed in the telemetry thread
// TODO should send a status (SUCCESS, FAILED, TIMEOUT)
connect(utalk, SIGNAL(transactionCompleted(UAVObject *, bool)), this, SLOT(transactionCompleted(UAVObject *, bool)));
@ -568,6 +570,10 @@ void Telemetry::newObject(UAVObject *obj)
{
QMutexLocker locker(mutex);
#ifdef VERBOSE_TELEMETRY
qDebug() << "Telemetry - new object" << obj->toStringBrief();
#endif
registerObject(obj);
}
@ -575,6 +581,10 @@ void Telemetry::newInstance(UAVObject *obj)
{
QMutexLocker locker(mutex);
#ifdef VERBOSE_TELEMETRY
qDebug() << "Telemetry - new object instance" << obj->toStringBrief();
#endif
registerObject(obj);
}

View File

@ -10,7 +10,7 @@
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.00620,0.01000,0.00005,0.3" limits="%BE:0:0.01; %BE:0:0.01 ; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.00620,0.01000,0.00005,0.3" limits="%BE:0:0.01; %BE:0:0.015 ; ; "/>
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>

View File

@ -10,7 +10,7 @@
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.00620,0.01000,0.00005,0.3" limits="%BE:0:0.01; %BE:0:0.01 ; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.00620,0.01000,0.00005,0.3" limits="%BE:0:0.01; %BE:0:0.015 ; ; "/>
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>

View File

@ -10,7 +10,7 @@
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0025,0.004,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.00620,0.01000,0.00005,0.3" limits="%BE:0:0.01; %BE:0:0.01 ; ; "/>
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.00620,0.01000,0.00005,0.3" limits="%BE:0:0.01; %BE:0:0.015 ; ; "/>
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>