From 23a1e33e205b2d565c986fdb5c0b4ba2868327a5 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sat, 28 Jul 2012 17:19:19 +0900 Subject: [PATCH] AP_InertialSensor_MPU6000: another attempt at fixing the SITL build --- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 24fc4c4d81..d8d5471ce9 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -879,7 +879,7 @@ void AP_InertialSensor_MPU6000::dmp_load_mem() digitalWrite(_cs_pin, LOW); SPI.transfer(MPUREG_MEM_R_W); for(int k = 0; k < 16; k++){ - uint8_t byteToSend = pgm_read_byte(&(dmpMem[i][j][k])); + uint8_t byteToSend = pgm_read_byte((const prog_char *)&(dmpMem[i][j][k])); SPI.transfer((uint8_t) byteToSend); } digitalWrite(_cs_pin, HIGH); @@ -893,7 +893,7 @@ void AP_InertialSensor_MPU6000::dmp_load_mem() digitalWrite(_cs_pin, LOW); SPI.transfer(MPUREG_MEM_R_W); for(int k = 0; k < 16; k++){ - uint8_t byteToSend = pgm_read_byte(&(dmpMem[7][j][k])); + uint8_t byteToSend = pgm_read_byte((const prog_char *)&(dmpMem[7][j][k])); SPI.transfer((uint8_t) byteToSend); } digitalWrite(_cs_pin, HIGH); @@ -903,7 +903,7 @@ void AP_InertialSensor_MPU6000::dmp_load_mem() digitalWrite(_cs_pin, LOW); SPI.transfer(MPUREG_MEM_R_W); for(int k = 0; k < 9; k++){ - uint8_t byteToSend = pgm_read_byte(&(dmpMem[7][8][k])); + uint8_t byteToSend = pgm_read_byte((const prog_char *)&(dmpMem[7][8][k])); SPI.transfer((uint8_t) byteToSend); } digitalWrite(_cs_pin, HIGH);