mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Limits: fixed some memory cast warnings
This commit is contained in:
parent
0534406f6d
commit
859401f334
@ -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()) {
|
||||
|
Loading…
Reference in New Issue
Block a user