Browse Source

ArduPlane: avoid comparison between signed and unsigned

master
Lucas De Marchi 9 years ago
parent
commit
8eb0b559f2
  1. 2
      ArduPlane/Attitude.cpp
  2. 2
      ArduPlane/geofence.cpp

2
ArduPlane/Attitude.cpp

@ -586,7 +586,7 @@ bool Plane::suppress_throttle(void) @@ -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

2
ArduPlane/geofence.cpp

@ -49,7 +49,7 @@ static const StorageAccess fence_storage(StorageManager::StorageFence); @@ -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…
Cancel
Save