updated throttle range

This commit is contained in:
Jason Short 2012-02-18 21:11:06 -08:00
parent 669e8e34ea
commit 0517ed5199
1 changed files with 3 additions and 6 deletions

View File

@ -22,10 +22,7 @@ static void init_rc_in()
// set rc channel ranges // set rc channel ranges
g.rc_1.set_angle(4500); g.rc_1.set_angle(4500);
g.rc_2.set_angle(4500); g.rc_2.set_angle(4500);
g.rc_3.set_range(0, MAXIMUM_THROTTLE); g.rc_3.set_range(MINIMUM_THROTTLE, MAXIMUM_THROTTLE);
#if FRAME_CONFIG != HELI_FRAME
g.rc_3.scale_output = .9;
#endif
g.rc_4.set_angle(4500); g.rc_4.set_angle(4500);
// reverse: CW = left // reverse: CW = left
@ -69,7 +66,7 @@ static void init_rc_out()
} }
// we are full throttle // we are full throttle
if(g.rc_3.control_in == 800){ if(g.rc_3.control_in >= (MAXIMUM_THROTTLE - 50)){
if(g.esc_calibrate == 0){ if(g.esc_calibrate == 0){
// we will enter esc_calibrate mode on next reboot // we will enter esc_calibrate mode on next reboot
g.esc_calibrate.set_and_save(1); g.esc_calibrate.set_and_save(1);
@ -138,7 +135,7 @@ static void read_radio()
#if FRAME_CONFIG != HELI_FRAME #if FRAME_CONFIG != HELI_FRAME
// limit our input to 800 so we can still pitch and roll // limit our input to 800 so we can still pitch and roll
g.rc_3.control_in = min(g.rc_3.control_in, 800); g.rc_3.control_in = min(g.rc_3.control_in, MAXIMUM_THROTTLE);
#endif #endif
throttle_failsafe(g.rc_3.radio_in); throttle_failsafe(g.rc_3.radio_in);