From 7d8e58ea171283b324e800a7b6b6c19f846add09 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 5 Mar 2024 16:50:57 +1100 Subject: [PATCH] AP_HAL_SITL: move support for SFML joysticks down into AP_RCProtocol --- libraries/AP_HAL_SITL/RCInput.cpp | 27 --------------------------- 1 file changed, 27 deletions(-) diff --git a/libraries/AP_HAL_SITL/RCInput.cpp b/libraries/AP_HAL_SITL/RCInput.cpp index 98e28a6db0..9cffbbed62 100644 --- a/libraries/AP_HAL_SITL/RCInput.cpp +++ b/libraries/AP_HAL_SITL/RCInput.cpp @@ -8,14 +8,6 @@ #include #include -#ifdef SFML_JOYSTICK - #ifdef HAVE_SFML_GRAPHICS_HPP - #include - #elif HAVE_SFML_GRAPHIC_H - #include - #endif -#endif // SFML_JOYSTICK - using namespace HALSITL; extern const AP_HAL::HAL& hal; @@ -50,22 +42,7 @@ uint16_t RCInput::read(uint8_t ch) if (ch >= num_channels()) { return 0; } -#ifdef SFML_JOYSTICK - SITL::SIM *_sitl = AP::sitl(); - if (_sitl) { - const sf::Joystick::Axis axis = sf::Joystick::Axis(_sitl->sfml_joystick_axis[ch].get()); - const unsigned int stickID = _sitl->sfml_joystick_id; - if (sf::Joystick::hasAxis(stickID, axis)) { - return (constrain_float(sf::Joystick::getAxisPosition(stickID, axis) + 100, 0, 200) * 5) + 1000; - } else { - return 0; - } - } else { - return 0; - } -#else return _sitlState->pwm_input[ch]; -#endif } uint8_t RCInput::read(uint16_t* periods, uint8_t len) @@ -86,11 +63,7 @@ uint8_t RCInput::num_channels() } SITL::SIM *_sitl = AP::sitl(); if (_sitl) { -#ifdef SFML_JOYSTICK - return (sf::Joystick::isConnected(_sitl->sfml_joystick_id.get())) ? ARRAY_SIZE(_sitl->sfml_joystick_axis) : 0; -#else return MIN(_sitl->rc_chancount.get(), SITL_RC_INPUT_CHANNELS); -#endif // SFML_JOYSTICK } return SITL_RC_INPUT_CHANNELS; }