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

HAL_ChibiOS: switch to minimum scheduling delta of 10us #18416

Merged
merged 1 commit into from
Aug 23, 2021
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
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/Scheduler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ void Scheduler::delay_microseconds(uint16_t usec)
// calling with ticks == 0 causes a hard fault on ChibiOS
ticks = 1;
}
chThdSleep(ticks); //Suspends Thread for desired microseconds
chThdSleep(MAX(ticks,CH_CFG_ST_TIMEDELTA)); //Suspends Thread for desired microseconds
tridge marked this conversation as resolved.
Show resolved Hide resolved
}

/*
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ extern "C" {
* this value.
*/
#ifndef CH_CFG_ST_TIMEDELTA
#define CH_CFG_ST_TIMEDELTA 2
#define CH_CFG_ST_TIMEDELTA 10
#endif

/*
Expand Down