Skip to content

Commit

Permalink
Copter: force trigger_groups() and reduce attitude thread priority
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Jun 7, 2024
1 parent ed6bdd2 commit 2370654
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 2 deletions.
4 changes: 3 additions & 1 deletion ArduCopter/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,15 +69,17 @@ void Copter::rate_controller_thread()
attitude_control->set_notch_sample_rate(loop_rate_hz);
motors->set_dt(1.0/loop_rate_hz);
ins.set_rate_decimation(0);
hal.rcout->force_trigger_groups(false);
was_using_rate_thread = false;
}
hal.scheduler->delay_microseconds(500);
last_run_us = AP_HAL::micros();
continue;
}

// set up rate thread requirements
using_rate_thread = true;

hal.rcout->force_trigger_groups(true);
ins.set_rate_decimation(rate_decimation);

// wait for an IMU sample
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -700,7 +700,7 @@ void Copter::one_hz_loop()

if (hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&Copter::rate_controller_thread, void),
"attitude",
2048, AP_HAL::Scheduler::PRIORITY_BOOST, 1)) {
1024, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) {
started_rate_thread = true;
}
}
Expand Down

0 comments on commit 2370654

Please sign in to comment.