Skip to content

Commit

Permalink
DataFlash: fix bug in ekf gyro bias logging
Browse files Browse the repository at this point in the history
  • Loading branch information
jschall authored and Andrew Tridgell committed Oct 30, 2014
1 parent bb6d8fd commit ac2e5f6
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions libraries/DataFlash/LogFile.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -900,18 +900,18 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
struct log_EKF1 pkt = {
LOG_PACKET_HEADER_INIT(LOG_EKF1_MSG),
time_ms : hal.scheduler->millis(),
roll : (int16_t)(100*degrees(euler.x)), // roll angle (centi-deg)
pitch : (int16_t)(100*degrees(euler.y)), // pitch angle (centi-deg)
yaw : (uint16_t)wrap_360_cd(100*degrees(euler.z)), // yaw angle (centi-deg)
roll : (int16_t)(100*degrees(euler.x)), // roll angle (centi-deg, displayed as deg due to format string)
pitch : (int16_t)(100*degrees(euler.y)), // pitch angle (centi-deg, displayed as deg due to format string)
yaw : (uint16_t)wrap_360_cd(100*degrees(euler.z)), // yaw angle (centi-deg, displayed as deg due to format string)
velN : (float)(velNED.x), // velocity North (m/s)
velE : (float)(velNED.y), // velocity East (m/s)
velD : (float)(velNED.z), // velocity Down (m/s)
posN : (float)(posNED.x), // metres North
posE : (float)(posNED.y), // metres East
posD : (float)(posNED.z), // metres Down
gyrX : (int8_t)(60*degrees(gyroBias.x)), // deg/min
gyrY : (int8_t)(60*degrees(gyroBias.y)), // deg/min
gyrZ : (int8_t)(60*degrees(gyroBias.z)) // deg/min
gyrX : (int16_t)(100*degrees(gyroBias.x)), // cd/sec, displayed as deg/sec due to format string
gyrY : (int16_t)(100*degrees(gyroBias.y)), // cd/sec, displayed as deg/sec due to format string
gyrZ : (int16_t)(100*degrees(gyroBias.z)) // cd/sec, displayed as deg/sec due to format string
};
WriteBlock(&pkt, sizeof(pkt));

Expand Down

0 comments on commit ac2e5f6

Please sign in to comment.