DataFlash: use AHRS_View for RATE log msg

This commit is contained in:
Andrew Tridgell 2018-12-21 17:15:40 +11:00
parent 8d572e8565
commit e2907ba88b
2 changed files with 6 additions and 6 deletions

View File

@ -138,7 +138,7 @@ public:
const AP_Mission::Mission_Command &cmd); const AP_Mission::Mission_Command &cmd);
void Log_Write_Origin(uint8_t origin_type, const Location &loc); void Log_Write_Origin(uint8_t origin_type, const Location &loc);
void Log_Write_RPM(const AP_RPM &rpm_sensor); void Log_Write_RPM(const AP_RPM &rpm_sensor);
void Log_Write_Rate(const AP_AHRS &ahrs, void Log_Write_Rate(const AP_AHRS_View *ahrs,
const AP_Motors &motors, const AP_Motors &motors,
const AC_AttitudeControl &attitude_control, const AC_AttitudeControl &attitude_control,
const AC_PosControl &pos_control); const AC_PosControl &pos_control);

View File

@ -1621,7 +1621,7 @@ void DataFlash_Class::Log_Write_RPM(const AP_RPM &rpm_sensor)
} }
// Write a rate packet // Write a rate packet
void DataFlash_Class::Log_Write_Rate(const AP_AHRS &ahrs, void DataFlash_Class::Log_Write_Rate(const AP_AHRS_View *ahrs,
const AP_Motors &motors, const AP_Motors &motors,
const AC_AttitudeControl &attitude_control, const AC_AttitudeControl &attitude_control,
const AC_PosControl &pos_control) const AC_PosControl &pos_control)
@ -1632,16 +1632,16 @@ void DataFlash_Class::Log_Write_Rate(const AP_AHRS &ahrs,
LOG_PACKET_HEADER_INIT(LOG_RATE_MSG), LOG_PACKET_HEADER_INIT(LOG_RATE_MSG),
time_us : AP_HAL::micros64(), time_us : AP_HAL::micros64(),
control_roll : degrees(rate_targets.x), control_roll : degrees(rate_targets.x),
roll : degrees(ahrs.get_gyro().x), roll : degrees(ahrs->get_gyro().x),
roll_out : motors.get_roll(), roll_out : motors.get_roll(),
control_pitch : degrees(rate_targets.y), control_pitch : degrees(rate_targets.y),
pitch : degrees(ahrs.get_gyro().y), pitch : degrees(ahrs->get_gyro().y),
pitch_out : motors.get_pitch(), pitch_out : motors.get_pitch(),
control_yaw : degrees(rate_targets.z), control_yaw : degrees(rate_targets.z),
yaw : degrees(ahrs.get_gyro().z), yaw : degrees(ahrs->get_gyro().z),
yaw_out : motors.get_yaw(), yaw_out : motors.get_yaw(),
control_accel : (float)accel_target.z, control_accel : (float)accel_target.z,
accel : (float)(-(ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f), accel : (float)(-(ahrs->get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f),
accel_out : motors.get_throttle() accel_out : motors.get_throttle()
}; };
WriteBlock(&pkt_rate, sizeof(pkt_rate)); WriteBlock(&pkt_rate, sizeof(pkt_rate));