Sub: Update forward and strafe rc channels in the control mode files.

This commit is contained in:
jaxxzer 2016-01-08 18:25:59 -05:00 committed by Andrew Tridgell
parent c2d37ffd6e
commit 2f3aff7499
3 changed files with 15 additions and 0 deletions

View File

@ -47,6 +47,11 @@ void Copter::acro_run()
// output pilot's throttle without angle boost // output pilot's throttle without angle boost
attitude_control.set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt); attitude_control.set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
//control_in is range 0-1000
//radio_in is raw pwm value
motors.set_forward(channel_forward->radio_in);
motors.set_strafe(channel_strafe->radio_in);
} }

View File

@ -158,4 +158,9 @@ void Copter::althold_run()
pos_control.update_z_controller(); pos_control.update_z_controller();
break; break;
} }
//control_in is range 0-1000
//radio_in is raw pwm value
motors.set_forward(channel_forward->radio_in);
motors.set_strafe(channel_strafe->radio_in);
} }

View File

@ -57,4 +57,9 @@ void Copter::stabilize_run()
// output pilot's throttle // output pilot's throttle
attitude_control.set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt); attitude_control.set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt);
//control_in is range 0-1000
//radio_in is raw pwm value
motors.set_forward(channel_forward->radio_in);
motors.set_strafe(channel_strafe->radio_in);
} }