mirror of https://github.com/ArduPilot/ardupilot
Copter: fast attitude logging should be at loop rate
This commit is contained in:
parent
a34ff49bac
commit
1c8d206dfb
|
@ -182,7 +182,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||
SCHED_TASK(check_dynamic_flight, 50, 75, 72),
|
||||
#endif
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
SCHED_TASK(fourhundred_hz_logging,400, 50, 75),
|
||||
SCHED_TASK(loop_rate_logging, LOOP_RATE, 50, 75),
|
||||
#endif
|
||||
SCHED_TASK_CLASS(AP_Notify, &copter.notify, update, 50, 90, 78),
|
||||
SCHED_TASK(one_hz_loop, 1, 100, 81),
|
||||
|
@ -485,8 +485,8 @@ void Copter::update_batt_compass(void)
|
|||
}
|
||||
|
||||
// Full rate logging of attitude, rate and pid loops
|
||||
// should be run at 400hz
|
||||
void Copter::fourhundred_hz_logging()
|
||||
// should be run at loop rate
|
||||
void Copter::loop_rate_logging()
|
||||
{
|
||||
if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
|
||||
Log_Write_Attitude();
|
||||
|
|
|
@ -663,7 +663,7 @@ private:
|
|||
void rc_loop();
|
||||
void throttle_loop();
|
||||
void update_batt_compass(void);
|
||||
void fourhundred_hz_logging();
|
||||
void loop_rate_logging();
|
||||
void ten_hz_logging_loop();
|
||||
void twentyfive_hz_logging();
|
||||
void three_hz_loop();
|
||||
|
|
Loading…
Reference in New Issue