diff --git a/ArduSub/control_acro.cpp b/ArduSub/control_acro.cpp index 3725d8c5df..19e7f505b4 100644 --- a/ArduSub/control_acro.cpp +++ b/ArduSub/control_acro.cpp @@ -49,8 +49,8 @@ void Sub::acro_run() //control_in is range 0-1000 //radio_in is raw pwm value - motors.set_forward(channel_forward->norm_input()); - motors.set_lateral(channel_lateral->norm_input()); + motors.set_forward(channel_forward->norm_input_dz()); + motors.set_lateral(channel_lateral->norm_input_dz()); } diff --git a/ArduSub/control_althold.cpp b/ArduSub/control_althold.cpp index 8cc389d405..60498119c9 100644 --- a/ArduSub/control_althold.cpp +++ b/ArduSub/control_althold.cpp @@ -160,6 +160,6 @@ void Sub::althold_run() //control_in is range 0-1000 //radio_in is raw pwm value - motors.set_forward(channel_forward->norm_input()); - motors.set_lateral(channel_lateral->norm_input()); + motors.set_forward(channel_forward->norm_input_dz()); + motors.set_lateral(channel_lateral->norm_input_dz()); } diff --git a/ArduSub/control_manual.cpp b/ArduSub/control_manual.cpp index afb3791167..d49d0bdc6e 100644 --- a/ArduSub/control_manual.cpp +++ b/ArduSub/control_manual.cpp @@ -27,10 +27,10 @@ void Sub::manual_run() motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); - motors.set_roll(channel_roll->norm_input()*0.67f); - motors.set_pitch(channel_pitch->norm_input()*0.67f); - motors.set_yaw(channel_yaw->norm_input()*0.67f); + 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_forward(channel_forward->norm_input()*0.67f); - motors.set_lateral(channel_lateral->norm_input()*0.67f); + motors.set_forward(channel_forward->norm_input_dz()*0.67f); + motors.set_lateral(channel_lateral->norm_input_dz()*0.67f); } diff --git a/ArduSub/control_stabilize.cpp b/ArduSub/control_stabilize.cpp index 7b855a4d13..ed0adf4464 100644 --- a/ArduSub/control_stabilize.cpp +++ b/ArduSub/control_stabilize.cpp @@ -78,6 +78,6 @@ void Sub::stabilize_run() //control_in is range -1000-1000 //radio_in is raw pwm value - motors.set_forward(channel_forward->norm_input()); - motors.set_lateral(channel_lateral->norm_input()); + motors.set_forward(channel_forward->norm_input_dz()); + motors.set_lateral(channel_lateral->norm_input_dz()); } diff --git a/ArduSub/control_surface.cpp b/ArduSub/control_surface.cpp index 98a6a3d446..4b19718436 100644 --- a/ArduSub/control_surface.cpp +++ b/ArduSub/control_surface.cpp @@ -59,6 +59,6 @@ void Sub::surface_run() pos_control.update_z_controller(); // pilot has control for repositioning - motors.set_forward(channel_forward->norm_input()); - motors.set_lateral(channel_lateral->norm_input()); + motors.set_forward(channel_forward->norm_input_dz()); + motors.set_lateral(channel_lateral->norm_input_dz()); }