Skip to content

Commit

Permalink
Copter: allocation failure on rate thread start
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per authored and tridge committed Dec 3, 2024
1 parent 88f6125 commit 3ed6ada
Showing 1 changed file with 2 additions and 0 deletions.
2 changes: 2 additions & 0 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -817,6 +817,8 @@ void Copter::one_hz_loop()
"rate",
1536, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) {
started_rate_thread = true;
} else {
AP_BoardConfig::allocation_error("rate thread");
}
}
#endif
Expand Down

0 comments on commit 3ed6ada

Please sign in to comment.