Skip to content

Commit

Permalink
Copter: reset target modifiers at loop rate
Browse files Browse the repository at this point in the history
don't compile in support on tradheli
  • Loading branch information
andyp1per committed Aug 1, 2024
1 parent a329952 commit 27113dd
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 @@ -5,7 +5,7 @@
* Attitude Rate controllers and timing
****************************************************************/

#if AP_INERTIALSENSOR_RATE_LOOP_WINDOW_ENABLED
#if AP_INERTIALSENSOR_RATE_LOOP_WINDOW_ENABLED && FRAME_CONFIG != HELI_FRAME
#pragma GCC push_options
#pragma GCC optimize("O2")

Expand Down Expand Up @@ -339,6 +339,8 @@ void Copter::run_rate_controller_main()
motors->set_dt(last_loop_time_s);
// only run the rate controller if we are not using the rate thread
attitude_control->rate_controller_run();
} else {
attitude_control->rate_controller_target_reset();
}
}

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -718,7 +718,7 @@ void Copter::one_hz_loop()
custom_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
#endif

#if AP_INERTIALSENSOR_RATE_LOOP_WINDOW_ENABLED
#if AP_INERTIALSENSOR_RATE_LOOP_WINDOW_ENABLED && FRAME_CONFIG != HELI_FRAME
// see if we should have a separate rate thread
if (!started_rate_thread && get_fast_rate_type() != FastRateType::FAST_RATE_DISABLED) {
if (hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&Copter::rate_controller_thread, void),
Expand Down

0 comments on commit 27113dd

Please sign in to comment.