mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Math: added degF_to_Kelvin()
This commit is contained in:
parent
367503be91
commit
319592a148
@ -473,3 +473,9 @@ float fixedwing_turn_rate(float bank_angle_deg, float airspeed)
|
||||
bank_angle_deg = constrain_float(bank_angle_deg, -80, 80);
|
||||
return degrees(GRAVITY_MSS*tanf(radians(bank_angle_deg))/MAX(airspeed,1));
|
||||
}
|
||||
|
||||
// convert degrees farenheight to Kelvin
|
||||
float degF_to_Kelvin(float temp_f)
|
||||
{
|
||||
return (temp_f + 459.67) * 0.55556;
|
||||
}
|
||||
|
@ -345,3 +345,7 @@ uint16_t float2fixed(const float input, const uint8_t fractional_bits = 8);
|
||||
fixed wing aircraft
|
||||
*/
|
||||
float fixedwing_turn_rate(float bank_angle_deg, float airspeed);
|
||||
|
||||
// convert degrees farenheight to Kelvin
|
||||
float degF_to_Kelvin(float temp_f);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user