diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 5d308773ca..440fe2b11c 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2366,7 +2366,7 @@ void QuadPlane::vtol_position_controller(void) case QPOS_APPROACH: if (in_vtol_mode()) { - // this means we're not running update_transition() and + // this means we're not running transition update code and // thus not doing qassist checking, force POSITION1 mode // now. We don't expect this to trigger, it is a failsafe // for a logic error diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index d87709562c..6861acc956 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -223,9 +223,6 @@ private: // check for quadplane assistance needed bool should_assist(float aspeed, bool have_airspeed); - // update transition handling - void update_transition(void); - // check for an EKF yaw reset void check_yaw_reset(void);