uncrustify ArduPlane/Attitude.pde

This commit is contained in:
uncrustify 2012-08-21 19:19:50 -07:00 committed by Pat Hickey
parent ce04d62815
commit e5ac3bdc65

View File

@ -20,7 +20,7 @@ static void stabilize()
}
speed_scaler = constrain(speed_scaler, 0.5, 2.0);
} else {
if (g.channel_throttle.servo_out > 0){
if (g.channel_throttle.servo_out > 0) {
speed_scaler = 0.5 + ((float)THROTTLE_CRUISE / g.channel_throttle.servo_out / 2.0); // First order taylor expansion of square root
// Should maybe be to the 2/7 power, but we aren't goint to implement that...
}else{
@ -29,7 +29,7 @@ static void stabilize()
speed_scaler = constrain(speed_scaler, 0.6, 1.67); // This case is constrained tighter as we don't have real speed info
}
if(crash_timer > 0){
if(crash_timer > 0) {
nav_roll_cd = 0;
}
@ -122,7 +122,7 @@ static void stabilize()
static void crash_checker()
{
if(ahrs.pitch_sensor < -4500){
if(ahrs.pitch_sensor < -4500) {
crash_timer = 255;
}
if(crash_timer > 0)
@ -165,8 +165,8 @@ static void calc_throttle()
}
/*****************************************
* Calculate desired roll/pitch/yaw angles (in medium freq loop)
*****************************************/
* Calculate desired roll/pitch/yaw angles (in medium freq loop)
*****************************************/
// Yaw is separated into a function for future implementation of heading hold on rolling take-off
// ----------------------------------------------------------------------------------------
@ -239,20 +239,20 @@ static void calc_nav_roll()
/*****************************************
* Roll servo slew limit
*****************************************/
* Roll servo slew limit
*****************************************/
/*
float roll_slew_limit(float servo)
{
static float last;
float temp = constrain(servo, last-ROLL_SLEW_LIMIT * delta_ms_fast_loop/1000.f, last + ROLL_SLEW_LIMIT * delta_ms_fast_loop/1000.f);
last = servo;
return temp;
}*/
* float roll_slew_limit(float servo)
* {
* static float last;
* float temp = constrain(servo, last-ROLL_SLEW_LIMIT * delta_ms_fast_loop/1000.f, last + ROLL_SLEW_LIMIT * delta_ms_fast_loop/1000.f);
* last = servo;
* return temp;
* }*/
/*****************************************
* Throttle slew limit
*****************************************/
* Throttle slew limit
*****************************************/
static void throttle_slew_limit()
{
static int16_t last = 1000;
@ -295,9 +295,9 @@ static void set_servos(void)
rc_array[CH_7] = &g.rc_7;
rc_array[CH_8] = &g.rc_8;
if(control_mode == MANUAL){
if(control_mode == MANUAL) {
// do a direct pass through of radio values
if (g.mix_mode == 0){
if (g.mix_mode == 0) {
g.channel_roll.radio_out = g.channel_roll.radio_in;
g.channel_pitch.radio_out = g.channel_pitch.radio_in;
} else {
@ -341,39 +341,39 @@ static void set_servos(void)
}
g.channel_rudder.calc_pwm();
#if THROTTLE_OUT == 0
#if THROTTLE_OUT == 0
g.channel_throttle.servo_out = 0;
#else
#else
// convert 0 to 100% into PWM
g.channel_throttle.servo_out = constrain(g.channel_throttle.servo_out, g.throttle_min.get(), g.throttle_max.get());
// We want to supress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
/* Disable throttle if following conditions are met:
1 - We are in Circle mode (which we use for short term failsafe), or in FBW-B or higher
AND
2 - Our reported altitude is within 10 meters of the home altitude.
3 - Our reported speed is under 5 meters per second.
4 - We are not performing a takeoff in Auto mode
OR
5 - Home location is not set
* 1 - We are in Circle mode (which we use for short term failsafe), or in FBW-B or higher
* AND
* 2 - Our reported altitude is within 10 meters of the home altitude.
* 3 - Our reported speed is under 5 meters per second.
* 4 - We are not performing a takeoff in Auto mode
* OR
* 5 - Home location is not set
*/
if (
(control_mode == CIRCLE || control_mode >= FLY_BY_WIRE_B) &&
(labs(home.alt - current_loc.alt) < 1000) &&
((airspeed.use()? airspeed.get_airspeed_cm() : g_gps->ground_speed) < 500 ) &&
((airspeed.use() ? airspeed.get_airspeed_cm() : g_gps->ground_speed) < 500 ) &&
!(control_mode==AUTO && takeoff_complete == false)
) {
g.channel_throttle.servo_out = 0;
g.channel_throttle.calc_pwm();
}
#endif
#endif
g.channel_throttle.calc_pwm();
if (control_mode >= FLY_BY_WIRE_B) {
/* only do throttle slew limiting in modes where throttle
control is automatic */
* control is automatic */
throttle_slew_limit();
}
}
@ -419,17 +419,17 @@ static void set_servos(void)
g.rc_6.output_ch(CH_6);
g.rc_7.output_ch(CH_7);
g.rc_8.output_ch(CH_8);
# if CONFIG_APM_HARDWARE != APM_HARDWARE_APM1
# if CONFIG_APM_HARDWARE != APM_HARDWARE_APM1
g.rc_9.output_ch(CH_9);
g.rc_10.output_ch(CH_10);
g.rc_11.output_ch(CH_11);
# endif
# endif
#endif
}
static void demo_servos(byte i) {
while(i > 0){
while(i > 0) {
gcs_send_text_P(SEVERITY_LOW,PSTR("Demo Servos!"));
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
APM_RC.OutputCh(1, 1400);