diff --git a/flight/libraries/sanitycheck.c b/flight/libraries/sanitycheck.c
index 04015dfb7..bf0e37014 100644
--- a/flight/libraries/sanitycheck.c
+++ b/flight/libraries/sanitycheck.c
@@ -46,7 +46,7 @@
****************************/
// ! Check a stabilization mode switch position for safety
-static int32_t check_stabilization_settings(int index, bool multirotor);
+static int32_t check_stabilization_settings(int index, bool multirotor, bool coptercontrol);
/**
* Run a preflight check over the hardware configuration
@@ -98,34 +98,19 @@ int32_t configuration_check()
}
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED1:
- severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : severity;
+ severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor, coptercontrol) : severity;
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED2:
- severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : severity;
+ severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor, coptercontrol) : severity;
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED3:
- severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : severity;
+ severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor, coptercontrol) : severity;
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_AUTOTUNE:
if (!PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_AUTOTUNE)) {
severity = SYSTEMALARMS_ALARM_ERROR;
}
break;
- case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD:
- case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_ALTITUDEVARIO:
- if (coptercontrol) {
- severity = SYSTEMALARMS_ALARM_ERROR;
- }
- // TODO: put check equivalent to TASK_MONITOR_IsRunning
- // here as soon as available for delayed callbacks
- break;
- case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL:
- if (coptercontrol) {
- severity = SYSTEMALARMS_ALARM_ERROR;
- } else if (!PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { // Revo supports altitude hold
- severity = SYSTEMALARMS_ALARM_ERROR;
- }
- break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD:
if (coptercontrol) {
severity = SYSTEMALARMS_ALARM_ERROR;
@@ -199,7 +184,7 @@ int32_t configuration_check()
* @param[in] index Which stabilization mode to check
* @returns SYSTEMALARMS_ALARM_OK or SYSTEMALARMS_ALARM_ERROR
*/
-static int32_t check_stabilization_settings(int index, bool multirotor)
+static int32_t check_stabilization_settings(int index, bool multirotor, bool coptercontrol)
{
// Make sure the modes have identical sizes
if (FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM != FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_NUMELEM ||
@@ -224,15 +209,40 @@ static int32_t check_stabilization_settings(int index, bool multirotor)
return SYSTEMALARMS_ALARM_ERROR;
}
- // For multirotors verify that nothing is set to "none"
+ // For multirotors verify that roll/pitch/yaw are not set to "none"
+ // (why not? might be fun to test ones reactions ;) if you dare, set your frame to "custom"!
if (multirotor) {
- for (uint32_t i = 0; i < NELEMENTS(modes); i++) {
+ for (uint32_t i = 0; i < FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST; i++) {
if (modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NONE) {
return SYSTEMALARMS_ALARM_ERROR;
}
}
}
+ // coptercontrol cannot do altitude holding
+ if (coptercontrol) {
+ if (modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDE
+ || modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY
+ ) {
+ return SYSTEMALARMS_ALARM_ERROR;
+ }
+ }
+
+ // check that thrust modes are only set to thrust axis
+ for (uint32_t i = 0; i < FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST; i++) {
+ if (modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDE
+ || modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY
+ ) {
+ return SYSTEMALARMS_ALARM_ERROR;
+ }
+ }
+ if (!(modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NONE
+ || modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDE
+ || modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY
+ )) {
+ return SYSTEMALARMS_ALARM_ERROR;
+ }
+
// Warning: This assumes that certain conditions in the XML file are met. That
// FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NONE has the same numeric value for each channel
// and is the same for STABILIZATIONDESIRED_STABILIZATIONMODE_NONE
diff --git a/flight/modules/ManualControl/inc/manualcontrol.h b/flight/modules/ManualControl/inc/manualcontrol.h
index b5e2c9bf6..4f5fdcd32 100644
--- a/flight/modules/ManualControl/inc/manualcontrol.h
+++ b/flight/modules/ManualControl/inc/manualcontrol.h
@@ -61,13 +61,6 @@ void manualHandler(bool newinit);
*/
void stabilizedHandler(bool newinit);
-/**
- * @brief Handler to control deprecated flight modes controlled by AltitudeHold module
- * @input: ManualControlCommand
- * @output: AltitudeHoldDesired
- */
-void altitudeHandler(bool newinit);
-
/**
* @brief Handler to control Guided flightmodes. FlightControl is governed by PathFollower, control via PathDesired
* @input: NONE: fully automated mode -- TODO recursively call handler for advanced stick commands
@@ -119,9 +112,6 @@ void pathPlannerHandler(bool newinit);
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED1 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED1) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED2 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED2) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED3 == (int)FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) && \
- ((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD == (int)FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) && \
- ((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_ALTITUDEVARIO == (int)FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO) && \
- ((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL == (int)FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD == (int)FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_PATHPLANNER == (int)FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) && \
((int)FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_RETURNTOBASE == (int)FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE) && \
diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c
index 4de61af46..16294a920 100644
--- a/flight/modules/ManualControl/manualcontrol.c
+++ b/flight/modules/ManualControl/manualcontrol.c
@@ -85,16 +85,6 @@ static const controlHandler handler_AUTOTUNE = {
};
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
-// TODO: move the altitude handling into stabi
-static const controlHandler handler_ALTITUDE = {
- .controlChain = {
- .Stabilization = true,
- .PathFollower = false,
- .PathPlanner = false,
- },
- .handler = &altitudeHandler,
-};
-
static const controlHandler handler_PATHFOLLOWER = {
.controlChain = {
.Stabilization = true,
@@ -206,7 +196,6 @@ static void manualControlTask(void)
handler = &handler_STABILIZED;
break;
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
- case FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL:
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE:
case FLIGHTSTATUS_FLIGHTMODE_LAND:
@@ -216,10 +205,6 @@ static void manualControlTask(void)
case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER:
handler = &handler_PATHPLANNER;
break;
- case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD:
- case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEVARIO:
- handler = &handler_ALTITUDE;
- break;
#endif
case FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE:
handler = &handler_AUTOTUNE;
diff --git a/flight/modules/ManualControl/altitudehandler.c b/flight/modules/Stabilization/altitudeloop.c.old
similarity index 100%
rename from flight/modules/ManualControl/altitudehandler.c
rename to flight/modules/Stabilization/altitudeloop.c.old
diff --git a/flight/modules/Stabilization/stabilization.c b/flight/modules/Stabilization/stabilization.c
index 87c149ffe..88eeeda3e 100644
--- a/flight/modules/Stabilization/stabilization.c
+++ b/flight/modules/Stabilization/stabilization.c
@@ -838,10 +838,10 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
cruise_control_inverted_power_switch = settings.CruiseControlInvertedPowerSwitch;
cruise_control_neutral_thrust = (float)settings.CruiseControlNeutralThrust / 100.0f;
- memcpy(
- cruise_control_flight_mode_switch_pos_enable,
- settings.CruiseControlFlightModeSwitchPosEnable,
- sizeof(cruise_control_flight_mode_switch_pos_enable));
+ // memcpy( // disabled because removed from uavobject for refactoring (CRITICAL! doesnt fly, just to make it compile!!!)
+ // cruise_control_flight_mode_switch_pos_enable,
+ // settings.CruiseControlFlightModeSwitchPosEnable,
+ // sizeof(cruise_control_flight_mode_switch_pos_enable));
}
/**
diff --git a/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h b/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h
index d589d20ed..13697942d 100644
--- a/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h
+++ b/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h
@@ -169,10 +169,10 @@
#endif
#define PIOS_TELEM_RX_STACK_SIZE 410
#define PIOS_TELEM_TX_STACK_SIZE 560
-#define PIOS_EVENTDISPATCHER_STACK_SIZE 95
+#define PIOS_EVENTDISPATCHER_STACK_SIZE 95
/* This can't be too high to stop eventdispatcher thread overflowing */
-#define PIOS_EVENTDISAPTCHER_QUEUE 10
+#define PIOS_EVENTDISAPTCHER_QUEUE 10
/* Revolution series */
/* #define REVOLUTION */
diff --git a/flight/targets/boards/revolution/firmware/Makefile b/flight/targets/boards/revolution/firmware/Makefile
index 5b89372a1..bf9254e7c 100644
--- a/flight/targets/boards/revolution/firmware/Makefile
+++ b/flight/targets/boards/revolution/firmware/Makefile
@@ -33,7 +33,7 @@ MODULES += Sensors
MODULES += StateEstimation # use instead of Attitude
MODULES += Altitude/revolution
MODULES += Airspeed
-MODULES += AltitudeHold
+#MODULES += AltitudeHold # now integrated in Stabilization
MODULES += Stabilization
MODULES += VtolPathFollower
MODULES += ManualControl
diff --git a/flight/targets/boards/revoproto/firmware/Makefile b/flight/targets/boards/revoproto/firmware/Makefile
index 2e5df1ac3..2b2a4ad99 100644
--- a/flight/targets/boards/revoproto/firmware/Makefile
+++ b/flight/targets/boards/revoproto/firmware/Makefile
@@ -33,7 +33,7 @@ MODULES += Sensors
MODULES += StateEstimation # use instead of Attitude
MODULES += Altitude/revolution
MODULES += Airspeed
-MODULES += AltitudeHold
+#MODULES += AltitudeHold # now integrated in Stabilization
MODULES += Stabilization
MODULES += VtolPathFollower
MODULES += ManualControl
diff --git a/flight/targets/boards/simposix/firmware/Makefile b/flight/targets/boards/simposix/firmware/Makefile
index beda566a8..c6ffd2cc8 100644
--- a/flight/targets/boards/simposix/firmware/Makefile
+++ b/flight/targets/boards/simposix/firmware/Makefile
@@ -42,7 +42,7 @@ MODULES += FirmwareIAP
MODULES += StateEstimation
#MODULES += Sensors/simulated/Sensors
MODULES += Airspeed
-MODULES += AltitudeHold
+#MODULES += AltitudeHold # now integrated in Stabilization
#MODULES += OveroSync
# Paths
diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp
index d3348787c..8b732c197 100644
--- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp
+++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp
@@ -152,6 +152,9 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
addWidgetBinding("FlightModeSettings", "Stabilization1Settings", ui->fmsSsPos1Yaw, "Yaw", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true);
addWidgetBinding("FlightModeSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true);
+ addWidgetBinding("FlightModeSettings", "Stabilization1Settings", ui->fmsSsPos1Thrust, "Thrust", 1, true);
+ addWidgetBinding("FlightModeSettings", "Stabilization2Settings", ui->fmsSsPos2Thrust, "Thrust", 1, true);
+ addWidgetBinding("FlightModeSettings", "Stabilization3Settings", ui->fmsSsPos3Thrust, "Thrust", 1, true);
addWidgetBinding("FlightModeSettings", "Arming", ui->armControl);
addWidgetBinding("FlightModeSettings", "ArmedTimeout", ui->armTimeout, 0, 1000);
@@ -1324,32 +1327,26 @@ void ConfigInputWidget::updatePositionSlider()
default:
case 6:
ui->fmsModePos6->setEnabled(true);
- ui->cc_box_5->setEnabled(true);
ui->pidBankSs1_5->setEnabled(true);
// pass through
case 5:
ui->fmsModePos5->setEnabled(true);
- ui->cc_box_4->setEnabled(true);
ui->pidBankSs1_4->setEnabled(true);
// pass through
case 4:
ui->fmsModePos4->setEnabled(true);
- ui->cc_box_3->setEnabled(true);
ui->pidBankSs1_3->setEnabled(true);
// pass through
case 3:
ui->fmsModePos3->setEnabled(true);
- ui->cc_box_2->setEnabled(true);
ui->pidBankSs1_2->setEnabled(true);
// pass through
case 2:
ui->fmsModePos2->setEnabled(true);
- ui->cc_box_1->setEnabled(true);
ui->pidBankSs1_1->setEnabled(true);
// pass through
case 1:
ui->fmsModePos1->setEnabled(true);
- ui->cc_box_0->setEnabled(true);
ui->pidBankSs1_0->setEnabled(true);
// pass through
case 0:
@@ -1359,32 +1356,26 @@ void ConfigInputWidget::updatePositionSlider()
switch (manualSettingsDataPriv.FlightModeNumber) {
case 0:
ui->fmsModePos1->setEnabled(false);
- ui->cc_box_0->setEnabled(false);
ui->pidBankSs1_0->setEnabled(false);
// pass through
case 1:
ui->fmsModePos2->setEnabled(false);
- ui->cc_box_1->setEnabled(false);
ui->pidBankSs1_1->setEnabled(false);
// pass through
case 2:
ui->fmsModePos3->setEnabled(false);
- ui->cc_box_2->setEnabled(false);
ui->pidBankSs1_2->setEnabled(false);
// pass through
case 3:
ui->fmsModePos4->setEnabled(false);
- ui->cc_box_3->setEnabled(false);
ui->pidBankSs1_3->setEnabled(false);
// pass through
case 4:
ui->fmsModePos5->setEnabled(false);
- ui->cc_box_4->setEnabled(false);
ui->pidBankSs1_4->setEnabled(false);
// pass through
case 5:
ui->fmsModePos6->setEnabled(false);
- ui->cc_box_5->setEnabled(false);
ui->pidBankSs1_5->setEnabled(false);
// pass through
case 6:
diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui
index b6a1f765e..86e5d4c00 100644
--- a/ground/openpilotgcs/src/plugins/config/input.ui
+++ b/ground/openpilotgcs/src/plugins/config/input.ui
@@ -17,7 +17,7 @@
-
- 0
+ 1
@@ -27,16 +27,7 @@
0
-
- 0
-
-
- 0
-
-
- 0
-
-
+
0
-
@@ -117,20 +108,11 @@
0
0
774
- 748
+ 753
-
- 12
-
-
- 12
-
-
- 12
-
-
+
12
@@ -161,16 +143,7 @@
-
- 12
-
-
- 12
-
-
- 12
-
-
+
12
-
@@ -269,16 +242,7 @@
-
- 12
-
-
- 12
-
-
- 12
-
-
+
12
-
@@ -457,16 +421,7 @@
Flight Mode Switch Settings
-
- 0
-
-
- 0
-
-
- 0
-
-
+
0
-
@@ -546,21 +501,12 @@
0
0
- 768
- 742
+ 774
+ 753
-
- 12
-
-
- 12
-
-
- 12
-
-
+
12
-
@@ -587,7 +533,7 @@
Stabilization Modes Configuration
-
+
9
@@ -626,6 +572,51 @@
+ -
+
+
+ Qt::Horizontal
+
+
+ QSizePolicy::Fixed
+
+
+
+ 10
+ 20
+
+
+
+
+ -
+
+
+
+ 120
+ 20
+
+
+
+
+ 16777215
+ 20
+
+
+
+ background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
+color: rgb(255, 255, 255);
+border-radius: 5;
+font: bold 12px;
+margin:1px;
+
+
+ Thrust
+
+
+ Qt::AlignCenter
+
+
+
-
@@ -684,7 +675,7 @@ margin:1px;
- -
+
-
Qt::Horizontal
@@ -792,16 +783,7 @@ margin:1px;
QFrame::Raised
-
- 1
-
-
- 1
-
-
- 1
-
-
+
1
-
@@ -843,16 +825,7 @@ margin:1px;
QFrame::Raised
-
- 1
-
-
- 1
-
-
- 1
-
-
+
1
-
@@ -894,16 +867,7 @@ margin:1px;
QFrame::Raised
-
- 1
-
-
- 1
-
-
- 1
-
-
+
1
-
@@ -936,6 +900,48 @@ margin:1px;
+ -
+
+
+ QFrame::NoFrame
+
+
+ QFrame::Raised
+
+
+
+ 1
+
+
-
+
+
+
+ 0
+ 0
+
+
+
+ Qt::StrongFocus
+
+
+
+ -
+
+
+ Qt::StrongFocus
+
+
+
+ -
+
+
+ Qt::StrongFocus
+
+
+
+
+
+
-
@@ -973,23 +979,14 @@ margin:1px;
Flight Mode Switch Positions
-
- 9
-
-
- 9
-
-
- 9
-
-
+
9
6
-
-
+
80
@@ -1078,7 +1075,7 @@ channel value for each flight mode.
-
-
+
0
0
@@ -1090,7 +1087,7 @@ channel value for each flight mode.
- Avoid "Manual" for multirotors!
+ Avoid "Manual" for multirotors! Never select "Altitude", "VelocityControl" or "CruiseControl" on a fixed wing!
Qt::AlignCenter
@@ -1116,22 +1113,6 @@ channel value for each flight mode.
- -
-
-
- Qt::Horizontal
-
-
- QSizePolicy::Fixed
-
-
-
- 10
- 20
-
-
-
-
-
@@ -1164,35 +1145,6 @@ channel value for each flight mode.
- -
-
-
-
- 105
- 20
-
-
-
-
- 16777215
- 20
-
-
-
- background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
-color: rgb(255, 255, 255);
-border-radius: 5;
-font: bold 12px;
-margin:1px;
-
-
- Cruise Control
-
-
- Qt::AlignCenter
-
-
-
-
@@ -1229,294 +1181,6 @@ margin:1px;
- -
-
-
-
- 30
- 0
-
-
-
-
- 16777215
- 16777215
-
-
-
-
- 6
-
-
- 1
-
-
- 1
-
-
- 1
-
-
- 1
-
-
-
-
-
-
- 0
- 0
-
-
-
-
- 0
- 20
-
-
-
-
- 16777215
- 20
-
-
-
-
- 75
- true
-
-
-
- <html><head/><body><p>Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #1.</p></body></html>
-
-
- Qt::RightToLeft
-
-
-
-
-
-
- objname:StabilizationSettings
- fieldname:CruiseControlFlightModeSwitchPosEnable
- index:0
- haslimits:no
- scale:1
-
-
-
-
- -
-
-
-
- 0
- 20
-
-
-
-
- 16777215
- 20
-
-
-
-
- 75
- true
-
-
-
- <html><head/><body><p>Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #2.</p></body></html>
-
-
- Qt::RightToLeft
-
-
-
-
-
-
- objname:StabilizationSettings
- fieldname:CruiseControlFlightModeSwitchPosEnable
- index:1
- haslimits:no
- scale:1
-
-
-
-
- -
-
-
-
- 0
- 20
-
-
-
-
- 16777215
- 20
-
-
-
-
- 75
- true
-
-
-
- <html><head/><body><p>Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #3.</p></body></html>
-
-
- Qt::RightToLeft
-
-
-
-
-
-
- objname:StabilizationSettings
- fieldname:CruiseControlFlightModeSwitchPosEnable
- index:2
- haslimits:no
- scale:1
-
-
-
-
- -
-
-
- false
-
-
-
- 0
- 20
-
-
-
-
- 16777215
- 20
-
-
-
-
- 75
- true
-
-
-
- <html><head/><body><p>Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #4.</p></body></html>
-
-
- Qt::RightToLeft
-
-
-
-
-
-
- objname:StabilizationSettings
- fieldname:CruiseControlFlightModeSwitchPosEnable
- index:3
- haslimits:no
- scale:1
-
-
-
-
- -
-
-
- false
-
-
-
- 0
- 20
-
-
-
-
- 16777215
- 20
-
-
-
-
- 75
- true
-
-
-
- <html><head/><body><p>Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #5.</p></body></html>
-
-
- Qt::RightToLeft
-
-
-
-
-
-
- objname:StabilizationSettings
- fieldname:CruiseControlFlightModeSwitchPosEnable
- index:4
- haslimits:no
- scale:1
-
-
-
-
- -
-
-
- false
-
-
-
- 0
- 20
-
-
-
-
- 16777215
- 20
-
-
-
-
- 75
- true
-
-
-
- <html><head/><body><p>Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #6.</p></body></html>
-
-
- Qt::RightToLeft
-
-
-
-
-
-
- objname:StabilizationSettings
- fieldname:CruiseControlFlightModeSwitchPosEnable
- index:5
- haslimits:no
- scale:1
-
-
-
-
-
-
-
-
@@ -1538,21 +1202,12 @@ margin:1px;
QFrame::Raised
-
- 1
-
-
- 1
-
-
- 1
-
-
- 1
-
10
+
+ 1
+
-
@@ -1770,16 +1425,7 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
-
- 1
-
-
- 1
-
-
- 1
-
-
+
1
-
@@ -1867,7 +1513,7 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
-
-
+
75
@@ -1881,16 +1527,7 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
-
- 1
-
-
- 1
-
-
- 1
-
-
+
1
-
@@ -2075,16 +1712,7 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
Arming Settings
-
- 0
-
-
- 0
-
-
- 0
-
-
+
0
-
@@ -2164,21 +1792,12 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
0
0
- 768
- 742
+ 774
+ 753
-
- 12
-
-
- 12
-
-
- 12
-
-
+
12
-
diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp
index 9221d7393..d3e8656da 100644
--- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp
+++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp
@@ -328,8 +328,8 @@ void VehicleConfigurationHelper::applyFlighModeConfiguration()
data.FlightModePosition[0] = FlightModeSettings::FLIGHTMODEPOSITION_STABILIZED1;
data.FlightModePosition[1] = FlightModeSettings::FLIGHTMODEPOSITION_STABILIZED2;
data.FlightModePosition[2] = FlightModeSettings::FLIGHTMODEPOSITION_STABILIZED3;
- data.FlightModePosition[3] = FlightModeSettings::FLIGHTMODEPOSITION_ALTITUDEHOLD;
- data.FlightModePosition[4] = FlightModeSettings::FLIGHTMODEPOSITION_POSITIONHOLD;
+ data.FlightModePosition[3] = FlightModeSettings::FLIGHTMODEPOSITION_MANUAL;
+ data.FlightModePosition[4] = FlightModeSettings::FLIGHTMODEPOSITION_MANUAL;
data.FlightModePosition[5] = FlightModeSettings::FLIGHTMODEPOSITION_MANUAL;
modeSettings->setData(data);
addModifiedObject(modeSettings, tr("Writing flight mode settings 1/2"));
diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro
index 9c6dc8d67..f5db470dd 100644
--- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro
+++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro
@@ -62,6 +62,7 @@ HEADERS += \
$$UAVOBJECT_SYNTHETICS/overosyncstats.h \
$$UAVOBJECT_SYNTHETICS/overosyncsettings.h \
$$UAVOBJECT_SYNTHETICS/systemsettings.h \
+ $$UAVOBJECT_SYNTHETICS/stabilizationstatus.h \
$$UAVOBJECT_SYNTHETICS/stabilizationsettings.h \
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank1.h \
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank2.h \
@@ -163,6 +164,7 @@ SOURCES += \
$$UAVOBJECT_SYNTHETICS/overosyncstats.cpp \
$$UAVOBJECT_SYNTHETICS/overosyncsettings.cpp \
$$UAVOBJECT_SYNTHETICS/systemsettings.cpp \
+ $$UAVOBJECT_SYNTHETICS/stabilizationstatus.cpp \
$$UAVOBJECT_SYNTHETICS/stabilizationsettings.cpp \
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank1.cpp \
$$UAVOBJECT_SYNTHETICS/stabilizationsettingsbank2.cpp \
diff --git a/shared/uavobjectdefinition/flightmodesettings.xml b/shared/uavobjectdefinition/flightmodesettings.xml
index b9b6aa211..e2ea535f6 100644
--- a/shared/uavobjectdefinition/flightmodesettings.xml
+++ b/shared/uavobjectdefinition/flightmodesettings.xml
@@ -6,20 +6,38 @@
+ elementnames="Roll,Pitch,Yaw,Thrust"
+ options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,Altitude,VerticalVelocity,CruiseControl"
+ defaultvalue="Attitude,Attitude,AxisLock,CruiseControl"
+ limits="%NE:RelayRate:RelayAttitude:Altitude:VerticalVelocity:CruiseControl; \
+ %NE:RelayRate:RelayAttitude:Altitude:VerticalVelocity:CruiseControl; \
+ %NE:RelayRate:RelayAttitude:Altitude:VerticalVelocity:CruiseControl; \
+ %NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
+ %0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:Altitude:VerticalVelocity,\
+ %0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:Altitude:VerticalVelocity;"
+ />
+ elementnames="Roll,Pitch,Yaw,Thrust"
+ options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,Altitude,VerticalVelocity,CruiseControl"
+ defaultvalue="Attitude,Attitude,Rate,CruiseControl"
+ limits="%NE:RelayRate:RelayAttitude:Altitude:VerticalVelocity:CruiseControl; \
+ %NE:RelayRate:RelayAttitude:Altitude:VerticalVelocity:CruiseControl; \
+ %NE:RelayRate:RelayAttitude:Altitude:VerticalVelocity:CruiseControl; \
+ %NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
+ %0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:Altitude:VerticalVelocity,\
+ %0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:Altitude:VerticalVelocity;"
+ />
+ elementnames="Roll,Pitch,Yaw,Thrust"
+ options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,Altitude,VerticalVelocity,CruiseControl"
+ defaultvalue="Rate,Rate,Rate,None"
+ limits="%NE:RelayRate:RelayAttitude:Altitude:VerticalVelocity:CruiseControl; \
+ %NE:RelayRate:RelayAttitude:Altitude:VerticalVelocity:CruiseControl; \
+ %NE:RelayRate:RelayAttitude:Altitude:VerticalVelocity:CruiseControl; \
+ %NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
+ %0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:Altitude:VerticalVelocity,\
+ %0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:Altitude:VerticalVelocity;"
+ />
@@ -27,32 +45,32 @@
units=""
type="enum"
elements="6"
- options="Manual,Stabilized1,Stabilized2,Stabilized3,Autotune,AltitudeHold,AltitudeVario,VelocityControl,PositionHold,ReturnToBase,Land,PathPlanner,POI"
- defaultvalue="Stabilized1,Stabilized2,Stabilized3,AltitudeHold,AltitudeVario,Manual"
+ options="Manual,Stabilized1,Stabilized2,Stabilized3,Autotune,PositionHold,ReturnToBase,Land,PathPlanner,POI"
+ defaultvalue="Stabilized1,Stabilized2,Stabilized3,Manual,Manual,Manual"
limits="\
- %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
+ %0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
\
- %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
+ %0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
\
- %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
+ %0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
\
- %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
+ %0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
\
- %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
+ %0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
\
- %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
- %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI"/>
+ %0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
+ %0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI"/>
diff --git a/shared/uavobjectdefinition/flightstatus.xml b/shared/uavobjectdefinition/flightstatus.xml
index a7009f4c4..f24408c5c 100644
--- a/shared/uavobjectdefinition/flightstatus.xml
+++ b/shared/uavobjectdefinition/flightstatus.xml
@@ -4,7 +4,7 @@
-
+
diff --git a/shared/uavobjectdefinition/stabilizationdesired.xml b/shared/uavobjectdefinition/stabilizationdesired.xml
index 70bdfe9c0..38279a96b 100644
--- a/shared/uavobjectdefinition/stabilizationdesired.xml
+++ b/shared/uavobjectdefinition/stabilizationdesired.xml
@@ -5,9 +5,8 @@
-
-
-
+
+
diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml
index d9702c75e..51d6497bd 100644
--- a/shared/uavobjectdefinition/stabilizationsettings.xml
+++ b/shared/uavobjectdefinition/stabilizationsettings.xml
@@ -37,7 +37,6 @@
-
diff --git a/shared/uavobjectdefinition/stabilizationstatus.xml b/shared/uavobjectdefinition/stabilizationstatus.xml
new file mode 100644
index 000000000..f68f8e30b
--- /dev/null
+++ b/shared/uavobjectdefinition/stabilizationstatus.xml
@@ -0,0 +1,28 @@
+
+
+