Skip to content

Commit b0bc9d7

Browse files
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]>
1 parent e3c3388 commit b0bc9d7

File tree

7 files changed

+622
-19
lines changed

7 files changed

+622
-19
lines changed

joy/CMakeLists.txt

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,27 @@ rclcpp_components_register_node(joy
3838
PLUGIN "joy::Joy"
3939
EXECUTABLE joy_node)
4040

41+
add_library(game_controller SHARED src/game_controller.cpp)
42+
target_include_directories(game_controller PUBLIC
43+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
44+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
45+
ament_target_dependencies(game_controller
46+
rclcpp
47+
rclcpp_components
48+
sensor_msgs)
49+
target_link_libraries(game_controller
50+
SDL2::SDL2)
51+
52+
install(TARGETS game_controller EXPORT export_game_controller
53+
LIBRARY DESTINATION lib
54+
ARCHIVE DESTINATION lib
55+
RUNTIME DESTINATION bin
56+
)
57+
58+
rclcpp_components_register_node(game_controller
59+
PLUGIN "joy::GameController"
60+
EXECUTABLE game_controller_node)
61+
4162
add_executable(joy_enumerate_devices
4263
src/joy_enumerate_devices.cpp)
4364
target_link_libraries(joy_enumerate_devices
@@ -52,6 +73,7 @@ install(DIRECTORY config launch
5273
DESTINATION share/${PROJECT_NAME})
5374

5475
ament_export_targets(export_joy)
76+
ament_export_targets(export_game_controller)
5577
ament_export_dependencies(
5678
"rclcpp"
5779
"sensor_msgs"

joy/README.md

Lines changed: 44 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,49 @@
1-
# ROS 2 Driver for Generic Joysticks
1+
# ROS 2 Driver for Generic Joysticks and Game Controllers
22

3-
The joy package contains joy_node, a node that interfaces a generic joystick to ROS 2. This node publishes a "sensor_msgs/msg/Joy" message, which contains the current state of each one of the joystick's buttons and axes.
3+
The joy package contains joy_node, and game_controller node which interface generic joysticks and game controllers to ROS 2. These nodes publish "sensor_msgs/msg/Joy" messages, which contain the state of the devices button and axes. Examples of game controllers are ones that come with recently released game consoles and their after market clones.
4+
5+
The game_controller_node uses SDL2's built device mapping database to give buttons and axes a consistent order in the "sensor_msgs/msg/Joy". Custom mappings can also be supplied using SDL's SDL_GAMECONTROLLERCONFIG environment variable. A third party tool can be used to create the mapping string. The joy_node supports both joysticks and game controllers but the order that buttons and axes appear with the message will dependend on the manufacturer of the device.
6+
7+
For game_controller_node the following tables detail the indexes of buttons and axes.
8+
9+
| Index | Button |
10+
| - | - |
11+
| 0 | A (CROSS) |
12+
| 1 | B (CIRCLE) |
13+
| 2 | X (SQUARE) |
14+
| 3 | Y (TRIANGLE) |
15+
| 4 | BACK (SELECT) |
16+
| 5 | GUIDE (Middle/Manufacturer Button) |
17+
| 6 | START |
18+
| 7 | LEFTSTICK |
19+
| 8 | RIGHTSTICK |
20+
| 9 | LEFTSHOULDER |
21+
| 10 | RIGHTSHOULDER |
22+
| 11 | DPAD_UP |
23+
| 12 | DPAD_DOWN |
24+
| 13 | DPAD_LEFT |
25+
| 14 | DPAD_RIGHT |
26+
| 15 | MISC1 (Depends on the controller manufacturer, but is usually at a similar location on the controller as back/start) |
27+
| 16 | PADDLE1 (Upper left, facing the back of the controller if present) |
28+
| 17 | PADDLE2 (Upper right, facing the back of the controller if present) |
29+
| 18 | PADDLE3 (Lower left, facing the back of the controller if present) |
30+
| 19 | PADDLE4 (Lower right, facing the back of the controller if present) |
31+
| 20 | TOUCHPAD (If present. Button status only) |
32+
33+
| Index | Axis |
34+
| - | - |
35+
| 0 | LEFTX |
36+
| 1 | LEFTY |
37+
| 2 | RIGHTX |
38+
| 3 | RIGHTY |
39+
| 4 | TRIGGERLEFT |
40+
| 5 | TRIGGERRIGHT |
41+
42+
For joy_node run `ros2 run joy joy_node` in one terminal and `ros2 topic echo /joy` in another. Pressing buttons and moving sticks can be used to determine at which location they appear in "sensor_msgs/msg/Joy".
443

544
## Supported Hardware
645

7-
This node should work with any joystick that is supported by SDL.
46+
This nodes should work with any joystick or game controller that is supported by SDL.
847

948
## Published Topics
1049

@@ -16,7 +55,7 @@ This node should work with any joystick that is supported by SDL.
1655
## Parameters
1756

1857
* device_id (int, default: 0)
19-
* The joystick device to use.
58+
* The joystick device to use. `ros2 run joy joy_enumerate_devices` wil list the attached devices.
2059

2160
* device_name (string, default: "")
2261
* The joystick name to use. This can be useful when multiple different joysticks are attached. If both device_name and device_id are specified, device_name takes precedence.
@@ -33,6 +72,6 @@ This node should work with any joystick that is supported by SDL.
3372
* coalesce_interval_ms (int, default: 1)
3473
* The number of milliseconds to wait after an axis event before publishing a message. Since the kernel sends an event for every change, this can significantly reduce the number of messages published. Setting it to 0 disables this behavior. The default of 1 ms is a good compromise between message delays and number of messages published.
3574

36-
## Technical note about interfacing with the joystick on Linux
75+
## Technical note about interfacing with joysticks and game controllers on Linux
3776

3877
On Linux there are two different ways to interface with a joystick. The distinction only makes a difference when attempting to pass through the device into a container or virtual machine. The first interface is via the joystick driver subsystem, which generally shows up as a device in /dev/input/js0 (or other numbers at the end). This is the way that the "joy_linux" package accesses the joystick. The second way to interface is through the generic event subsystem, which generally shows up as /dev/input/event7 (or other numbers at the end). This is the way that SDL (and hence this "joy" package) accesses the joysticks.
Lines changed: 94 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,94 @@
1+
/*
2+
* Copyright (c) 2020, Open Source Robotics Foundation.
3+
* Copyright (c) 2023, CSIRO Data61.
4+
* All rights reserved.
5+
*
6+
* Redistribution and use in source and binary forms, with or without
7+
* modification, are permitted provided that the following conditions are met:
8+
*
9+
* * Redistributions of source code must retain the above copyright
10+
* notice, this list of conditions and the following disclaimer.
11+
* * Redistributions in binary form must reproduce the above copyright
12+
* notice, this list of conditions and the following disclaimer in the
13+
* documentation and/or other materials provided with the distribution.
14+
* * Neither the name of the copyright holder nor the names of its
15+
* contributors may be used to endorse or promote products derived from
16+
* this software without specific prior written permission.
17+
*
18+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22+
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23+
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24+
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25+
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26+
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27+
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28+
* POSSIBILITY OF SUCH DAMAGE.
29+
*/
30+
31+
#ifndef JOY__GAME_CONTROLLER_HPP_
32+
#define JOY__GAME_CONTROLLER_HPP_
33+
34+
#include <SDL.h>
35+
36+
#include <future>
37+
#include <memory>
38+
#include <string>
39+
#include <thread>
40+
41+
#include <rclcpp/rclcpp.hpp>
42+
#include <sensor_msgs/msg/joy.hpp>
43+
#include <sensor_msgs/msg/joy_feedback.hpp>
44+
45+
namespace joy
46+
{
47+
48+
class GameController final : public rclcpp::Node
49+
{
50+
public:
51+
explicit GameController(const rclcpp::NodeOptions & options);
52+
GameController(GameController && c) = delete;
53+
GameController & operator=(GameController && c) = delete;
54+
GameController(const GameController & c) = delete;
55+
GameController & operator=(const GameController & c) = delete;
56+
57+
~GameController() override;
58+
59+
private:
60+
void eventThread();
61+
bool handleControllerAxis(const SDL_ControllerAxisEvent & e);
62+
bool handleControllerButtonDown(const SDL_ControllerButtonEvent & e);
63+
bool handleControllerButtonUp(const SDL_ControllerButtonEvent & e);
64+
void handleControllerDeviceAdded(const SDL_ControllerDeviceEvent & e);
65+
void handleControllerDeviceRemoved(const SDL_ControllerDeviceEvent & e);
66+
float convertRawAxisValueToROS(int16_t val);
67+
void feedbackCb(const std::shared_ptr<sensor_msgs::msg::JoyFeedback> msg);
68+
69+
int dev_id_{0};
70+
71+
SDL_GameController * game_controller_{nullptr};
72+
SDL_JoystickID joystick_instance_id_{0};
73+
double scaled_deadzone_{0.0};
74+
double unscaled_deadzone_{0.0};
75+
double scale_{0.0};
76+
double autorepeat_rate_{0.0};
77+
int autorepeat_interval_ms_{0};
78+
bool sticky_buttons_{false};
79+
bool publish_soon_{false};
80+
rclcpp::Time publish_soon_time_;
81+
int coalesce_interval_ms_{0};
82+
std::string dev_name_;
83+
std::thread event_thread_;
84+
std::shared_future<void> future_;
85+
std::promise<void> exit_signal_;
86+
rclcpp::Publisher<sensor_msgs::msg::Joy>::SharedPtr pub_;
87+
rclcpp::Subscription<sensor_msgs::msg::JoyFeedback>::SharedPtr feedback_sub_;
88+
89+
sensor_msgs::msg::Joy joy_msg_;
90+
};
91+
92+
} // namespace joy
93+
94+
#endif // JOY__GAME_CONTROLLER_HPP_

joy/package.xml

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -4,12 +4,9 @@
44
<name>joy</name>
55
<version>3.1.0</version>
66

7-
<description>
8-
The joy package contains joy_node, a node that interfaces a
9-
generic joystick to ROS 2. This node publishes a "Joy"
10-
message, which contains the current state of each one of the
11-
joystick's buttons and axes.
12-
</description>
7+
<description> The joy package contains joy_node, a node that interfaces a generic joystick to ROS
8+
2. This node publishes a "Joy" message, which contains the current state of each one of the
9+
joystick's buttons and axes. </description>
1310

1411
<maintainer email="[email protected]">Chris Lalancette</maintainer>
1512
<license>BSD</license>
@@ -21,6 +18,7 @@
2118
<author>Kevin Watts</author>
2219
<author>Blaise Gassend</author>
2320
<author>Jonathan Bohren</author>
21+
<author>Rod Taylor</author>
2422

2523
<buildtool_depend>ament_cmake_ros</buildtool_depend>
2624

0 commit comments

Comments
 (0)