Commit 8547fa05 authored by LM's avatar LM

Fixed UART baud rates. 921600 IS supported on all platforms, they just do not define / report it

parents 18340b64 821e0e63
...@@ -363,8 +363,7 @@ HEADERS += src/MG.h \ ...@@ -363,8 +363,7 @@ HEADERS += src/MG.h \
src/ui/mavlink/QGCMAVLinkMessageSender.h \ src/ui/mavlink/QGCMAVLinkMessageSender.h \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \ src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \
src/ui/QGCPluginHost.h \ src/ui/QGCPluginHost.h \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h
src/ui/map3D/TerrainParamDialog.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
...@@ -391,7 +390,8 @@ contains(DEPENDENCIES_PRESENT, osg) { ...@@ -391,7 +390,8 @@ contains(DEPENDENCIES_PRESENT, osg) {
src/ui/map3D/Texture.h \ src/ui/map3D/Texture.h \
src/ui/map3D/Imagery.h \ src/ui/map3D/Imagery.h \
src/ui/map3D/HUDScaleGeode.h \ src/ui/map3D/HUDScaleGeode.h \
src/ui/map3D/WaypointGroupNode.h src/ui/map3D/WaypointGroupNode.h \
src/ui/map3D/TerrainParamDialog.h
} }
contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
message("Including headers for Protocol Buffers") message("Including headers for Protocol Buffers")
...@@ -504,8 +504,7 @@ SOURCES += src/main.cc \ ...@@ -504,8 +504,7 @@ SOURCES += src/main.cc \
src/ui/mavlink/QGCMAVLinkMessageSender.cc \ src/ui/mavlink/QGCMAVLinkMessageSender.cc \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.cc \ src/ui/firmwareupdate/QGCFirmwareUpdateWidget.cc \
src/ui/QGCPluginHost.cc \ src/ui/QGCPluginHost.cc \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc
src/ui/map3D/TerrainParamDialog.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
...@@ -534,7 +533,8 @@ contains(DEPENDENCIES_PRESENT, osg) { ...@@ -534,7 +533,8 @@ contains(DEPENDENCIES_PRESENT, osg) {
src/ui/map3D/Texture.cc \ src/ui/map3D/Texture.cc \
src/ui/map3D/Imagery.cc \ src/ui/map3D/Imagery.cc \
src/ui/map3D/HUDScaleGeode.cc \ src/ui/map3D/HUDScaleGeode.cc \
src/ui/map3D/WaypointGroupNode.cc src/ui/map3D/WaypointGroupNode.cc \
src/ui/map3D/TerrainParamDialog.cc
contains(DEPENDENCIES_PRESENT, osgearth) { contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including sources for osgEarth") message("Including sources for osgEarth")
......
...@@ -645,20 +645,23 @@ void SerialLink::setName(QString name) ...@@ -645,20 +645,23 @@ void SerialLink::setName(QString name)
} }
/**
* This function maps baud rate constants to numerical equivalents.
* It relies on the mapping given in qportsettings.h from the QSerialPort library.
*/
qint64 SerialLink::getNominalDataRate() qint64 SerialLink::getNominalDataRate()
{ {
qint64 dataRate = 0; qint64 dataRate = 0;
switch (portSettings.baudRate()) { switch (portSettings.baudRate()) {
#ifndef Q_OS_WIN
// Baud rates supported only by POSIX systems
#if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
case QPortSettings::BAUDR_50: case QPortSettings::BAUDR_50:
dataRate = 50; dataRate = 50;
break; break;
case QPortSettings::BAUDR_75: case QPortSettings::BAUDR_75:
dataRate = 75; dataRate = 75;
break; break;
case QPortSettings::BAUDR_110:
dataRate = 110;
break;
case QPortSettings::BAUDR_134: case QPortSettings::BAUDR_134:
dataRate = 134; dataRate = 134;
break; break;
...@@ -668,7 +671,48 @@ qint64 SerialLink::getNominalDataRate() ...@@ -668,7 +671,48 @@ qint64 SerialLink::getNominalDataRate()
case QPortSettings::BAUDR_200: case QPortSettings::BAUDR_200:
dataRate = 200; dataRate = 200;
break; break;
case QPortSettings::BAUDR_1800:
dataRate = 1800;
break;
#endif #endif
// Baud rates supported only by Linux
#ifdef Q_OS_LINUX
case QPortSettings::BAUDR_230400:
dataRate = 230400;
break;
case QPortSettings::BAUDR_460800:
dataRate = 460800;
break;
case QPortSettings::BAUDR_500000:
dataRate = 500000;
break;
case QPortSettings::BAUDR_576000:
dataRate = 576000;
break;
case QPortSettings::BAUDR_921600:
dataRate = 921600;
break;
#endif
// Baud rates supported only by Windows
#if defined(Q_OS_WIN32) || defined(Q_OS_WINCE)
case QPortSettings::BAUDR_14400:
dataRate = 14400;
break;
case QPortSettings::BAUDR_56000:
dataRate = 56000;
break;
case QPortSettings::BAUDR_128000:
dataRate = 128000;
break;
case QPortSettings::BAUDR_256000:
dataRate = 256000;
#endif
case QPortSettings::BAUDR_110:
dataRate = 110;
break;
case QPortSettings::BAUDR_300: case QPortSettings::BAUDR_300:
dataRate = 300; dataRate = 300;
break; break;
...@@ -678,11 +722,6 @@ qint64 SerialLink::getNominalDataRate() ...@@ -678,11 +722,6 @@ qint64 SerialLink::getNominalDataRate()
case QPortSettings::BAUDR_1200: case QPortSettings::BAUDR_1200:
dataRate = 1200; dataRate = 1200;
break; break;
#ifndef Q_OS_WIN
case QPortSettings::BAUDR_1800:
dataRate = 1800;
break;
#endif
case QPortSettings::BAUDR_2400: case QPortSettings::BAUDR_2400:
dataRate = 2400; dataRate = 2400;
break; break;
...@@ -692,52 +731,22 @@ qint64 SerialLink::getNominalDataRate() ...@@ -692,52 +731,22 @@ qint64 SerialLink::getNominalDataRate()
case QPortSettings::BAUDR_9600: case QPortSettings::BAUDR_9600:
dataRate = 9600; dataRate = 9600;
break; break;
#ifdef Q_OS_WIN
case QPortSettings::BAUDR_14400:
dataRate = 14400;
break;
#endif
case QPortSettings::BAUDR_19200: case QPortSettings::BAUDR_19200:
dataRate = 19200; dataRate = 19200;
break; break;
case QPortSettings::BAUDR_38400: case QPortSettings::BAUDR_38400:
dataRate = 38400; dataRate = 38400;
break; break;
#ifdef Q_OS_WIN
case QPortSettings::BAUDR_56000:
dataRate = 56000;
break;
#endif
case QPortSettings::BAUDR_57600: case QPortSettings::BAUDR_57600:
dataRate = 57600; dataRate = 57600;
break; break;
#ifdef Q_OS_WIN_XXXX // FIXME
case QPortSettings::BAUDR_76800:
dataRate = 76800;
break;
#endif
case QPortSettings::BAUDR_115200: case QPortSettings::BAUDR_115200:
dataRate = 115200; dataRate = 115200;
break; break;
#ifdef Q_OS_WIN
// Windows-specific high-end baudrates // Otherwise do nothing.
case QPortSettings::BAUDR_128000:
dataRate = 128000;
break;
case QPortSettings::BAUDR_256000:
dataRate = 256000;
case QPortSettings::BAUDR_230400:
dataRate = 230400;
case QPortSettings::BAUDR_460800:
dataRate = 460800;
#endif
// All-OS high-speed
case QPortSettings::BAUDR_921600:
dataRate = 921600;
break;
case QPortSettings::BAUDR_UNKNOWN: case QPortSettings::BAUDR_UNKNOWN:
default: default:
// Do nothing
break; break;
} }
return dataRate; return dataRate;
...@@ -907,13 +916,19 @@ bool SerialLink::setBaudRateType(int rateIndex) ...@@ -907,13 +916,19 @@ bool SerialLink::setBaudRateType(int rateIndex)
if(isConnected()) reconnect = true; if(isConnected()) reconnect = true;
disconnect(); disconnect();
#ifdef Q_OS_WIN // These minimum and maximum baud rates were based on those enumerated in qportsettings.h.
const int minBaud = (int)QPortSettings::BAUDR_14400; #if defined(Q_OS_WIN32) || defined(Q_OS_WINCE)
#else const int minBaud = (int)QPortSettings::BAUDR_110;
const int maxBaud = (int)QPortSettings::BAUDR_256000;
#elif defined(Q_OS_LINUX)
const int minBaud = (int)QPortSettings::BAUDR_50;
const int maxBaud = (int)QPortSettings::BAUDR_921600;
#elif defined(Q_OS_UNIX) || defined(Q_OS_DARWIN)
const int minBaud = (int)QPortSettings::BAUDR_50; const int minBaud = (int)QPortSettings::BAUDR_50;
const int maxBaud = (int)QPortSettings::BAUDR_115200;
#endif #endif
if (rateIndex >= minBaud && rateIndex <= (int)QPortSettings::BAUDR_921600) if (rateIndex >= minBaud && rateIndex <= maxBaud)
{ {
portSettings.setBaudRate((QPortSettings::BaudRate)rateIndex); portSettings.setBaudRate((QPortSettings::BaudRate)rateIndex);
} }
...@@ -932,27 +947,24 @@ bool SerialLink::setBaudRateString(const QString& rate) ...@@ -932,27 +947,24 @@ bool SerialLink::setBaudRateString(const QString& rate)
bool SerialLink::setBaudRate(int rate) bool SerialLink::setBaudRate(int rate)
{ {
//qDebug() << "BAUD RATE:" << rate;
bool reconnect = false; bool reconnect = false;
bool accepted = true; // This is changed if none of the data rates matches bool accepted = true; // This is changed if none of the data rates matches
if(isConnected()) { if(isConnected()) {
reconnect = true; reconnect = true;
} }
disconnect(); disconnect();
// This switch-statment relies on the mapping given in qportsettings.h from the QSerialPort library.
switch (rate) { switch (rate) {
#ifndef Q_OS_WIN // Baud rates supported only by non-Windows systems
#if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
case 50: case 50:
portSettings.setBaudRate(QPortSettings::BAUDR_50); portSettings.setBaudRate(QPortSettings::BAUDR_50);
break; break;
case 75: case 75:
portSettings.setBaudRate(QPortSettings::BAUDR_75); portSettings.setBaudRate(QPortSettings::BAUDR_75);
break; break;
case 110:
portSettings.setBaudRate(QPortSettings::BAUDR_110);
break;
case 134: case 134:
portSettings.setBaudRate(QPortSettings::BAUDR_134); portSettings.setBaudRate(QPortSettings::BAUDR_134);
break; break;
...@@ -962,7 +974,50 @@ bool SerialLink::setBaudRate(int rate) ...@@ -962,7 +974,50 @@ bool SerialLink::setBaudRate(int rate)
case 200: case 200:
portSettings.setBaudRate(QPortSettings::BAUDR_200); portSettings.setBaudRate(QPortSettings::BAUDR_200);
break; break;
case 1800:
portSettings.setBaudRate(QPortSettings::BAUDR_1800);
break;
#endif
// Supported only by Linux
#ifdef Q_OS_LINUX
case 230400:
portSettings.setBaudRate(QPortSettings::BAUDR_230400);
break;
case 460800:
portSettings.setBaudRate(QPortSettings::BAUDR_460800);
break;
case 500000:
portSettings.setBaudRate(QPortSettings::BAUDR_500000);
break;
case 576000:
portSettings.setBaudRate(QPortSettings::BAUDR_576000);
break;
case 921600:
portSettings.setBaudRate(QPortSettings::BAUDR_921600);
break;
#endif
// Baud rates supported only by windows
#if defined(Q_OS_WIN32) || defined(Q_OS_WINCE)
case 14400:
portSettings.setBaudRate(QPortSettings::BAUDR_14400);
break;
case 56000:
portSettings.setBaudRate(QPortSettings::BAUDR_56000);
break;
case 128000:
portSettings.setBaudRate(QPortSettings::BAUDR_128000);
break;
case 256000:
portSettings.setBaudRate(QPortSettings::BAUDR_256000);
break;
#endif #endif
// Supported by all OSes:
case 110:
portSettings.setBaudRate(QPortSettings::BAUDR_110);
break;
case 300: case 300:
portSettings.setBaudRate(QPortSettings::BAUDR_300); portSettings.setBaudRate(QPortSettings::BAUDR_300);
break; break;
...@@ -972,11 +1027,6 @@ bool SerialLink::setBaudRate(int rate) ...@@ -972,11 +1027,6 @@ bool SerialLink::setBaudRate(int rate)
case 1200: case 1200:
portSettings.setBaudRate(QPortSettings::BAUDR_1200); portSettings.setBaudRate(QPortSettings::BAUDR_1200);
break; break;
#ifndef Q_OS_WIN
case 1800:
portSettings.setBaudRate(QPortSettings::BAUDR_1800);
break;
#endif
case 2400: case 2400:
portSettings.setBaudRate(QPortSettings::BAUDR_2400); portSettings.setBaudRate(QPortSettings::BAUDR_2400);
break; break;
...@@ -986,50 +1036,18 @@ bool SerialLink::setBaudRate(int rate) ...@@ -986,50 +1036,18 @@ bool SerialLink::setBaudRate(int rate)
case 9600: case 9600:
portSettings.setBaudRate(QPortSettings::BAUDR_9600); portSettings.setBaudRate(QPortSettings::BAUDR_9600);
break; break;
#ifdef Q_OS_WIN
case 14400:
portSettings.setBaudRate(QPortSettings::BAUDR_14400);
break;
#endif
case 19200: case 19200:
portSettings.setBaudRate(QPortSettings::BAUDR_19200); portSettings.setBaudRate(QPortSettings::BAUDR_19200);
break; break;
case 38400: case 38400:
portSettings.setBaudRate(QPortSettings::BAUDR_38400); portSettings.setBaudRate(QPortSettings::BAUDR_38400);
break; break;
#ifdef Q_OS_WIN
case 56000:
portSettings.setBaudRate(QPortSettings::BAUDR_56000);
break;
#endif
case 57600: case 57600:
portSettings.setBaudRate(QPortSettings::BAUDR_57600); portSettings.setBaudRate(QPortSettings::BAUDR_57600);
break; break;
#ifdef Q_OS_WIN_XXXX // FIXME CHECK THIS
case 76800:
portSettings.setBaudRate(QPortSettings::BAUDR_76800);
break;
#endif
case 115200: case 115200:
portSettings.setBaudRate(QPortSettings::BAUDR_115200); portSettings.setBaudRate(QPortSettings::BAUDR_115200);
break; break;
#ifdef Q_OS_WIN
case 128000:
portSettings.setBaudRate(QPortSettings::BAUDR_128000);
break;
case 230400:
portSettings.setBaudRate(QPortSettings::BAUDR_230400);
break;
case 256000:
portSettings.setBaudRate(QPortSettings::BAUDR_256000);
break;
case 460800:
portSettings.setBaudRate(QPortSettings::BAUDR_460800);
break;
#endif
case 921600:
portSettings.setBaudRate(QPortSettings::BAUDR_921600);
break;
default: default:
// If none of the above cases matches, there must be an error // If none of the above cases matches, there must be an error
accepted = false; accepted = false;
......
...@@ -43,10 +43,13 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), ...@@ -43,10 +43,13 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
waypointManager(this), waypointManager(this),
thrustSum(0), thrustSum(0),
thrustMax(10), thrustMax(10),
startVoltage(0), startVoltage(-1.0f),
tickVoltage(10.5f),
lastTickVoltageValue(13.0f),
tickLowpassVoltage(12.0f),
warnVoltage(9.5f), warnVoltage(9.5f),
warnLevelPercent(20.0f), warnLevelPercent(20.0f),
currentVoltage(12.0f), currentVoltage(12.6f),
lpVoltage(12.0f), lpVoltage(12.0f),
batteryRemainingEstimateEnabled(true), batteryRemainingEstimateEnabled(true),
mode(-1), mode(-1),
...@@ -333,15 +336,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -333,15 +336,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
} }
QString audiostring = "System " + getUASName(); QString audiostring = QString("System %1").arg(uasId);
QString stateAudio = ""; QString stateAudio = "";
QString modeAudio = ""; QString modeAudio = "";
QString navModeAudio = ""; QString navModeAudio = "";
bool statechanged = false; bool statechanged = false;
bool modechanged = false; bool modechanged = false;
QString audiomodeText = getAudioModeTextFor(static_cast<int>(state.base_mode));
if (state.system_status != this->status)
if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
{ {
statechanged = true; statechanged = true;
this->status = state.system_status; this->status = state.system_status;
...@@ -362,7 +367,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -362,7 +367,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit modeChanged(this->getUASID(), shortModeText, ""); emit modeChanged(this->getUASID(), shortModeText, "");
modeAudio = " is now in " + shortModeText; modeAudio = " is now in " + audiomodeText;
} }
if (navMode != state.custom_mode) if (navMode != state.custom_mode)
...@@ -414,7 +419,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -414,7 +419,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time); emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time);
emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time); emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time);
emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time); emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time);
emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time); emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);
// Process CPU load. // Process CPU load.
emit loadChanged(this,state.load/10.0f); emit loadChanged(this,state.load/10.0f);
...@@ -423,8 +428,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -423,8 +428,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Battery charge/time remaining/voltage calculations // Battery charge/time remaining/voltage calculations
currentVoltage = state.voltage_battery/1000.0f; currentVoltage = state.voltage_battery/1000.0f;
lpVoltage = filterVoltage(currentVoltage); lpVoltage = filterVoltage(currentVoltage);
tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage;
// We don't want to tick above the threshold
if (tickLowpassVoltage > tickVoltage)
{
lastTickVoltageValue = tickLowpassVoltage;
}
if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f)
&& (lpVoltage < tickVoltage))
{
GAudioOutput::instance()->say(QString("voltage warning: %1 volt").arg(lpVoltage, 2));
lastTickVoltageValue = tickLowpassVoltage;
}
if (startVoltage == 0) startVoltage = currentVoltage; if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage;
timeRemaining = calculateTimeRemaining(); timeRemaining = calculateTimeRemaining();
if (!batteryRemainingEstimateEnabled && chargeLevel != -1) if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
{ {
...@@ -442,7 +461,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -442,7 +461,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
// LOW BATTERY ALARM // LOW BATTERY ALARM
if (lpVoltage < warnVoltage) if (lpVoltage < warnVoltage && (startVoltage > 0.0f))
{ {
startLowBattAlarm(); startLowBattAlarm();
} }
...@@ -451,6 +470,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -451,6 +470,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
stopLowBattAlarm(); stopLowBattAlarm();
} }
qDebug() << "START" << startVoltage;
// control_sensors_enabled: // control_sensors_enabled:
// relevant bits: 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control // relevant bits: 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control
...@@ -2357,6 +2378,45 @@ const QString& UAS::getShortState() const ...@@ -2357,6 +2378,45 @@ const QString& UAS::getShortState() const
return shortStateText; return shortStateText;
} }
QString UAS::getAudioModeTextFor(int id)
{
QString mode;
uint8_t modeid = id;
// BASE MODE DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
{
mode += "autonomous";
}
else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
{
mode += "guided";
}
else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
{
mode += "manual";
}
if (modeid != 0)
{
mode += " mode";
}
// ARMED STATE DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
{
mode.append(" and armed");
}
// HARDWARE IN THE LOOP DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
{
mode.append(" using hardware in the loop simulation");
}
return mode;
}
QString UAS::getShortModeTextFor(int id) QString UAS::getShortModeTextFor(int id)
{ {
QString mode; QString mode;
......
...@@ -75,6 +75,8 @@ public: ...@@ -75,6 +75,8 @@ public:
const QString& getShortMode() const; const QString& getShortMode() const;
/** @brief Translate from mode id to text */ /** @brief Translate from mode id to text */
static QString getShortModeTextFor(int id); static QString getShortModeTextFor(int id);
/** @brief Translate from mode id to audio text */
static QString getAudioModeTextFor(int id);
/** @brief Get the unique system id */ /** @brief Get the unique system id */
int getUASID() const; int getUASID() const;
/** @brief Get the airframe */ /** @brief Get the airframe */
...@@ -211,6 +213,9 @@ protected: //COMMENTS FOR TEST UNIT ...@@ -211,6 +213,9 @@ protected: //COMMENTS FOR TEST UNIT
float fullVoltage; ///< Voltage of the fully charged battery (100%) float fullVoltage; ///< Voltage of the fully charged battery (100%)
float emptyVoltage; ///< Voltage of the empty battery (0%) float emptyVoltage; ///< Voltage of the empty battery (0%)
float startVoltage; ///< Voltage at system start float startVoltage; ///< Voltage at system start
float tickVoltage; ///< Voltage where 0.1 V ticks are told
float lastTickVoltageValue; ///< The last voltage where a tick was announced
float tickLowpassVoltage; ///< Lowpass-filtered voltage for the tick announcement
float warnVoltage; ///< Voltage where QGC will start to warn about low battery float warnVoltage; ///< Voltage where QGC will start to warn about low battery
float warnLevelPercent; ///< Warning level, in percent float warnLevelPercent; ///< Warning level, in percent
double currentVoltage; ///< Voltage currently measured double currentVoltage; ///< Voltage currently measured
......
...@@ -910,13 +910,7 @@ void HSIDisplay::sendBodySetPointCoordinates() ...@@ -910,13 +910,7 @@ void HSIDisplay::sendBodySetPointCoordinates()
// Send the coordinates to the MAV // Send the coordinates to the MAV
if (uas) if (uas)
{ {
double dx = uiXSetCoordinate - uas->getLocalX(); uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
double dy = uiYSetCoordinate - uas->getLocalY();
double dz = uiZSetCoordinate - uas->getLocalZ();
bool valid = (sqrt(dx*dx + dy*dy + dz*dz) < 200.0);//UASManager::instance()->isInLocalNEDSafetyLimits(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate);
// if (valid)
// {
uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
} }
} }
......
...@@ -1211,23 +1211,24 @@ void MainWindow::UASCreated(UASInterface* uas) ...@@ -1211,23 +1211,24 @@ void MainWindow::UASCreated(UASInterface* uas)
QIcon icon; QIcon icon;
// Set matching icon // Set matching icon
switch (uas->getSystemType()) { switch (uas->getSystemType())
case 0: {
case MAV_TYPE_GENERIC:
icon = QIcon(":/images/mavs/generic.svg"); icon = QIcon(":/images/mavs/generic.svg");
break; break;
case 1: case MAV_TYPE_FIXED_WING:
icon = QIcon(":/images/mavs/fixed-wing.svg"); icon = QIcon(":/images/mavs/fixed-wing.svg");
break; break;
case 2: case MAV_TYPE_QUADROTOR:
icon = QIcon(":/images/mavs/quadrotor.svg"); icon = QIcon(":/images/mavs/quadrotor.svg");
break; break;
case 3: case MAV_TYPE_COAXIAL:
icon = QIcon(":/images/mavs/coaxial.svg"); icon = QIcon(":/images/mavs/coaxial.svg");
break; break;
case 4: case MAV_TYPE_HELICOPTER:
icon = QIcon(":/images/mavs/helicopter.svg"); icon = QIcon(":/images/mavs/helicopter.svg");
break; break;
case 5: case MAV_TYPE_GCS:
icon = QIcon(":/images/mavs/groundstation.svg"); icon = QIcon(":/images/mavs/groundstation.svg");
break; break;
default: default:
......
...@@ -59,39 +59,55 @@ SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidge ...@@ -59,39 +59,55 @@ SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidge
// Set up baud rates // Set up baud rates
ui.baudRate->clear(); ui.baudRate->clear();
ui.baudRate->addItem("50", 50);
ui.baudRate->addItem("70", 70); // Keep track of all desired baud rates by OS. These are iterated through
ui.baudRate->addItem("110", 110); // later and added to ui.baudRate.
ui.baudRate->addItem("134", 134); QList<int> supportedBaudRates;
ui.baudRate->addItem("150", 150);
ui.baudRate->addItem("200", 200); // Baud rates supported only by POSIX systems
ui.baudRate->addItem("300", 300); #if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
ui.baudRate->addItem("600", 600); supportedBaudRates << 50;
ui.baudRate->addItem("1200", 1200); supportedBaudRates << 75;
ui.baudRate->addItem("1800", 1800); supportedBaudRates << 134;
ui.baudRate->addItem("2400", 2400); supportedBaudRates << 150;
ui.baudRate->addItem("4800", 4800); supportedBaudRates << 200;
ui.baudRate->addItem("9600", 9600); supportedBaudRates << 1800;
#ifdef Q_OS_WIN
ui.baudRate->addItem("14400", 14400);
#endif
ui.baudRate->addItem("19200", 19200);
ui.baudRate->addItem("38400", 38400);
#ifdef Q_OS_WIN
ui.baudRate->addItem("56000", 56000);
#endif #endif
ui.baudRate->addItem("57600", 57600); // Baud rates supported only by Linux
#ifdef Q_OS_WIN #if defined(Q_OS_LINUX)
ui.baudRate->addItem("76800", 76800); supportedBaudRates << 230400;
supportedBaudRates << 460800;
supportedBaudRates << 500000;
supportedBaudRates << 576000;
supportedBaudRates << 921600;
#endif #endif
ui.baudRate->addItem("115200", 115200);
#ifdef Q_OS_WIN // Baud rates supported only by Windows
ui.baudRate->addItem("128000", 128000); #if defined(Q_OS_WIN)
ui.baudRate->addItem("230400", 230400); supportedBaudRates << 14400;
ui.baudRate->addItem("256000", 256000); supportedBaudRates << 56000;
ui.baudRate->addItem("460800", 460800); supportedBaudRates << 128000;
supportedBaudRates << 256000;
#endif #endif
ui.baudRate->addItem("921600", 921600);
// Baud rates supported by everyone
supportedBaudRates << 110;
supportedBaudRates << 300;
supportedBaudRates << 600;
supportedBaudRates << 1200;
supportedBaudRates << 2400;
supportedBaudRates << 4800;
supportedBaudRates << 9600;
supportedBaudRates << 19200;
supportedBaudRates << 38400;
supportedBaudRates << 57600;
supportedBaudRates << 115200;
// Now actually add all of our supported baud rates to the UI.
qSort(supportedBaudRates.begin(), supportedBaudRates.end());
for (int i = 0; i < supportedBaudRates.size(); ++i) {
ui.baudRate->addItem(QString::number(supportedBaudRates.at(i)), supportedBaudRates.at(i));
}
connect(action, SIGNAL(triggered()), this, SLOT(configureCommunication())); connect(action, SIGNAL(triggered()), this, SLOT(configureCommunication()));
......
...@@ -39,7 +39,7 @@ void QGCMAVLinkMessageSender::refresh() ...@@ -39,7 +39,7 @@ void QGCMAVLinkMessageSender::refresh()
bool QGCMAVLinkMessageSender::sendMessage() bool QGCMAVLinkMessageSender::sendMessage()
{ {
sendMessage(ui->messageIdSpinBox->value()); return sendMessage(ui->messageIdSpinBox->value());
} }
bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid) bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid)
......
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