HAL_SITL: only do the cygwin speedup hack for scripting while armed

this stops us chewing lots of CPU while disarmed, and also stops the
logging thread from chewing a lot of CPU
This commit is contained in:
Andrew Tridgell 2022-11-09 14:26:34 +11:00
parent 5fc018fff4
commit 1c554ccc24
3 changed files with 30 additions and 8 deletions

View File

@ -186,14 +186,19 @@ void SITL_State::wait_clock(uint64_t wait_time_usec)
_fdm_input_step();
} else {
#ifdef CYGWIN_BUILD
if (speedup > 2) {
// this effectively does a yield of the CPU. The
// granularity of sleeps on cygwin is very high, so
// this is needed for good thread performance. We
// don't do this at low speedups as it causes the cpu
// to run hot
usleep(0);
continue;
if (speedup > 2 && hal.util->get_soft_armed()) {
const char *current_thread = Scheduler::from(hal.scheduler)->get_current_thread_name();
if (current_thread && strcmp(current_thread, "Scripting") == 0) {
// this effectively does a yield of the CPU. The
// granularity of sleeps on cygwin is very high,
// so this is needed for good thread performance
// in scripting. We don't do this at low speedups
// as it causes the cpu to run hot
// We also don't do it while disarmed, as lua performance is less
// critical while disarmed
usleep(0);
continue;
}
}
#endif
usleep(1000);

View File

@ -308,6 +308,7 @@ void Scheduler::stop_clock(uint64_t time_usec)
void *Scheduler::thread_create_trampoline(void *ctx)
{
struct thread_attr *a = (struct thread_attr *)ctx;
a->thread = pthread_self();
a->f[0]();
WITH_SEMAPHORE(_thread_sem);
@ -408,3 +409,15 @@ void Scheduler::check_thread_stacks(void)
}
}
}
// get the name of the current thread, or nullptr if not known
const char *Scheduler::get_current_thread_name(void) const
{
const pthread_t self = pthread_self();
for (struct thread_attr *a=threads; a; a=a->next) {
if (a->thread == self) {
return a->name;
}
}
return nullptr;
}

View File

@ -67,6 +67,9 @@ public:
// a couple of helper functions to cope with SITL's time stepping
bool semaphore_wait_hack_required() const;
// get the name of the current thread, or nullptr if not known
const char *get_current_thread_name(void) const;
private:
SITL_State *_sitlState;
uint8_t _nested_atomic_ctr;
@ -105,6 +108,7 @@ private:
void *stack;
const uint8_t *stack_min;
const char *name;
pthread_t thread;
};
static struct thread_attr *threads;
static const uint8_t stackfill = 0xEB;