mirror of https://github.com/ArduPilot/ardupilot
ACM: Fixed comment
This commit is contained in:
parent
1c0b28c956
commit
6201bdb8a7
|
@ -250,8 +250,8 @@ static void Log_Read_GPS()
|
||||||
int8_t temp2 = DataFlash.ReadByte(); // 2 sats
|
int8_t temp2 = DataFlash.ReadByte(); // 2 sats
|
||||||
int32_t temp3 = DataFlash.ReadLong(); // 3 lat
|
int32_t temp3 = DataFlash.ReadLong(); // 3 lat
|
||||||
int32_t temp4 = DataFlash.ReadLong(); // 4 lon
|
int32_t temp4 = DataFlash.ReadLong(); // 4 lon
|
||||||
float temp5 = DataFlash.ReadLong() / 100.0; // 5 gps alt
|
float temp5 = DataFlash.ReadLong() / 100.0; // 5 sensor alt
|
||||||
float temp6 = DataFlash.ReadLong() / 100.0; // 6 sensor alt
|
float temp6 = DataFlash.ReadLong() / 100.0; // 6 gps alt
|
||||||
int16_t temp7 = DataFlash.ReadInt(); // 7 ground speed
|
int16_t temp7 = DataFlash.ReadInt(); // 7 ground speed
|
||||||
int32_t temp8 = DataFlash.ReadLong();// 8 ground course
|
int32_t temp8 = DataFlash.ReadLong();// 8 ground course
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue