Commit f3aa6560 authored by Gus Grubba's avatar Gus Grubba

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into resetParametersMessage

parents 4b868491 a573371c
......@@ -78,22 +78,9 @@ WindowsBuild {
ReleaseBuild {
# Copy Visual Studio DLLs
# Note that this is only done for release because the debugging versions of these DLLs cannot be redistributed.
win32-msvc2010 {
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"C:\\Windows\\System32\\msvcp100.dll\" \"$$DESTDIR_WIN\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"C:\\Windows\\System32\\msvcr100.dll\" \"$$DESTDIR_WIN\"
} else:win32-msvc2012 {
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"C:\\Windows\\System32\\msvcp110.dll\" \"$$DESTDIR_WIN\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"C:\\Windows\\System32\\msvcr110.dll\" \"$$DESTDIR_WIN\"
} else:win32-msvc2013 {
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"C:\\Windows\\System32\\msvcp120.dll\" \"$$DESTDIR_WIN\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"C:\\Windows\\System32\\msvcr120.dll\" \"$$DESTDIR_WIN\"
} else:win32-msvc2015 {
win32-msvc2015 {
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"C:\\Windows\\System32\\msvcp140.dll\" \"$$DESTDIR_WIN\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"C:\\Windows\\System32\\vcruntime140.dll\" \"$$DESTDIR_WIN\"
} else {
error("Visual studio version not supported, installation cannot be completed.")
}
......
Subproject commit 18cf6ff2fc0e51e4555b19fc31e8b06eb38bdd79
Subproject commit 2a9615b7a28fe63b3f422116e2c0f75d43b1fa71
......@@ -31,16 +31,17 @@ PX4AdvancedFlightModesController::PX4AdvancedFlightModesController(void) :
_returnModeSelected(false),
_offboardModeSelected(false)
{
QStringList usedParams;
usedParams << "RC_MAP_THROTTLE" << "RC_MAP_YAW" << "RC_MAP_PITCH" << "RC_MAP_ROLL" << "RC_MAP_FLAPS" << "RC_MAP_AUX1" << "RC_MAP_AUX2" <<
"RC_MAP_MODE_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_OFFB_SW" << "RC_MAP_ACRO_SW";
QStringList usedParams = QStringList({
"RC_MAP_THROTTLE", "RC_MAP_YAW", "RC_MAP_PITCH", "RC_MAP_ROLL", "RC_MAP_FLAPS", "RC_MAP_AUX1", "RC_MAP_AUX2",
"RC_MAP_MODE_SW", "RC_MAP_RETURN_SW", "RC_MAP_LOITER_SW", "RC_MAP_POSCTL_SW", "RC_MAP_OFFB_SW", "RC_MAP_ACRO_SW"});
if (!_allParametersExists(FactSystem::defaultComponentId, usedParams)) {
return;
}
_init();
_validateConfiguration();
connect(_vehicle, &Vehicle::rcChannelsChanged, this, &PX4AdvancedFlightModesController::_rcChannelsChanged);
}
......@@ -96,20 +97,17 @@ void PX4AdvancedFlightModesController::_init(void)
// Auto mode is visible if Mission/Loiter are on separate channel from main Mode switch
_autoModeVisible = loiterChannel != modeChannel;
}
// Setup the channel combobox model
QList<int> usedChannels;
QStringList attitudeParams;
attitudeParams << "RC_MAP_THROTTLE" << "RC_MAP_YAW" << "RC_MAP_PITCH" << "RC_MAP_ROLL" << "RC_MAP_FLAPS" << "RC_MAP_AUX1" << "RC_MAP_AUX2";
foreach(const QString &attitudeParam, attitudeParams) {
QVector<int> usedChannels;
for (const QString &attitudeParam : {"RC_MAP_THROTTLE", "RC_MAP_YAW", "RC_MAP_PITCH", "RC_MAP_ROLL", "RC_MAP_FLAPS", "RC_MAP_AUX1", "RC_MAP_AUX2"}) {
int channel = getParameterFact(-1, attitudeParam)->rawValue().toInt();
if (channel != 0) {
usedChannels << channel;
}
}
_channelListModel << "Disabled";
_channelListModelChannel << 0;
for (int channel=1; channel<=_channelCount; channel++) {
......@@ -140,13 +138,11 @@ void PX4AdvancedFlightModesController::_validateConfiguration(void)
_validConfiguration = true;
// Make sure switches are valid and within channel range
QStringList switchParams;
const QStringList switchParams = {"RC_MAP_MODE_SW", "RC_MAP_ACRO_SW", "RC_MAP_POSCTL_SW", "RC_MAP_LOITER_SW", "RC_MAP_RETURN_SW", "RC_MAP_OFFB_SW"};
QList<int> switchMappings;
switchParams << "RC_MAP_MODE_SW" << "RC_MAP_ACRO_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_OFFB_SW";
for(int i=0; i<switchParams.count(); i++) {
for(int i=0, end = switchParams.count(); i < end; i++) {
int map = getParameterFact(FactSystem::defaultComponentId, switchParams[i])->rawValue().toInt();
switchMappings << map;
......@@ -157,16 +153,16 @@ void PX4AdvancedFlightModesController::_validateConfiguration(void)
}
// Make sure mode switches are not double-mapped
QStringList attitudeParams;
attitudeParams << "RC_MAP_THROTTLE" << "RC_MAP_YAW" << "RC_MAP_PITCH" << "RC_MAP_ROLL" << "RC_MAP_FLAPS" << "RC_MAP_AUX1" << "RC_MAP_AUX2";
for (int i=0; i<attitudeParams.count(); i++) {
const QStringList attitudeParams = {"RC_MAP_THROTTLE", "RC_MAP_YAW", "RC_MAP_PITCH", "RC_MAP_ROLL", "RC_MAP_FLAPS", "RC_MAP_AUX1", "RC_MAP_AUX2"};
for (int i=0, end = attitudeParams.count(); i < end; i++) {
int map = getParameterFact(FactSystem::defaultComponentId, attitudeParams[i])->rawValue().toInt();
if (map == 0) {
continue;
}
for (int j=0; j<switchParams.count(); j++) {
if (map != 0 && map == switchMappings[j]) {
if (map == switchMappings[j]) {
_validConfiguration = false;
_configurationErrors += tr("%1 is set to same channel as %2.\n").arg(switchParams[j], attitudeParams[i]);
}
......@@ -174,12 +170,7 @@ void PX4AdvancedFlightModesController::_validateConfiguration(void)
}
// Validate thresholds within range
QStringList thresholdParams;
thresholdParams << "RC_ASSIST_TH" << "RC_AUTO_TH" << "RC_ACRO_TH" << "RC_POSCTL_TH" << "RC_LOITER_TH" << "RC_RETURN_TH" << "RC_OFFB_TH";
foreach(const QString &thresholdParam, thresholdParams) {
for(const QString &thresholdParam : {"RC_ASSIST_TH", "RC_AUTO_TH", "RC_ACRO_TH", "RC_POSCTL_TH", "RC_LOITER_TH", "RC_RETURN_TH", "RC_OFFB_TH"}) {
float threshold = getParameterFact(-1, thresholdParam)->rawValue().toFloat();
if (threshold < 0.0f || threshold > 1.0f) {
_validConfiguration = false;
......
......@@ -43,25 +43,19 @@ bool PX4RadioComponent::setupComplete(void) const
if (_vehicle->parameterManager()->getParameter(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) {
// The best we can do to detect the need for a radio calibration is look for attitude
// controls to be mapped.
QStringList attitudeMappings;
attitudeMappings << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE";
foreach(const QString &mapParam, attitudeMappings) {
for(const QString &mapParam : {"RC_MAP_ROLL", "RC_MAP_PITCH", "RC_MAP_YAW", "RC_MAP_THROTTLE"}) {
if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, mapParam)->rawValue().toInt() == 0) {
return false;
}
}
}
return true;
}
QStringList PX4RadioComponent::setupCompleteChangedTriggerList(void) const
{
QStringList triggers;
triggers << "COM_RC_IN_MODE" << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE";
return triggers;
return {"COM_RC_IN_MODE", "RC_MAP_ROLL", "RC_MAP_PITCH", "RC_MAP_YAW", "RC_MAP_THROTTLE"};
}
QUrl PX4RadioComponent::setupSource(void) const
......
......@@ -49,10 +49,7 @@ bool PowerComponent::setupComplete(void) const
QStringList PowerComponent::setupCompleteChangedTriggerList(void) const
{
QStringList triggerList;
triggerList << "BAT_V_CHARGED" << "BAT_V_EMPTY" << "BAT_N_CELLS";
return triggerList;
return {"BAT_V_CHARGED", "BAT_V_EMPTY", "BAT_N_CELLS"};
}
QUrl PowerComponent::setupSource(void) const
......
......@@ -26,7 +26,7 @@ SensorsComponent::SensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot,
VehicleComponent(vehicle, autopilot, parent),
_name(tr("Sensors"))
{
_deviceIds << QStringLiteral("CAL_GYRO0_ID") << QStringLiteral("CAL_ACC0_ID");
_deviceIds = QStringList({QStringLiteral("CAL_GYRO0_ID"), QStringLiteral("CAL_ACC0_ID") });
}
QString SensorsComponent::name(void) const
......
......@@ -1285,27 +1285,13 @@ QMap<QString, FactMetaData*> FactMetaData::createMapFromJsonArray(const QJsonArr
QVariant FactMetaData::cookedMax(void) const
{
// We have to be careful with cooked min/max. Running the raw values through the translator could flip min and max.
QVariant cookedMax = _rawTranslator(_rawMax);
QVariant cookedMin = _rawTranslator(_rawMin);
if (cookedMax < cookedMin) {
// We need to flip
return cookedMin;
} else {
return cookedMax;
}
return qMax(_rawTranslator(_rawMax), _rawTranslator(_rawMin));
}
QVariant FactMetaData::cookedMin(void) const
{
// We have to be careful with cooked min/max. Running the raw values through the translator could flip min and max.
QVariant cookedMax = _rawTranslator(_rawMax);
QVariant cookedMin = _rawTranslator(_rawMin);
if (cookedMax < cookedMin) {
// We need to flip
return cookedMax;
} else {
return cookedMin;
}
return qMin(_rawTranslator(_rawMax), _rawTranslator(_rawMin));
}
void FactMetaData::setVolatileValue(bool bValue)
......
......@@ -722,41 +722,39 @@ void APMFirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact
QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
{
QList<MAV_CMD> list;
list << MAV_CMD_NAV_WAYPOINT
<< MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TURNS << MAV_CMD_NAV_LOITER_TIME
<< MAV_CMD_NAV_RETURN_TO_LAUNCH << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF
<< MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT
<< MAV_CMD_NAV_LOITER_TO_ALT
<< MAV_CMD_NAV_SPLINE_WAYPOINT
<< MAV_CMD_NAV_GUIDED_ENABLE
<< MAV_CMD_NAV_DELAY
<< MAV_CMD_CONDITION_DELAY << MAV_CMD_CONDITION_DISTANCE << MAV_CMD_CONDITION_YAW
<< MAV_CMD_DO_SET_MODE
<< MAV_CMD_DO_JUMP
<< MAV_CMD_DO_CHANGE_SPEED
<< MAV_CMD_DO_SET_HOME
<< MAV_CMD_DO_SET_RELAY << MAV_CMD_DO_REPEAT_RELAY
<< MAV_CMD_DO_SET_SERVO << MAV_CMD_DO_REPEAT_SERVO
<< MAV_CMD_DO_LAND_START
<< MAV_CMD_DO_SET_ROI
<< MAV_CMD_DO_DIGICAM_CONFIGURE << MAV_CMD_DO_DIGICAM_CONTROL
<< MAV_CMD_DO_MOUNT_CONTROL
<< MAV_CMD_DO_SET_CAM_TRIGG_DIST
<< MAV_CMD_DO_FENCE_ENABLE
<< MAV_CMD_DO_PARACHUTE
<< MAV_CMD_DO_INVERTED_FLIGHT
<< MAV_CMD_DO_GRIPPER
<< MAV_CMD_DO_GUIDED_LIMITS
<< MAV_CMD_DO_AUTOTUNE_ENABLE
<< MAV_CMD_NAV_VTOL_TAKEOFF << MAV_CMD_NAV_VTOL_LAND << MAV_CMD_DO_VTOL_TRANSITION;
return {
MAV_CMD_NAV_WAYPOINT,
MAV_CMD_NAV_LOITER_UNLIM, MAV_CMD_NAV_LOITER_TURNS, MAV_CMD_NAV_LOITER_TIME,
MAV_CMD_NAV_RETURN_TO_LAUNCH, MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT,
MAV_CMD_NAV_LOITER_TO_ALT,
MAV_CMD_NAV_SPLINE_WAYPOINT,
MAV_CMD_NAV_GUIDED_ENABLE,
MAV_CMD_NAV_DELAY,
MAV_CMD_CONDITION_DELAY, MAV_CMD_CONDITION_DISTANCE, MAV_CMD_CONDITION_YAW,
MAV_CMD_DO_SET_MODE,
MAV_CMD_DO_JUMP,
MAV_CMD_DO_CHANGE_SPEED,
MAV_CMD_DO_SET_HOME,
MAV_CMD_DO_SET_RELAY, MAV_CMD_DO_REPEAT_RELAY,
MAV_CMD_DO_SET_SERVO, MAV_CMD_DO_REPEAT_SERVO,
MAV_CMD_DO_LAND_START,
MAV_CMD_DO_SET_ROI,
MAV_CMD_DO_DIGICAM_CONFIGURE, MAV_CMD_DO_DIGICAM_CONTROL,
MAV_CMD_DO_MOUNT_CONTROL,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_CMD_DO_FENCE_ENABLE,
MAV_CMD_DO_PARACHUTE,
MAV_CMD_DO_INVERTED_FLIGHT,
MAV_CMD_DO_GRIPPER,
MAV_CMD_DO_GUIDED_LIMITS,
MAV_CMD_DO_AUTOTUNE_ENABLE,
MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND, MAV_CMD_DO_VTOL_TRANSITION,
#if 0
// Waiting for module update
<< MAV_CMD_DO_SET_REVERSE;
MAV_CMD_DO_SET_REVERSE,
#endif
return list;
};
}
QString APMFirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
......
......@@ -22,54 +22,52 @@ FirmwarePlugin::remapParamNameMajorVersionMap_t ArduCopterFirmwarePlugin::_remap
APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
APMCustomMode(mode, settable)
{
QMap<uint32_t,QString> enumToString;
enumToString.insert(STABILIZE, "Stabilize");
enumToString.insert(ACRO, "Acro");
enumToString.insert(ALT_HOLD, "Altitude Hold");
enumToString.insert(AUTO, "Auto");
enumToString.insert(GUIDED, "Guided");
enumToString.insert(LOITER, "Loiter");
enumToString.insert(RTL, "RTL");
enumToString.insert(CIRCLE, "Circle");
enumToString.insert(LAND, "Land");
enumToString.insert(DRIFT, "Drift");
enumToString.insert(SPORT, "Sport");
enumToString.insert(FLIP, "Flip");
enumToString.insert(AUTOTUNE, "Autotune");
enumToString.insert(POS_HOLD, "Position Hold");
enumToString.insert(BRAKE, "Brake");
enumToString.insert(THROW, "Throw");
enumToString.insert(AVOID_ADSB, "Avoid ADSB");
enumToString.insert(GUIDED_NOGPS, "Guided No GPS");
enumToString.insert(SAFE_RTL, "Smart RTL");
setEnumToStringMapping(enumToString);
setEnumToStringMapping({
{STABILIZE, "Stabilize"},
{ACRO, "Acro"},
{ALT_HOLD, "Altitude Hold"},
{AUTO, "Auto"},
{GUIDED, "Guided"},
{LOITER, "Loiter"},
{RTL, "RTL"},
{CIRCLE, "Circle"},
{LAND, "Land"},
{DRIFT, "Drift"},
{SPORT, "Sport"},
{FLIP, "Flip"},
{AUTOTUNE, "Autotune"},
{POS_HOLD, "Position Hold"},
{BRAKE, "Brake"},
{THROW, "Throw"},
{AVOID_ADSB, "Avoid ADSB"},
{GUIDED_NOGPS, "Guided No GPS"},
{SAFE_RTL, "Smart RTL"},
});
}
ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
{
QList<APMCustomMode> supportedFlightModes;
supportedFlightModes << APMCopterMode(APMCopterMode::STABILIZE ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::ACRO ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::ALT_HOLD ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::AUTO ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::GUIDED ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::LOITER ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::RTL ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::CIRCLE ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::LAND ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::DRIFT ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::SPORT ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::FLIP ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::AUTOTUNE ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::POS_HOLD ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::BRAKE ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::THROW ,true);
supportedFlightModes << APMCopterMode(APMCopterMode::AVOID_ADSB,true);
supportedFlightModes << APMCopterMode(APMCopterMode::GUIDED_NOGPS,true);
supportedFlightModes << APMCopterMode(APMCopterMode::SAFE_RTL,true);
setSupportedModes(supportedFlightModes);
setSupportedModes({
APMCopterMode(APMCopterMode::STABILIZE ,true),
APMCopterMode(APMCopterMode::ACRO ,true),
APMCopterMode(APMCopterMode::ALT_HOLD ,true),
APMCopterMode(APMCopterMode::AUTO ,true),
APMCopterMode(APMCopterMode::GUIDED ,true),
APMCopterMode(APMCopterMode::LOITER ,true),
APMCopterMode(APMCopterMode::RTL ,true),
APMCopterMode(APMCopterMode::CIRCLE ,true),
APMCopterMode(APMCopterMode::LAND ,true),
APMCopterMode(APMCopterMode::DRIFT ,true),
APMCopterMode(APMCopterMode::SPORT ,true),
APMCopterMode(APMCopterMode::FLIP ,true),
APMCopterMode(APMCopterMode::AUTOTUNE ,true),
APMCopterMode(APMCopterMode::POS_HOLD ,true),
APMCopterMode(APMCopterMode::BRAKE ,true),
APMCopterMode(APMCopterMode::THROW ,true),
APMCopterMode(APMCopterMode::AVOID_ADSB,true),
APMCopterMode(APMCopterMode::GUIDED_NOGPS,true),
APMCopterMode(APMCopterMode::SAFE_RTL,true),
});
if (!_remapParamNameIntialized) {
FirmwarePlugin::remapParamNameMap_t& remapV3_6 = _remapParamName[3][6];
......
......@@ -15,53 +15,52 @@ FirmwarePlugin::remapParamNameMajorVersionMap_t ArduPlaneFirmwarePlugin::_remapP
APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable)
: APMCustomMode(mode, settable)
{
QMap<uint32_t,QString> enumToString;
enumToString.insert(MANUAL, "Manual");
enumToString.insert(CIRCLE, "Circle");
enumToString.insert(STABILIZE, "Stabilize");
enumToString.insert(TRAINING, "Training");
enumToString.insert(ACRO, "Acro");
enumToString.insert(FLY_BY_WIRE_A, "FBW A");
enumToString.insert(FLY_BY_WIRE_B, "FBW B");
enumToString.insert(CRUISE, "Cruise");
enumToString.insert(AUTOTUNE, "Autotune");
enumToString.insert(AUTO, "Auto");
enumToString.insert(RTL, "RTL");
enumToString.insert(LOITER, "Loiter");
enumToString.insert(GUIDED, "Guided");
enumToString.insert(INITIALIZING, "Initializing");
enumToString.insert(QSTABILIZE, "QuadPlane Stabilize");
enumToString.insert(QHOVER, "QuadPlane Hover");
enumToString.insert(QLOITER, "QuadPlane Loiter");
enumToString.insert(QLAND, "QuadPlane Land");
enumToString.insert(QRTL, "QuadPlane RTL");
setEnumToStringMapping(enumToString);
setEnumToStringMapping({
{MANUAL, "Manual"},
{CIRCLE, "Circle"},
{STABILIZE, "Stabilize"},
{TRAINING, "Training"},
{ACRO, "Acro"},
{FLY_BY_WIRE_A, "FBW A"},
{FLY_BY_WIRE_B, "FBW B"},
{CRUISE, "Cruise"},
{AUTOTUNE, "Autotune"},
{AUTO, "Auto"},
{RTL, "RTL"},
{LOITER, "Loiter"},
{GUIDED, "Guided"},
{INITIALIZING, "Initializing"},
{QSTABILIZE, "QuadPlane Stabilize"},
{QHOVER, "QuadPlane Hover"},
{QLOITER, "QuadPlane Loiter"},
{QLAND, "QuadPlane Land"},
{QRTL, "QuadPlane RTL"},
});
}
ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(void)
{
QList<APMCustomMode> supportedFlightModes;
supportedFlightModes << APMPlaneMode(APMPlaneMode::MANUAL ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::CIRCLE ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::STABILIZE ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::TRAINING ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::ACRO ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::FLY_BY_WIRE_A ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::FLY_BY_WIRE_B ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::CRUISE ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::AUTOTUNE ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::AUTO ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::RTL ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::LOITER ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::GUIDED ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::INITIALIZING ,false);
supportedFlightModes << APMPlaneMode(APMPlaneMode::QSTABILIZE ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::QHOVER ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::QLOITER ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::QLAND ,true);
supportedFlightModes << APMPlaneMode(APMPlaneMode::QRTL ,true);
setSupportedModes(supportedFlightModes);
setSupportedModes({
APMPlaneMode(APMPlaneMode::MANUAL ,true),
APMPlaneMode(APMPlaneMode::CIRCLE ,true),
APMPlaneMode(APMPlaneMode::STABILIZE ,true),
APMPlaneMode(APMPlaneMode::TRAINING ,true),
APMPlaneMode(APMPlaneMode::ACRO ,true),
APMPlaneMode(APMPlaneMode::FLY_BY_WIRE_A ,true),
APMPlaneMode(APMPlaneMode::FLY_BY_WIRE_B ,true),
APMPlaneMode(APMPlaneMode::CRUISE ,true),
APMPlaneMode(APMPlaneMode::AUTOTUNE ,true),
APMPlaneMode(APMPlaneMode::AUTO ,true),
APMPlaneMode(APMPlaneMode::RTL ,true),
APMPlaneMode(APMPlaneMode::LOITER ,true),
APMPlaneMode(APMPlaneMode::GUIDED ,true),
APMPlaneMode(APMPlaneMode::INITIALIZING ,false),
APMPlaneMode(APMPlaneMode::QSTABILIZE ,true),
APMPlaneMode(APMPlaneMode::QHOVER ,true),
APMPlaneMode(APMPlaneMode::QLOITER ,true),
APMPlaneMode(APMPlaneMode::QLAND ,true),
APMPlaneMode(APMPlaneMode::QRTL ,true),
});
if (!_remapParamNameIntialized) {
FirmwarePlugin::remapParamNameMap_t& remapV3_10 = _remapParamName[3][10];
......
......@@ -16,39 +16,38 @@ FirmwarePlugin::remapParamNameMajorVersionMap_t ArduRoverFirmwarePlugin::_remapP
APMRoverMode::APMRoverMode(uint32_t mode, bool settable)
: APMCustomMode(mode, settable)
{
QMap<uint32_t,QString> enumToString;
enumToString.insert(MANUAL, "Manual");
enumToString.insert(ACRO, "Acro");
enumToString.insert(STEERING, "Steering");
enumToString.insert(HOLD, "Hold");
enumToString.insert(LOITER, "Loiter");
enumToString.insert(FOLLOW, "Follow");
enumToString.insert(SIMPLE, "Simple");
enumToString.insert(AUTO, "Auto");
enumToString.insert(RTL, "RTL");
enumToString.insert(SMART_RTL, "Smart RTL");
enumToString.insert(GUIDED, "Guided");
enumToString.insert(INITIALIZING, "Initializing");
setEnumToStringMapping(enumToString);
setEnumToStringMapping({
{MANUAL, "Manual"},
{ACRO, "Acro"},
{STEERING, "Steering"},
{HOLD, "Hold"},
{LOITER, "Loiter"},
{FOLLOW, "Follow"},
{SIMPLE, "Simple"},
{AUTO, "Auto"},
{RTL, "RTL"},
{SMART_RTL, "Smart RTL"},
{GUIDED, "Guided"},
{INITIALIZING, "Initializing"},
});
}
ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void)
{
QList<APMCustomMode> supportedFlightModes;
supportedFlightModes << APMRoverMode(APMRoverMode::MANUAL ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::ACRO ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::STEERING ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::HOLD ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::LOITER ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::FOLLOW ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::SIMPLE ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::AUTO ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::RTL ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::SMART_RTL ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::GUIDED ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::INITIALIZING ,false);
setSupportedModes(supportedFlightModes);
setSupportedModes({
APMRoverMode(APMRoverMode::MANUAL ,true),
APMRoverMode(APMRoverMode::ACRO ,true),
APMRoverMode(APMRoverMode::STEERING ,true),
APMRoverMode(APMRoverMode::HOLD ,true),
APMRoverMode(APMRoverMode::LOITER ,true),
APMRoverMode(APMRoverMode::FOLLOW ,true),
APMRoverMode(APMRoverMode::SIMPLE ,true),
APMRoverMode(APMRoverMode::AUTO ,true),
APMRoverMode(APMRoverMode::RTL ,true),
APMRoverMode(APMRoverMode::SMART_RTL ,true),
APMRoverMode(APMRoverMode::GUIDED ,true),
APMRoverMode(APMRoverMode::INITIALIZING ,false),
});
if (!_remapParamNameIntialized) {
FirmwarePlugin::remapParamNameMap_t& remapV3_5 = _remapParamName[3][5];
......
......@@ -32,34 +32,33 @@ FirmwarePlugin::remapParamNameMajorVersionMap_t ArduSubFirmwarePlugin::_remapPar
APMSubMode::APMSubMode(uint32_t mode, bool settable) :
APMCustomMode(mode, settable)
{
QMap<uint32_t,QString> enumToString;
enumToString.insert(MANUAL, "Manual");
enumToString.insert(STABILIZE, "Stabilize");
enumToString.insert(ACRO, "Acro");
enumToString.insert(ALT_HOLD, "Depth Hold");
enumToString.insert(AUTO, "Auto");
enumToString.insert(GUIDED, "Guided");
enumToString.insert(CIRCLE, "Circle");
enumToString.insert(SURFACE, "Surface");
enumToString.insert(POSHOLD, "Position Hold");
setEnumToStringMapping(enumToString);
setEnumToStringMapping({
{MANUAL, "Manual"},
{STABILIZE, "Stabilize"},
{ACRO, "Acro"},
{ALT_HOLD, "Depth Hold"},
{AUTO, "Auto"},
{GUIDED, "Guided"},
{CIRCLE, "Circle"},
{SURFACE, "Surface"},
{POSHOLD, "Position Hold"},
});
}
ArduSubFirmwarePlugin::ArduSubFirmwarePlugin(void):
_infoFactGroup(this)
{
QList<APMCustomMode> supportedFlightModes;
supportedFlightModes << APMSubMode(APMSubMode::MANUAL ,true);
supportedFlightModes << APMSubMode(APMSubMode::STABILIZE ,true);
supportedFlightModes << APMSubMode(APMSubMode::ACRO ,true);
supportedFlightModes << APMSubMode(APMSubMode::ALT_HOLD ,true);
supportedFlightModes << APMSubMode(APMSubMode::AUTO ,true);
supportedFlightModes << APMSubMode(APMSubMode::GUIDED ,true);
supportedFlightModes << APMSubMode(APMSubMode::CIRCLE ,true);
supportedFlightModes << APMSubMode(APMSubMode::SURFACE ,false);
supportedFlightModes << APMSubMode(APMSubMode::POSHOLD ,true);
setSupportedModes(supportedFlightModes);
setSupportedModes({
APMSubMode(APMSubMode::MANUAL ,true),
APMSubMode(APMSubMode::STABILIZE ,true),
APMSubMode(APMSubMode::ACRO ,true),
APMSubMode(APMSubMode::ALT_HOLD ,true),
APMSubMode(APMSubMode::AUTO ,true),
APMSubMode(APMSubMode::GUIDED ,true),
APMSubMode(APMSubMode::CIRCLE ,true),
APMSubMode(APMSubMode::SURFACE ,false),
APMSubMode(APMSubMode::POSHOLD ,true),
});
if (!_remapParamNameIntialized) {
FirmwarePlugin::remapParamNameMap_t& remapV3_5 = _remapParamName[3][5];
......@@ -134,34 +133,32 @@ ArduSubFirmwarePlugin::ArduSubFirmwarePlugin(void):
QList<MAV_CMD> ArduSubFirmwarePlugin::supportedMissionCommands(void)
{
QList<MAV_CMD> list;
list << MAV_CMD_NAV_WAYPOINT
<< MAV_CMD_NAV_RETURN_TO_LAUNCH
<< MAV_CMD_NAV_LAND
<< MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT
<< MAV_CMD_NAV_SPLINE_WAYPOINT
<< MAV_CMD_NAV_GUIDED_ENABLE
<< MAV_CMD_NAV_DELAY
<< MAV_CMD_CONDITION_DELAY << MAV_CMD_CONDITION_DISTANCE << MAV_CMD_CONDITION_YAW
<< MAV_CMD_DO_SET_MODE
<< MAV_CMD_DO_JUMP
<< MAV_CMD_DO_CHANGE_SPEED
<< MAV_CMD_DO_SET_HOME
<< MAV_CMD_DO_SET_RELAY << MAV_CMD_DO_REPEAT_RELAY
<< MAV_CMD_DO_SET_SERVO << MAV_CMD_DO_REPEAT_SERVO
<< MAV_CMD_DO_LAND_START
<< MAV_CMD_DO_SET_ROI
<< MAV_CMD_DO_DIGICAM_CONFIGURE << MAV_CMD_DO_DIGICAM_CONTROL
<< MAV_CMD_DO_MOUNT_CONTROL
<< MAV_CMD_DO_SET_CAM_TRIGG_DIST
<< MAV_CMD_DO_FENCE_ENABLE
<< MAV_CMD_DO_INVERTED_FLIGHT
<< MAV_CMD_DO_GRIPPER
<< MAV_CMD_DO_GUIDED_LIMITS
<< MAV_CMD_DO_AUTOTUNE_ENABLE;
return list;
return {
MAV_CMD_NAV_WAYPOINT,
MAV_CMD_NAV_RETURN_TO_LAUNCH,
MAV_CMD_NAV_LAND,
MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT,
MAV_CMD_NAV_SPLINE_WAYPOINT,
MAV_CMD_NAV_GUIDED_ENABLE,
MAV_CMD_NAV_DELAY,
MAV_CMD_CONDITION_DELAY, MAV_CMD_CONDITION_DISTANCE, MAV_CMD_CONDITION_YAW,
MAV_CMD_DO_SET_MODE,
MAV_CMD_DO_JUMP,
MAV_CMD_DO_CHANGE_SPEED,
MAV_CMD_DO_SET_HOME,
MAV_CMD_DO_SET_RELAY, MAV_CMD_DO_REPEAT_RELAY,
MAV_CMD_DO_SET_SERVO, MAV_CMD_DO_REPEAT_SERVO,
MAV_CMD_DO_LAND_START,
MAV_CMD_DO_SET_ROI,
MAV_CMD_DO_DIGICAM_CONFIGURE, MAV_CMD_DO_DIGICAM_CONTROL,
MAV_CMD_DO_MOUNT_CONTROL,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_CMD_DO_FENCE_ENABLE,
MAV_CMD_DO_INVERTED_FLIGHT,
MAV_CMD_DO_GRIPPER,
MAV_CMD_DO_GUIDED_LIMITS,
MAV_CMD_DO_AUTOTUNE_ENABLE,
};
}
int ArduSubFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const
......@@ -212,11 +209,13 @@ const QVariantList& ArduSubFirmwarePlugin::toolBarIndicators(const Vehicle* vehi
Q_UNUSED(vehicle);
//-- Sub specific list of indicators (Enter your modified list here)
if(_toolBarIndicators.size() == 0) {
_toolBarIndicators.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/MessageIndicator.qml")));
_toolBarIndicators.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/BatteryIndicator.qml")));
_toolBarIndicators.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/JoystickIndicator.qml")));
_toolBarIndicators.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml")));
_toolBarIndicators.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml")));
_toolBarIndicators = QVariantList({
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/MessageIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/BatteryIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/JoystickIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml")),
});
}
return _toolBarIndicators;
}
......
......@@ -322,17 +322,19 @@ const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle* vehicle)
Q_UNUSED(vehicle);
//-- Default list of indicators for all vehicles.
if(_toolBarIndicatorList.size() == 0) {
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/MultiVehicleSelector.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/MessageIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/TelemetryRSSIIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/RCRSSIIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/BatteryIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/VTOLModeIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSRTKIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/LinkIndicator.qml")));
_toolBarIndicatorList = QVariantList({
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/MultiVehicleSelector.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/MessageIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/TelemetryRSSIIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/RCRSSIIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/BatteryIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/VTOLModeIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSRTKIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/LinkIndicator.qml")),
});
}
return _toolBarIndicatorList;
}
......
......@@ -278,27 +278,25 @@ void PX4FirmwarePlugin::getParameterMetaDataVersionInfo(const QString& metaDataF
QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
{
QList<MAV_CMD> list;
list << MAV_CMD_NAV_WAYPOINT
<< MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TIME << MAV_CMD_NAV_LOITER_TO_ALT
<< MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF << MAV_CMD_NAV_RETURN_TO_LAUNCH
<< MAV_CMD_DO_JUMP
<< MAV_CMD_DO_VTOL_TRANSITION << MAV_CMD_NAV_VTOL_TAKEOFF << MAV_CMD_NAV_VTOL_LAND
<< MAV_CMD_DO_DIGICAM_CONTROL
<< MAV_CMD_DO_SET_CAM_TRIGG_DIST
<< MAV_CMD_DO_SET_SERVO
<< MAV_CMD_DO_CHANGE_SPEED
<< MAV_CMD_DO_LAND_START
<< MAV_CMD_DO_SET_ROI_LOCATION << MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET << MAV_CMD_DO_SET_ROI_NONE
<< MAV_CMD_DO_MOUNT_CONFIGURE
<< MAV_CMD_DO_MOUNT_CONTROL
<< MAV_CMD_SET_CAMERA_MODE
<< MAV_CMD_IMAGE_START_CAPTURE << MAV_CMD_IMAGE_STOP_CAPTURE << MAV_CMD_VIDEO_START_CAPTURE << MAV_CMD_VIDEO_STOP_CAPTURE
<< MAV_CMD_NAV_DELAY
<< MAV_CMD_CONDITION_YAW;
return list;
return {
MAV_CMD_NAV_WAYPOINT,
MAV_CMD_NAV_LOITER_UNLIM, MAV_CMD_NAV_LOITER_TIME, MAV_CMD_NAV_LOITER_TO_ALT,
MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF, MAV_CMD_NAV_RETURN_TO_LAUNCH,
MAV_CMD_DO_JUMP,
MAV_CMD_DO_VTOL_TRANSITION, MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND,
MAV_CMD_DO_DIGICAM_CONTROL,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_CMD_DO_SET_SERVO,
MAV_CMD_DO_CHANGE_SPEED,
MAV_CMD_DO_LAND_START,
MAV_CMD_DO_SET_ROI_LOCATION, MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET, MAV_CMD_DO_SET_ROI_NONE,
MAV_CMD_DO_MOUNT_CONFIGURE,
MAV_CMD_DO_MOUNT_CONTROL,
MAV_CMD_SET_CAMERA_MODE,
MAV_CMD_IMAGE_START_CAPTURE, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_CMD_VIDEO_START_CAPTURE, MAV_CMD_VIDEO_STOP_CAPTURE,
MAV_CMD_NAV_DELAY,
MAV_CMD_CONDITION_YAW,
};
}
QString PX4FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
......
......@@ -32,17 +32,17 @@ GenericSurfacePainter::GenericSurfacePainter()
//static
QSet<GstVideoFormat> GenericSurfacePainter::supportedPixelFormats()
{
return QSet<GstVideoFormat>()
return QSet<GstVideoFormat>({
#if Q_BYTE_ORDER == Q_BIG_ENDIAN
<< GST_VIDEO_FORMAT_ARGB
<< GST_VIDEO_FORMAT_xRGB
GST_VIDEO_FORMAT_ARGB,
GST_VIDEO_FORMAT_xRGB,
#else
<< GST_VIDEO_FORMAT_BGRA
<< GST_VIDEO_FORMAT_BGRx
GST_VIDEO_FORMAT_BGRA,
GST_VIDEO_FORMAT_BGRx,
#endif
<< GST_VIDEO_FORMAT_RGB
<< GST_VIDEO_FORMAT_RGB16
;
GST_VIDEO_FORMAT_RGB,
GST_VIDEO_FORMAT_RGB16,
});
}
void GenericSurfacePainter::init(const BufferFormat &format)
......
......@@ -67,26 +67,26 @@ OpenGLSurfacePainter::OpenGLSurfacePainter()
//static
QSet<GstVideoFormat> OpenGLSurfacePainter::supportedPixelFormats()
{
return QSet<GstVideoFormat>()
return QSet<GstVideoFormat>({
//also handled by the generic painter on LE
<< GST_VIDEO_FORMAT_BGRA
<< GST_VIDEO_FORMAT_BGRx
GST_VIDEO_FORMAT_BGRA,
GST_VIDEO_FORMAT_BGRx,
//also handled by the generic painter on BE
<< GST_VIDEO_FORMAT_ARGB
<< GST_VIDEO_FORMAT_xRGB
GST_VIDEO_FORMAT_ARGB,
GST_VIDEO_FORMAT_xRGB,
//also handled by the generic painter everywhere
<< GST_VIDEO_FORMAT_RGB
<< GST_VIDEO_FORMAT_RGB16
GST_VIDEO_FORMAT_RGB,
GST_VIDEO_FORMAT_RGB16,
//not handled by the generic painter
<< GST_VIDEO_FORMAT_BGR
<< GST_VIDEO_FORMAT_v308
<< GST_VIDEO_FORMAT_AYUV
<< GST_VIDEO_FORMAT_YV12
<< GST_VIDEO_FORMAT_I420
;
GST_VIDEO_FORMAT_BGR,
GST_VIDEO_FORMAT_v308,
GST_VIDEO_FORMAT_AYUV,
GST_VIDEO_FORMAT_YV12,
GST_VIDEO_FORMAT_I420,
});
}
void OpenGLSurfacePainter::updateColors(int brightness, int contrast, int hue, int saturation)
......
......@@ -513,50 +513,52 @@ QStringList SerialConfiguration::supportedBaudRates()
void SerialConfiguration::_initBaudRates()
{
kSupportedBaudRates.clear();
kSupportedBaudRates = QStringList({
#if USE_ANCIENT_RATES
#if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
kSupportedBaudRates << "50";
kSupportedBaudRates << "75";
"50",
"75",
#endif
kSupportedBaudRates << "110";
"110",
#if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
kSupportedBaudRates << "134";
kSupportedBaudRates << "150";
kSupportedBaudRates << "200";
"150",
"200" ,
"134" ,
#endif
kSupportedBaudRates << "300";
kSupportedBaudRates << "600";
kSupportedBaudRates << "1200";
"300",
"600",
"1200",
#if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
kSupportedBaudRates << "1800";
"1800",
#endif
#endif
kSupportedBaudRates << "2400";
kSupportedBaudRates << "4800";
kSupportedBaudRates << "9600";
"2400",
"4800",
"9600",
#if defined(Q_OS_WIN)
kSupportedBaudRates << "14400";
"14400",
#endif
kSupportedBaudRates << "19200";
kSupportedBaudRates << "38400";
"19200",
"38400",
#if defined(Q_OS_WIN)
kSupportedBaudRates << "56000";
"56000",
#endif
kSupportedBaudRates << "57600";
kSupportedBaudRates << "115200";
"57600",
"115200",
#if defined(Q_OS_WIN)
kSupportedBaudRates << "128000";
"128000",
#endif
kSupportedBaudRates << "230400";
"230400",
#if defined(Q_OS_WIN)
kSupportedBaudRates << "256000";
"256000",
#endif
kSupportedBaudRates << "460800";
kSupportedBaudRates << "500000";
"460800",
"500000",
#if defined(Q_OS_LINUX)
kSupportedBaudRates << "576000";
"576000",
#endif
kSupportedBaudRates << "921600";
"921600",
});
}
void SerialConfiguration::setUsbDirect(bool usbDirect)
......
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