Plane: added check for QPOS initialisation

thanks to Kris for noticing this!
This commit is contained in:
Andrew Tridgell 2021-06-09 10:54:20 +10:00
parent db34577755
commit 3611b1dbf7
2 changed files with 11 additions and 0 deletions

View File

@ -2613,6 +2613,11 @@ void QuadPlane::vtol_position_controller(void)
// horizontal position control // horizontal position control
switch (poscontrol.get_state()) { switch (poscontrol.get_state()) {
case QPOS_NONE:
poscontrol.set_state(QPOS_POSITION1);
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
break;
case QPOS_APPROACH: case QPOS_APPROACH:
if (in_vtol_mode()) { if (in_vtol_mode()) {
// this means we're not running update_transition() and // this means we're not running update_transition() and
@ -2909,6 +2914,11 @@ void QuadPlane::vtol_position_controller(void)
// now height control // now height control
switch (poscontrol.get_state()) { switch (poscontrol.get_state()) {
case QPOS_NONE:
poscontrol.set_state(QPOS_POSITION1);
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
break;
case QPOS_APPROACH: case QPOS_APPROACH:
case QPOS_AIRBRAKE: case QPOS_AIRBRAKE:
// we just want stability from the VTOL controller in these // we just want stability from the VTOL controller in these

View File

@ -459,6 +459,7 @@ private:
uint32_t last_loiter_ms; uint32_t last_loiter_ms;
enum position_control_state { enum position_control_state {
QPOS_NONE = 0,
QPOS_APPROACH, QPOS_APPROACH,
QPOS_AIRBRAKE, QPOS_AIRBRAKE,
QPOS_POSITION1, QPOS_POSITION1,