Dataflash: Log rate to degrees

This commit is contained in:
Leonard Hall 2016-06-18 20:17:45 +09:30 committed by Randy Mackay
parent 8737f6b62d
commit a5bb3c206e
1 changed files with 6 additions and 6 deletions

View File

@ -1862,14 +1862,14 @@ void DataFlash_Class::Log_Write_Rate(const AP_AHRS &ahrs,
struct log_Rate pkt_rate = {
LOG_PACKET_HEADER_INIT(LOG_RATE_MSG),
time_us : AP_HAL::micros64(),
control_roll : (float)rate_targets.x,
roll : (float)(ahrs.get_gyro().x * AC_ATTITUDE_CONTROL_DEGX100),
control_roll : degrees(rate_targets.x),
roll : degrees(ahrs.get_gyro().x),
roll_out : motors.get_roll(),
control_pitch : (float)rate_targets.y,
pitch : (float)(ahrs.get_gyro().y * AC_ATTITUDE_CONTROL_DEGX100),
control_pitch : degrees(rate_targets.y),
pitch : degrees(ahrs.get_gyro().y),
pitch_out : motors.get_pitch(),
control_yaw : (float)rate_targets.z,
yaw : (float)(ahrs.get_gyro().z * AC_ATTITUDE_CONTROL_DEGX100),
control_yaw : degrees(rate_targets.z),
yaw : degrees(ahrs.get_gyro().z),
yaw_out : motors.get_yaw(),
control_accel : (float)accel_target.z,
accel : (float)(-(ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f),