Skip to content

Commit

Permalink
Use the SDL2 Game Controller API (#258)
Browse files Browse the repository at this point in the history
* 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
rodericktaylor authored Sep 18, 2023
1 parent e3c3388 commit b0bc9d7
Show file tree
Hide file tree
Showing 7 changed files with 622 additions and 19 deletions.
22 changes: 22 additions & 0 deletions joy/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,27 @@ rclcpp_components_register_node(joy
PLUGIN "joy::Joy"
EXECUTABLE joy_node)

add_library(game_controller SHARED src/game_controller.cpp)
target_include_directories(game_controller PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
ament_target_dependencies(game_controller
rclcpp
rclcpp_components
sensor_msgs)
target_link_libraries(game_controller
SDL2::SDL2)

install(TARGETS game_controller EXPORT export_game_controller
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
RUNTIME DESTINATION bin
)

rclcpp_components_register_node(game_controller
PLUGIN "joy::GameController"
EXECUTABLE game_controller_node)

add_executable(joy_enumerate_devices
src/joy_enumerate_devices.cpp)
target_link_libraries(joy_enumerate_devices
Expand All @@ -52,6 +73,7 @@ install(DIRECTORY config launch
DESTINATION share/${PROJECT_NAME})

ament_export_targets(export_joy)
ament_export_targets(export_game_controller)
ament_export_dependencies(
"rclcpp"
"sensor_msgs"
Expand Down
49 changes: 44 additions & 5 deletions joy/README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,49 @@
# ROS 2 Driver for Generic Joysticks
# ROS 2 Driver for Generic Joysticks and Game Controllers

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.
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.

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.

For game_controller_node the following tables detail the indexes of buttons and axes.

| Index | Button |
| - | - |
| 0 | A (CROSS) |
| 1 | B (CIRCLE) |
| 2 | X (SQUARE) |
| 3 | Y (TRIANGLE) |
| 4 | BACK (SELECT) |
| 5 | GUIDE (Middle/Manufacturer Button) |
| 6 | START |
| 7 | LEFTSTICK |
| 8 | RIGHTSTICK |
| 9 | LEFTSHOULDER |
| 10 | RIGHTSHOULDER |
| 11 | DPAD_UP |
| 12 | DPAD_DOWN |
| 13 | DPAD_LEFT |
| 14 | DPAD_RIGHT |
| 15 | MISC1 (Depends on the controller manufacturer, but is usually at a similar location on the controller as back/start) |
| 16 | PADDLE1 (Upper left, facing the back of the controller if present) |
| 17 | PADDLE2 (Upper right, facing the back of the controller if present) |
| 18 | PADDLE3 (Lower left, facing the back of the controller if present) |
| 19 | PADDLE4 (Lower right, facing the back of the controller if present) |
| 20 | TOUCHPAD (If present. Button status only) |

| Index | Axis |
| - | - |
| 0 | LEFTX |
| 1 | LEFTY |
| 2 | RIGHTX |
| 3 | RIGHTY |
| 4 | TRIGGERLEFT |
| 5 | TRIGGERRIGHT |

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".

## Supported Hardware

This node should work with any joystick that is supported by SDL.
This nodes should work with any joystick or game controller that is supported by SDL.

## Published Topics

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

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

* device_name (string, default: "")
* 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.
Expand All @@ -33,6 +72,6 @@ This node should work with any joystick that is supported by SDL.
* coalesce_interval_ms (int, default: 1)
* 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.

## Technical note about interfacing with the joystick on Linux
## Technical note about interfacing with joysticks and game controllers on Linux

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.
94 changes: 94 additions & 0 deletions joy/include/joy/game_controller.hpp
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_
10 changes: 4 additions & 6 deletions joy/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand All @@ -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>

Expand Down
Loading

0 comments on commit b0bc9d7

Please sign in to comment.