mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed attitude logging with fast logging off
This commit is contained in:
parent
9c90709872
commit
eab42c5740
|
@ -74,7 +74,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
|||
SCHED_TASK(update_trigger, 50, 100),
|
||||
SCHED_TASK(log_perf_info, 0.2, 100),
|
||||
SCHED_TASK(compass_save, 0.1, 200),
|
||||
SCHED_TASK(Log_Write_Attitude, 25, 300),
|
||||
SCHED_TASK(Log_Write_Fast, 25, 300),
|
||||
SCHED_TASK(update_logging1, 10, 300),
|
||||
SCHED_TASK(update_logging2, 10, 300),
|
||||
SCHED_TASK(parachute_check, 10, 200),
|
||||
|
|
|
@ -159,9 +159,6 @@ void Plane::do_erase_logs(void)
|
|||
// Write an attitude packet
|
||||
void Plane::Log_Write_Attitude(void)
|
||||
{
|
||||
if (!should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||
return;
|
||||
}
|
||||
Vector3f targets; // Package up the targets into a vector for commonality with Copter usage of Log_Wrote_Attitude
|
||||
targets.x = nav_roll_cd;
|
||||
targets.y = nav_pitch_cd;
|
||||
|
@ -194,6 +191,14 @@ void Plane::Log_Write_Attitude(void)
|
|||
DataFlash.Log_Write_POS(ahrs);
|
||||
}
|
||||
|
||||
// do logging at loop rate
|
||||
void Plane::Log_Write_Fast(void)
|
||||
{
|
||||
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||
Log_Write_Attitude();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
struct PACKED log_Performance {
|
||||
LOG_PACKET_HEADER;
|
||||
|
|
|
@ -779,6 +779,7 @@ private:
|
|||
void gcs_retry_deferred(void);
|
||||
|
||||
void do_erase_logs(void);
|
||||
void Log_Write_Fast(void);
|
||||
void Log_Write_Attitude(void);
|
||||
void Log_Write_Performance();
|
||||
void Log_Write_Startup(uint8_t type);
|
||||
|
|
Loading…
Reference in New Issue