AP_Vehicle: move INS notch filter logging into INS

This commit is contained in:
Peter Barker 2021-12-31 11:32:17 +11:00 committed by Peter Barker
parent 6084682634
commit db6bb8d616
2 changed files with 0 additions and 28 deletions

View File

@ -364,32 +364,6 @@ bool AP_Vehicle::is_crashed() const
return AP::arming().last_disarm_method() == AP_Arming::Method::CRASH;
}
// @LoggerMessage: FTN
// @Description: Filter Tuning Messages
// @Field: TimeUS: microseconds since system startup
// @Field: NDn: number of active dynamic harmonic notches
// @Field: NF1: dynamic harmonic notch centre frequency for motor 1
// @Field: NF2: dynamic harmonic notch centre frequency for motor 2
// @Field: NF3: dynamic harmonic notch centre frequency for motor 3
// @Field: NF4: dynamic harmonic notch centre frequency for motor 4
// @Field: NF5: dynamic harmonic notch centre frequency for motor 5
// @Field: NF6: dynamic harmonic notch centre frequency for motor 6
// @Field: NF7: dynamic harmonic notch centre frequency for motor 7
// @Field: NF8: dynamic harmonic notch centre frequency for motor 8
// @Field: NF9: dynamic harmonic notch centre frequency for motor 9
// @Field: NF10: dynamic harmonic notch centre frequency for motor 10
// @Field: NF11: dynamic harmonic notch centre frequency for motor 11
// @Field: NF12: dynamic harmonic notch centre frequency for motor 12
void AP_Vehicle::write_notch_log_messages() const
{
const float* notches = ins.get_gyro_dynamic_notch_center_frequencies_hz();
AP::logger().Write(
"FTN", "TimeUS,NDn,NF1,NF2,NF3,NF4,NF5,NF6,NF7,NF8,NF9,NF10,NF11,NF12", "s-zzzzzzzzzzzz", "F-------------", "QBffffffffffff", AP_HAL::micros64(), ins.get_num_gyro_dynamic_notch_center_frequencies(),
notches[0], notches[1], notches[2], notches[3],
notches[4], notches[5], notches[6], notches[7],
notches[8], notches[9], notches[10], notches[11]);
}
// run notch update at either loop rate or 200Hz
void AP_Vehicle::update_dynamic_notch_at_specified_rate()
{

View File

@ -239,8 +239,6 @@ public:
#endif // AP_SCRIPTING_ENABLED
// write out harmonic notch log messages
void write_notch_log_messages() const;
// update the harmonic notch
virtual void update_dynamic_notch() {};