From e4b313d2cab7e2229a4f39f1bf2baa652ce89e54 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Sun, 25 Oct 2015 14:23:25 -0200 Subject: [PATCH] Replace use of memcpy_P() with memcpy() --- libraries/AP_Declination/AP_Declination.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Declination/AP_Declination.cpp b/libraries/AP_Declination/AP_Declination.cpp index 52e4576507..70dce1b306 100644 --- a/libraries/AP_Declination/AP_Declination.cpp +++ b/libraries/AP_Declination/AP_Declination.cpp @@ -204,7 +204,7 @@ AP_Declination::get_lookup_value(uint8_t x, uint8_t y) for(i = start_index; i < (start_index + PGM_UINT8(&declination_keys[1][x])) && current_virtual_index <= y; i++) { // Pull out the row_value struct - memcpy_P((void*) &stval, (const prog_char *)&declination_values[i], sizeof(struct row_value)); + memcpy((void*) &stval, (const prog_char *)&declination_values[i], sizeof(struct row_value)); // Pull the first offset and determine sign offset = stval.abs_offset;