mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: use WITH_SEMAPHORE()
and removed usage of hal.util->new_semaphore()
This commit is contained in:
parent
a1f1e7e435
commit
17049ff5f5
|
@ -103,21 +103,20 @@ void AP_OSD_SITL::write(uint8_t x, uint8_t y, const char* text)
|
|||
if (y >= video_lines || text == nullptr) {
|
||||
return;
|
||||
}
|
||||
mutex->take_blocking();
|
||||
WITH_SEMAPHORE(mutex);
|
||||
|
||||
while ((x < video_cols) && (*text != 0)) {
|
||||
buffer[y][x] = *text;
|
||||
++text;
|
||||
++x;
|
||||
}
|
||||
mutex->give();
|
||||
}
|
||||
|
||||
void AP_OSD_SITL::clear(void)
|
||||
{
|
||||
AP_OSD_Backend::clear();
|
||||
mutex->take_blocking();
|
||||
WITH_SEMAPHORE(mutex);
|
||||
memset(buffer, 0, sizeof(buffer));
|
||||
mutex->give();
|
||||
}
|
||||
|
||||
void AP_OSD_SITL::flush(void)
|
||||
|
@ -150,9 +149,10 @@ void AP_OSD_SITL::update_thread(void)
|
|||
last_counter = counter;
|
||||
|
||||
uint8_t buffer2[video_lines][video_cols];
|
||||
mutex->take_blocking();
|
||||
memcpy(buffer2, buffer, sizeof(buffer2));
|
||||
mutex->give();
|
||||
{
|
||||
WITH_SEMAPHORE(mutex);
|
||||
memcpy(buffer2, buffer, sizeof(buffer2));
|
||||
}
|
||||
w->clear();
|
||||
|
||||
for (uint8_t y=0; y<video_lines; y++) {
|
||||
|
@ -186,7 +186,6 @@ void *AP_OSD_SITL::update_thread_start(void *obj)
|
|||
// initialise backend
|
||||
bool AP_OSD_SITL::init(void)
|
||||
{
|
||||
mutex = hal.util->new_semaphore();
|
||||
pthread_create(&thread, NULL, update_thread_start, this);
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -68,7 +68,7 @@ private:
|
|||
void load_font();
|
||||
|
||||
pthread_t thread;
|
||||
AP_HAL::Semaphore *mutex;
|
||||
HAL_Semaphore mutex;
|
||||
uint32_t counter;
|
||||
uint32_t last_counter;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue