From 32362fd7d147c55d49be3bbc161cefbfcc993e80 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Fri, 6 Sep 2024 13:45:49 -0400 Subject: [PATCH] Update the launch file to work with modern joy. (#52) It should use "device_id" (not "dev") as the parameter, and the parameter should be a number, not a path (this is effectively the SDL device number, which is cross-platform). Signed-off-by: Chris Lalancette (cherry picked from commit e4856e4afeda704547bdb43edc29d008b07f15d9) # Conflicts: # README.md --- README.md | 13 +++++++++++-- launch/teleop-launch.py | 4 ++-- 2 files changed, 13 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 6953f83..f670e9a 100644 --- a/README.md +++ b/README.md @@ -2,10 +2,15 @@ ros2/teleop_twist_joy ===================== # Overview +<<<<<<< HEAD The purpose of this package is to provide a generic facility for tele-operating Twist-based ROS2 robots with a standard joystick. +======= +The purpose of this package is to provide a generic facility for tele-operating Twist-based ROS 2 robots with a standard joystick. +>>>>>>> e4856e4 (Update the launch file to work with modern joy. (#52)) It converts joy messages to velocity commands. -This node provides no rate limiting or autorepeat functionality. It is expected that you take advantage of the features built into [joy](https://index.ros.org/p/joy/github-ros-drivers-joystick_drivers/#foxy) for this. +This node provides no rate limiting or autorepeat functionality. +It is expected that you take advantage of the features built into [joy](https://index.ros.org/p/joy/github-ros-drivers-joystick_drivers) for this. ## Executables The package comes with the `teleop_node` that republishes `sensor_msgs/msg/Joy` messages as scaled `geometry_msgs/msg/Twist` messages. @@ -82,7 +87,11 @@ For most users building from source will not be required, execute `apt-get insta ## Run A launch file has been provided which has three arguments which can be changed in the terminal or via your own launch file. To configure the node to match your joystick a config file can be used. +<<<<<<< HEAD There are several common ones provided in this package (atk3, ps3-holonomic, ps3, xbox, xd3), located here: https://github.com/ros2/teleop_twist_joy/tree/eloquent/config. +======= +There are several common ones provided in this package (atk3, ps3-holonomic, ps3, xbox, xd3), located here: https://github.com/ros2/teleop_twist_joy/tree/rolling/config. +>>>>>>> e4856e4 (Update the launch file to work with modern joy. (#52)) PS3 is default, to run for another config (e.g. xbox) use this: ```` @@ -95,7 +104,7 @@ __Note:__ this launch file also launches the `joy` node so do not run it separat ## Arguments - `joy_config (string, default: 'ps3')` - Config file to use -- `joy_dev (string, default: 'dev/input/js0')` +- `joy_dev (string, default: '0')` - Joystick device to use - `config_filepath (string, default: '/opt/ros//share/teleop_twist_joy/config/' + LaunchConfig('joy_config') + '.config.yaml')` - Path to config files diff --git a/launch/teleop-launch.py b/launch/teleop-launch.py index 293d42d..b87d6e2 100755 --- a/launch/teleop-launch.py +++ b/launch/teleop-launch.py @@ -15,7 +15,7 @@ def generate_launch_description(): return launch.LaunchDescription([ launch.actions.DeclareLaunchArgument('joy_vel', default_value='cmd_vel'), launch.actions.DeclareLaunchArgument('joy_config', default_value='ps3'), - launch.actions.DeclareLaunchArgument('joy_dev', default_value='/dev/input/js0'), + launch.actions.DeclareLaunchArgument('joy_dev', default_value='0'), launch.actions.DeclareLaunchArgument('publish_stamped_twist', default_value='false'), launch.actions.DeclareLaunchArgument('config_filepath', default_value=[ launch.substitutions.TextSubstitution(text=os.path.join( @@ -25,7 +25,7 @@ def generate_launch_description(): launch_ros.actions.Node( package='joy', executable='joy_node', name='joy_node', parameters=[{ - 'dev': joy_dev, + 'device_id': joy_dev, 'deadzone': 0.3, 'autorepeat_rate': 20.0, }]),