diff --git a/ArduSub/control_manual.cpp b/ArduSub/control_manual.cpp index 0b1081a7ff..c98c199408 100644 --- a/ArduSub/control_manual.cpp +++ b/ArduSub/control_manual.cpp @@ -18,9 +18,6 @@ bool Sub::manual_init(bool ignore_checks) // should be called at 100hz or more void Sub::manual_run() { - float target_roll, target_pitch, target_yaw; - float pilot_throttle_scaled; - // if not armed set throttle to zero and exit immediately if (!motors.armed() || !motors.get_interlock()) { motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);