From 10b8030e628161eeabe120dca07f770dd43a5ab1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 19 Nov 2012 08:27:17 +1100 Subject: [PATCH] AP_Limits: fixed some memory cast warnings --- libraries/AP_Limits/AP_Limit_Geofence.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Limits/AP_Limit_Geofence.cpp b/libraries/AP_Limits/AP_Limit_Geofence.cpp index 96fc46089f..8778037bc9 100644 --- a/libraries/AP_Limits/AP_Limit_Geofence.cpp +++ b/libraries/AP_Limits/AP_Limit_Geofence.cpp @@ -144,7 +144,7 @@ AP_Int8 AP_Limit_Geofence::fence_total() { // save a fence point void AP_Limit_Geofence::set_fence_point_with_index(Vector2l &point, uint8_t i) { - uint32_t mem; + uintptr_t mem; if (i >= (unsigned)fence_total()) { // not allowed @@ -165,7 +165,7 @@ void AP_Limit_Geofence::set_fence_point_with_index(Vector2l &point, uint8_t i) */ Vector2l AP_Limit_Geofence::get_fence_point_with_index(uint8_t i) { - uint32_t mem; + uintptr_t mem; Vector2l ret; if (i > (unsigned) fence_total()) {