mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduPlane: avoid comparison between signed and unsigned
This commit is contained in:
parent
fef364e4e8
commit
8eb0b559f2
@ -586,7 +586,7 @@ bool Plane::suppress_throttle(void)
|
||||
|
||||
uint32_t launch_duration_ms = ((int32_t)g.takeoff_throttle_delay)*100 + 2000;
|
||||
if (is_flying() &&
|
||||
millis() - started_flying_ms > MAX(launch_duration_ms,5000) && // been flying >5s in any mode
|
||||
millis() - started_flying_ms > MAX(launch_duration_ms, 5000U) && // been flying >5s in any mode
|
||||
adjusted_relative_altitude_cm() > 500 && // are >5m above AGL/home
|
||||
labs(ahrs.pitch_sensor) < 3000 && // not high pitch, which happens when held before launch
|
||||
gps_movement) { // definate gps movement
|
||||
|
@ -49,7 +49,7 @@ static const StorageAccess fence_storage(StorageManager::StorageFence);
|
||||
*/
|
||||
uint8_t Plane::max_fencepoints(void)
|
||||
{
|
||||
return MIN(255, fence_storage.size() / sizeof(Vector2l));
|
||||
return MIN(255U, fence_storage.size() / sizeof(Vector2l));
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user