uncrustify ArduCopter/toy.pde

This commit is contained in:
uncrustify 2012-08-16 17:50:03 -07:00 committed by Pat Hickey
parent 1e2c01d8f6
commit c7ff6a6335

View File

@ -14,24 +14,25 @@ static const int16_t toy_lookup[] = {
1115, 2235, 3350, 4470,
1301, 2608, 3908, 4500,
1487, 2980, 4467, 4500,
1673, 3353, 4500, 4500};
1673, 3353, 4500, 4500
};
#endif
//called at 10hz
void update_toy_throttle()
{
/*
// Disabled, now handled by TOY_A (Alt hold) and TOY_M (Manual throttle)
if (false == CH6_toy_flag && g.rc_6.radio_in >= CH_6_PWM_TRIGGER){
CH6_toy_flag = true;
throttle_mode = THROTTLE_MANUAL;
}else if (CH6_toy_flag && g.rc_6.radio_in < CH_6_PWM_TRIGGER){
CH6_toy_flag = false;
throttle_mode = THROTTLE_AUTO;
set_new_altitude(current_loc.alt);
saved_toy_throttle = g.rc_3.control_in;
}*/
* // Disabled, now handled by TOY_A (Alt hold) and TOY_M (Manual throttle)
* if (false == CH6_toy_flag && g.rc_6.radio_in >= CH_6_PWM_TRIGGER){
* CH6_toy_flag = true;
* throttle_mode = THROTTLE_MANUAL;
*
* }else if (CH6_toy_flag && g.rc_6.radio_in < CH_6_PWM_TRIGGER){
* CH6_toy_flag = false;
* throttle_mode = THROTTLE_AUTO;
* set_new_altitude(current_loc.alt);
* saved_toy_throttle = g.rc_3.control_in;
* }*/
// look for a change in throttle position to exit throttle hold
if(abs(g.rc_3.control_in - saved_toy_throttle) > 40) {