mirror of https://github.com/ArduPilot/ardupilot
Plane: removed old angle wrap code
This commit is contained in:
parent
091b474a1d
commit
a165f0d138
|
@ -130,20 +130,6 @@ static void calc_altitude_error()
|
|||
altitude_error_cm = target_altitude_cm - adjusted_altitude_cm();
|
||||
}
|
||||
|
||||
static int32_t wrap_360_cd(int32_t error)
|
||||
{
|
||||
if (error > 36000) error -= 36000;
|
||||
if (error < 0) error += 36000;
|
||||
return error;
|
||||
}
|
||||
|
||||
static int32_t wrap_180_cd(int32_t error)
|
||||
{
|
||||
if (error > 18000) error -= 36000;
|
||||
if (error < -18000) error += 36000;
|
||||
return error;
|
||||
}
|
||||
|
||||
static void update_loiter()
|
||||
{
|
||||
float power;
|
||||
|
|
Loading…
Reference in New Issue