Skip to content

Commit 54e1593

Browse files
xianglunkaiWilliangalvani
authored andcommitted
ArduSub/mode_acro: fix bug for dealing throttle from pilot
1 parent 2a26d3c commit 54e1593

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

ArduSub/mode_acro.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ void ModeAcro::run()
3333
attitude_control->input_rate_bf_roll_pitch_yaw_cds(target_roll, target_pitch, target_yaw);
3434

3535
// output pilot's throttle without angle boost
36-
attitude_control->set_throttle_out(channel_throttle->norm_input(), false, g.throttle_filt);
36+
attitude_control->set_throttle_out((channel_throttle->norm_input() + 1.0f) / 2.0f, false, g.throttle_filt);
3737

3838
//control_in is range 0-1000
3939
//radio_in is raw pwm value

0 commit comments

Comments
 (0)