-
Notifications
You must be signed in to change notification settings - Fork 293
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Use the SDL2 Game Controller API (#258)
* Use the SDL2 Game Controller API Signed-off-by: Rod Taylor <[email protected]> * CMakeLists.txt for game_controller. Signed-off-by: Rod Taylor <[email protected]> * Add xbox wirelss controller udev rule file. Signed-off-by: Rod <[email protected]> --------- Signed-off-by: Rod Taylor <[email protected]> Signed-off-by: Rod <[email protected]>
- Loading branch information
1 parent
e3c3388
commit b0bc9d7
Showing
7 changed files
with
622 additions
and
19 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,94 @@ | ||
/* | ||
* Copyright (c) 2020, Open Source Robotics Foundation. | ||
* Copyright (c) 2023, CSIRO Data61. | ||
* All rights reserved. | ||
* | ||
* Redistribution and use in source and binary forms, with or without | ||
* modification, are permitted provided that the following conditions are met: | ||
* | ||
* * Redistributions of source code must retain the above copyright | ||
* notice, this list of conditions and the following disclaimer. | ||
* * Redistributions in binary form must reproduce the above copyright | ||
* notice, this list of conditions and the following disclaimer in the | ||
* documentation and/or other materials provided with the distribution. | ||
* * Neither the name of the copyright holder nor the names of its | ||
* contributors may be used to endorse or promote products derived from | ||
* this software without specific prior written permission. | ||
* | ||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" | ||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE | ||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE | ||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE | ||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR | ||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF | ||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS | ||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN | ||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) | ||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
* POSSIBILITY OF SUCH DAMAGE. | ||
*/ | ||
|
||
#ifndef JOY__GAME_CONTROLLER_HPP_ | ||
#define JOY__GAME_CONTROLLER_HPP_ | ||
|
||
#include <SDL.h> | ||
|
||
#include <future> | ||
#include <memory> | ||
#include <string> | ||
#include <thread> | ||
|
||
#include <rclcpp/rclcpp.hpp> | ||
#include <sensor_msgs/msg/joy.hpp> | ||
#include <sensor_msgs/msg/joy_feedback.hpp> | ||
|
||
namespace joy | ||
{ | ||
|
||
class GameController final : public rclcpp::Node | ||
{ | ||
public: | ||
explicit GameController(const rclcpp::NodeOptions & options); | ||
GameController(GameController && c) = delete; | ||
GameController & operator=(GameController && c) = delete; | ||
GameController(const GameController & c) = delete; | ||
GameController & operator=(const GameController & c) = delete; | ||
|
||
~GameController() override; | ||
|
||
private: | ||
void eventThread(); | ||
bool handleControllerAxis(const SDL_ControllerAxisEvent & e); | ||
bool handleControllerButtonDown(const SDL_ControllerButtonEvent & e); | ||
bool handleControllerButtonUp(const SDL_ControllerButtonEvent & e); | ||
void handleControllerDeviceAdded(const SDL_ControllerDeviceEvent & e); | ||
void handleControllerDeviceRemoved(const SDL_ControllerDeviceEvent & e); | ||
float convertRawAxisValueToROS(int16_t val); | ||
void feedbackCb(const std::shared_ptr<sensor_msgs::msg::JoyFeedback> msg); | ||
|
||
int dev_id_{0}; | ||
|
||
SDL_GameController * game_controller_{nullptr}; | ||
SDL_JoystickID joystick_instance_id_{0}; | ||
double scaled_deadzone_{0.0}; | ||
double unscaled_deadzone_{0.0}; | ||
double scale_{0.0}; | ||
double autorepeat_rate_{0.0}; | ||
int autorepeat_interval_ms_{0}; | ||
bool sticky_buttons_{false}; | ||
bool publish_soon_{false}; | ||
rclcpp::Time publish_soon_time_; | ||
int coalesce_interval_ms_{0}; | ||
std::string dev_name_; | ||
std::thread event_thread_; | ||
std::shared_future<void> future_; | ||
std::promise<void> exit_signal_; | ||
rclcpp::Publisher<sensor_msgs::msg::Joy>::SharedPtr pub_; | ||
rclcpp::Subscription<sensor_msgs::msg::JoyFeedback>::SharedPtr feedback_sub_; | ||
|
||
sensor_msgs::msg::Joy joy_msg_; | ||
}; | ||
|
||
} // namespace joy | ||
|
||
#endif // JOY__GAME_CONTROLLER_HPP_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -4,12 +4,9 @@ | |
<name>joy</name> | ||
<version>3.1.0</version> | ||
|
||
<description> | ||
The joy package contains joy_node, a node that interfaces a | ||
generic joystick to ROS 2. This node publishes a "Joy" | ||
message, which contains the current state of each one of the | ||
joystick's buttons and axes. | ||
</description> | ||
<description> The joy package contains joy_node, a node that interfaces a generic joystick to ROS | ||
2. This node publishes a "Joy" message, which contains the current state of each one of the | ||
joystick's buttons and axes. </description> | ||
|
||
<maintainer email="[email protected]">Chris Lalancette</maintainer> | ||
<license>BSD</license> | ||
|
@@ -21,6 +18,7 @@ | |
<author>Kevin Watts</author> | ||
<author>Blaise Gassend</author> | ||
<author>Jonathan Bohren</author> | ||
<author>Rod Taylor</author> | ||
|
||
<buildtool_depend>ament_cmake_ros</buildtool_depend> | ||
|
||
|
Oops, something went wrong.