Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_HAL_ChibiOS: Scheduler: clean up expected delay functions #28972

Merged
merged 2 commits into from
Dec 31, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 1 addition & 15 deletions libraries/AP_HAL_ChibiOS/Scheduler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -752,7 +752,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_
be used to prevent watchdog reset during expected long delays
A value of zero cancels the previous expected delay
*/
void Scheduler::_expect_delay_ms(uint32_t ms)
void Scheduler::expect_delay_ms(uint32_t ms)
{
if (!in_main_thread()) {
// only for main thread
Expand All @@ -762,8 +762,6 @@ void Scheduler::_expect_delay_ms(uint32_t ms)
// pat once immediately
watchdog_pat();

WITH_SEMAPHORE(expect_delay_sem);

if (ms == 0) {
if (expect_delay_nesting > 0) {
expect_delay_nesting--;
Expand All @@ -789,18 +787,6 @@ void Scheduler::_expect_delay_ms(uint32_t ms)
}
}

/*
this is _expect_delay_ms() with check that we are in the main thread
*/
void Scheduler::expect_delay_ms(uint32_t ms)
{
if (!in_main_thread()) {
// only for main thread
return;
}
_expect_delay_ms(ms);
}

// pat the watchdog
void Scheduler::watchdog_pat(void)
{
Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_HAL_ChibiOS/Scheduler.h
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,6 @@ class ChibiOS::Scheduler : public AP_HAL::Scheduler {
be used to prevent watchdog reset during expected long delays
A value of zero cancels the previous expected delay
*/
void _expect_delay_ms(uint32_t ms);
void expect_delay_ms(uint32_t ms) override;

/*
Expand Down Expand Up @@ -153,7 +152,6 @@ class ChibiOS::Scheduler : public AP_HAL::Scheduler {
uint32_t expect_delay_start;
uint32_t expect_delay_length;
uint32_t expect_delay_nesting;
HAL_Semaphore expect_delay_sem;

AP_HAL::MemberProc _timer_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS];
uint8_t _num_timer_procs;
Expand Down
7 changes: 1 addition & 6 deletions libraries/AP_HAL_ChibiOS/Storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -421,12 +421,7 @@ bool Storage::_flash_erase_sector(uint8_t sector)
// erasing a page can take long enough that USB may not initialise properly if it happens
// while the host is connecting. Only do a flash erase if we have been up for more than 4s
for (uint8_t i=0; i<STORAGE_FLASH_RETRIES; i++) {
/*
a sector erase stops the whole MCU. We need to setup a long
expected delay, and not only when running in the main
thread. We can't use EXPECT_DELAY_MS() as it checks we are
in the main thread
*/
// a sector erase stops the whole MCU so set up a long expected delay
EXPECT_DELAY_MS(1000);
#if AP_FLASH_STORAGE_DOUBLE_PAGE
if (hal.flash->erasepage(_flash_page+sector) && hal.flash->erasepage(_flash_page+sector+1)) {
Expand Down
Loading