diff --git a/ArduSub/control_manual.cpp b/ArduSub/control_manual.cpp index d49d0bdc6e..e1f2e0c573 100644 --- a/ArduSub/control_manual.cpp +++ b/ArduSub/control_manual.cpp @@ -30,7 +30,7 @@ void Sub::manual_run() motors.set_roll(channel_roll->norm_input_dz()*0.67f); motors.set_pitch(channel_pitch->norm_input_dz()*0.67f); motors.set_yaw(channel_yaw->norm_input_dz()*0.67f); - motors.set_throttle(channel_throttle->norm_input()); + motors.set_throttle(channel_throttle->norm_input_dz()); motors.set_forward(channel_forward->norm_input_dz()*0.67f); motors.set_lateral(channel_lateral->norm_input_dz()*0.67f); }