Commit ea8b11f5 authored by Geoff Fink's avatar Geoff Fink

Merge branch 'master' of github.com:gefink/qgroundcontrol

parents b3f2af3c e991326e
......@@ -38,7 +38,10 @@
* as the previous one created unless one calls deleteSettings in the code after
* creating the UAS.
*/
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lipoFull(4.2f),
lipoEmpty(3.5f),
uasId(id),
links(new QList<LinkInterface*>()),
unknownPackets(),
......@@ -3325,45 +3328,55 @@ QString UAS::getAudioModeTextFor(int id)
return mode;
}
/**
* The mode returned can be auto, stabilized, test, manual, preflight or unknown.
* @return the short text of the mode for the id given.
*/
/**
* The mode returned can be auto, stabilized, test, manual, preflight or unknown.
* @return the short text of the mode for the id given.
*/
QString UAS::getShortModeTextFor(int id)
{
QString mode;
QString mode = "";
uint8_t modeid = id;
qDebug() << "MODE:" << modeid;
// BASE MODE DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
{
mode += "|AUTO";
}
else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
{
mode += "|VECTOR";
}
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
{
mode += "|STABILIZED";
}
else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
{
mode += "|TEST";
}
else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
{
mode += "|MANUAL";
}
else if (modeid == 0)
if (modeid == 0)
{
mode = "|PREFLIGHT";
}
else
else {
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO){
mode += "|AUTO";
}
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL){
mode += "|MANUAL";
}
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED){
mode += "|VECTOR";
}
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE){
mode += "|STABILIZED";
}
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST){
mode += "|TEST";
}
}
if (mode.length() == 0)
{
mode = "|UNKNOWN";
qDebug() << __FILE__ << __LINE__ << " Unknown modeid: " << modeid;
}
// ARMED STATE DECODING
......@@ -3382,6 +3395,8 @@ QString UAS::getShortModeTextFor(int id)
mode.prepend("HIL:");
}
qDebug() << "MODE: " << modeid << " " << mode;
return mode;
}
......@@ -3445,8 +3460,8 @@ void UAS::setBattery(BatteryType type, int cells)
case LIION:
break;
case LIPOLY:
fullVoltage = this->cells * UAS::lipoFull;
emptyVoltage = this->cells * UAS::lipoEmpty;
fullVoltage = this->cells * lipoFull;
emptyVoltage = this->cells * lipoEmpty;
break;
case LIFE:
break;
......
......@@ -56,8 +56,8 @@ public:
UAS(MAVLinkProtocol* protocol, int id = 0);
~UAS();
static const float lipoFull = 4.2f; ///< 100% charged voltage
static const float lipoEmpty = 3.5f; ///< Discharged voltage
float lipoFull; ///< 100% charged voltage
float lipoEmpty; ///< Discharged voltage
/* MANAGEMENT */
......
......@@ -705,7 +705,7 @@ void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column)
current->setBackground(1, QBrush(QColor(QGC::colorOrange)));
}
switch (parameters.value(key)->value(str).type())
switch ((int)parameters.value(key)->value(str).type())
{
case QVariant::Int:
{
......@@ -766,7 +766,7 @@ void QGCParamWidget::saveParameters()
{
QString paramValue("%1");
QString paramType("%1");
switch (j.value().type())
switch ((int)j.value().type())
{
case QVariant::Int:
paramValue = paramValue.arg(j.value().toInt());
......@@ -777,7 +777,9 @@ void QGCParamWidget::saveParameters()
paramType = paramType.arg(MAV_PARAM_TYPE_UINT32);
break;
case QMetaType::Float:
paramValue = paramValue.arg(j.value().toDouble(), 25, 'g', 12);
// We store parameters as floats, with only 6 digits of precision guaranteed for decimal string conversion
// (see IEEE 754, 32 bit single-precision)
paramValue = paramValue.arg((double)j.value().toFloat(), 25, 'g', 6);
paramType = paramType.arg(MAV_PARAM_TYPE_REAL32);
break;
default:
......@@ -955,7 +957,7 @@ void QGCParamWidget::retransmissionGuardTick()
if (count < retransmissionBurstRequestSize) {
// Re-request write operation
QVariant value = missingParams->value(key);
switch (parameters.value(component)->value(key).type())
switch ((int)parameters.value(component)->value(key).type())
{
case QVariant::Int:
{
......@@ -1020,7 +1022,7 @@ void QGCParamWidget::setParameter(int component, QString parameterName, QVariant
return;
}
switch (parameters.value(component)->value(parameterName).type())
switch ((int)parameters.value(component)->value(parameterName).type())
{
case QVariant::Char:
{
......
......@@ -51,12 +51,17 @@ UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent),
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
ui.modeComboBox->clear();
ui.modeComboBox->insertItem(0, UAS::getShortModeTextFor(MAV_MODE_PREFLIGHT).remove(0, 2), MAV_MODE_PREFLIGHT);
ui.modeComboBox->insertItem(1, UAS::getShortModeTextFor((MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED)).remove(0, 2), (MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED));
ui.modeComboBox->insertItem(2, UAS::getShortModeTextFor(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED).remove(0, 2), MAV_MODE_FLAG_MANUAL_INPUT_ENABLED);
ui.modeComboBox->insertItem(3, UAS::getShortModeTextFor((MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED)).remove(0, 2), (MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED));
ui.modeComboBox->insertItem(4, UAS::getShortModeTextFor((MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED)).remove(0, 2), (MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED));
ui.modeComboBox->insertItem(5, UAS::getShortModeTextFor((MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_TEST_ENABLED)).remove(0, 2), (MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_TEST_ENABLED));
int modes[] = {
MAV_MODE_PREFLIGHT,
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED,
MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED,
MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED,
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_TEST_ENABLED,
};
for (int i = 0; i < sizeof(modes) / sizeof(int); i++) {
int mode = modes[i];
ui.modeComboBox->insertItem(i, UAS::getShortModeTextFor(mode).remove(0, 2), mode);
}
connect(ui.modeComboBox, SIGNAL(activated(int)), this, SLOT(setMode(int)));
connect(ui.setModeButton, SIGNAL(clicked()), this, SLOT(transmitMode()));
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment