AP_InertialSensor_MPU6000: another attempt at fixing the SITL build

This commit is contained in:
rmackay9 2012-07-28 17:19:19 +09:00
parent 7683e9d870
commit 5077674043
1 changed files with 3 additions and 3 deletions

View File

@ -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);