mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
uncrustify ArduPlane/Attitude.pde
This commit is contained in:
parent
0f415bbc6a
commit
d5767ef817
@ -242,13 +242,13 @@ static void calc_nav_roll()
|
||||
* 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
|
||||
@ -349,13 +349,13 @@ static void set_servos(void)
|
||||
|
||||
// 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) &&
|
||||
@ -373,7 +373,7 @@ static void set_servos(void)
|
||||
|
||||
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();
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user