From 8d6d5c6b49b6fc2d2ef9e57bfc1f5c81b3a849e7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 17 Dec 2020 13:19:19 +1100 Subject: [PATCH] SITL: removed flightaxis threading --- libraries/SITL/SIM_FlightAxis.cpp | 46 ++----------------------------- libraries/SITL/SIM_FlightAxis.h | 4 --- 2 files changed, 2 insertions(+), 48 deletions(-) diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index 90837a1549..4b31821d55 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -28,7 +28,6 @@ #include #include -#include "pthread.h" extern const AP_HAL::HAL& hal; @@ -106,47 +105,8 @@ FlightAxis::FlightAxis(const char *frame_str) : } } } - - int ret = pthread_create(&thread, NULL, update_thread, this); - if (ret != 0) { - AP_HAL::panic("SIM_FlightAxis: failed to create thread"); - } } -/* - update thread trampoline - */ -void *FlightAxis::update_thread(void *arg) -{ - FlightAxis *flightaxis = (FlightAxis *)arg; - -#if defined(__CYGWIN__) || defined(__CYGWIN64__) - //Cygwin doesn't support pthread_setname_np -#elif defined(__APPLE__) && defined(__MACH__) - pthread_setname_np("ardupilot-flightaxis"); -#else - pthread_setname_np(pthread_self(), "ardupilot-flightaxis"); -#endif - - flightaxis->update_loop(); - return nullptr; -} - -/* - main update loop - */ -void FlightAxis::update_loop(void) -{ - while (true) { - struct sitl_input new_input; - { - WITH_SEMAPHORE(mutex); - new_input = last_input; - } - exchange_data(new_input); - } -} - /* extremely primitive SOAP parser that assumes the format used by FlightAxis */ @@ -349,7 +309,6 @@ void FlightAxis::exchange_data(const struct sitl_input &input) scaled_servos[11]); if (reply) { - WITH_SEMAPHORE(mutex); double lastt_s = state.m_currentPhysicsTime_SEC; parse_reply(reply); double dt = state.m_currentPhysicsTime_SEC - lastt_s; @@ -370,10 +329,9 @@ void FlightAxis::exchange_data(const struct sitl_input &input) */ void FlightAxis::update(const struct sitl_input &input) { - WITH_SEMAPHORE(mutex); - last_input = input; - + exchange_data(input); + double dt_seconds = state.m_currentPhysicsTime_SEC - last_time_s; if (dt_seconds < 0) { // cope with restarting RealFlight while connected diff --git a/libraries/SITL/SIM_FlightAxis.h b/libraries/SITL/SIM_FlightAxis.h index 960012dabb..68bfdf7e09 100644 --- a/libraries/SITL/SIM_FlightAxis.h +++ b/libraries/SITL/SIM_FlightAxis.h @@ -160,7 +160,6 @@ private: void exchange_data(const struct sitl_input &input); void parse_reply(const char *reply); - static void *update_thread(void *arg); void update_loop(void); void report_FPS(void); @@ -183,9 +182,6 @@ private: const char *controller_ip = "127.0.0.1"; uint16_t controller_port = 18083; - - pthread_t thread; - HAL_Semaphore mutex; };