mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_Math: use if/else chain instead of 2 ternary operators
This commit is contained in:
parent
174f899a29
commit
846b4927ec
@ -141,7 +141,16 @@ T constrain_value(const T amt, const T low, const T high)
|
|||||||
if (isnan(amt)) {
|
if (isnan(amt)) {
|
||||||
return (low + high) * 0.5f;
|
return (low + high) * 0.5f;
|
||||||
}
|
}
|
||||||
return amt < low ? low : (amt > high ? high : amt);
|
|
||||||
|
if (amt < low) {
|
||||||
|
return low;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (amt > high) {
|
||||||
|
return high;
|
||||||
|
}
|
||||||
|
|
||||||
|
return amt;
|
||||||
}
|
}
|
||||||
|
|
||||||
template int constrain_value<int>(const int amt, const int low, const int high);
|
template int constrain_value<int>(const int amt, const int low, const int high);
|
||||||
|
Loading…
Reference in New Issue
Block a user