mirror of https://github.com/ArduPilot/ardupilot
Fixed bad output of GPS ground course.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2318 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
bb059aa2d9
commit
799e6a0c15
|
@ -396,18 +396,6 @@ void Log_Read_Nav_Tuning()
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Write a mode packet. Total length : 5 bytes
|
|
||||||
void Log_Write_Mode(byte mode)
|
|
||||||
{
|
|
||||||
DataFlash.WriteByte(HEAD_BYTE1);
|
|
||||||
DataFlash.WriteByte(HEAD_BYTE2);
|
|
||||||
DataFlash.WriteByte(LOG_MODE_MSG);
|
|
||||||
DataFlash.WriteByte(mode);
|
|
||||||
DataFlash.WriteByte(END_BYTE);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Write an GPS packet. Total length : 30 bytes
|
// Write an GPS packet. Total length : 30 bytes
|
||||||
void Log_Write_GPS()
|
void Log_Write_GPS()
|
||||||
{
|
{
|
||||||
|
@ -424,8 +412,8 @@ void Log_Write_GPS()
|
||||||
DataFlash.WriteLong(g_gps->altitude); // 6
|
DataFlash.WriteLong(g_gps->altitude); // 6
|
||||||
DataFlash.WriteLong(current_loc.alt); // 7
|
DataFlash.WriteLong(current_loc.alt); // 7
|
||||||
|
|
||||||
DataFlash.WriteInt(g_gps->ground_speed/100); // 8
|
DataFlash.WriteInt(g_gps->ground_speed); // 8
|
||||||
DataFlash.WriteInt((int)(g_gps->ground_course/100)); // 9
|
DataFlash.WriteInt((uint16_t)g_gps->ground_course); // 9
|
||||||
|
|
||||||
DataFlash.WriteByte(END_BYTE);
|
DataFlash.WriteByte(END_BYTE);
|
||||||
}
|
}
|
||||||
|
@ -447,7 +435,7 @@ void Log_Read_GPS()
|
||||||
(float)DataFlash.ReadLong() / 100.0, // 7 sensor alt
|
(float)DataFlash.ReadLong() / 100.0, // 7 sensor alt
|
||||||
|
|
||||||
DataFlash.ReadInt(), // 8 ground speed
|
DataFlash.ReadInt(), // 8 ground speed
|
||||||
DataFlash.ReadInt()); // 9 ground course
|
(uint16_t)DataFlash.ReadInt()); // 9 ground course
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -586,6 +574,7 @@ void Log_Write_Performance()
|
||||||
DataFlash.WriteByte( dcm.renorm_blowup_count);
|
DataFlash.WriteByte( dcm.renorm_blowup_count);
|
||||||
DataFlash.WriteByte( gps_fix_count);
|
DataFlash.WriteByte( gps_fix_count);
|
||||||
DataFlash.WriteInt( (int)(dcm.get_health() * 1000));
|
DataFlash.WriteInt( (int)(dcm.get_health() * 1000));
|
||||||
|
//PM, 20005, 3742, 10,0,0,0,0,89,1000,
|
||||||
|
|
||||||
DataFlash.WriteByte(END_BYTE);
|
DataFlash.WriteByte(END_BYTE);
|
||||||
}
|
}
|
||||||
|
@ -600,6 +589,7 @@ void Log_Read_Performance()
|
||||||
pm_time = DataFlash.ReadLong();
|
pm_time = DataFlash.ReadLong();
|
||||||
Serial.print(pm_time);
|
Serial.print(pm_time);
|
||||||
Serial.print(comma);
|
Serial.print(comma);
|
||||||
|
|
||||||
for (int y = 1; y < 9; y++) {
|
for (int y = 1; y < 9; y++) {
|
||||||
if(y < 3 || y > 7){
|
if(y < 3 || y > 7){
|
||||||
logvar = DataFlash.ReadInt();
|
logvar = DataFlash.ReadInt();
|
||||||
|
@ -676,6 +666,17 @@ void Log_Read_Attitude()
|
||||||
(uint16_t)DataFlash.ReadInt());
|
(uint16_t)DataFlash.ReadInt());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Write a mode packet. Total length : 5 bytes
|
||||||
|
void Log_Write_Mode(byte mode)
|
||||||
|
{
|
||||||
|
DataFlash.WriteByte(HEAD_BYTE1);
|
||||||
|
DataFlash.WriteByte(HEAD_BYTE2);
|
||||||
|
DataFlash.WriteByte(LOG_MODE_MSG);
|
||||||
|
DataFlash.WriteByte(mode);
|
||||||
|
DataFlash.WriteByte(END_BYTE);
|
||||||
|
}
|
||||||
|
|
||||||
// Read a mode packet
|
// Read a mode packet
|
||||||
void Log_Read_Mode()
|
void Log_Read_Mode()
|
||||||
{
|
{
|
||||||
|
|
Loading…
Reference in New Issue