Logitech - Gamepad F710
The Gamepad F710 by Logitech is a very popular controller in gaming, but also in the field of robotics. Connection is provided by fast 2.4 GHz wireless connection via a small USB receiver.
Getting started
To run the Gamepad F710, you must meet certain requirements listed below:
Software
- Docker Engine and Docker Compose.
- Device with Linux based OS (e.g. robot, laptop) and ROS 2 Humble installed.
Hardware
- Connectivity: USB 2.0/3.0
Make sure the Gamepad is in DirectInput Mode (switch in front of the gamepad with letters D and X -> select D).
Demo
Joy2Twist package creates a ROS 2 node, allowing control the ROS-powered mobile and manipulation robots with F710 Gamepad. Joy2Twist node converts sensor_msgs/Joy
message type to geometry_msgs/Twist
type in order to provide velocity commands for the robot. Therefore, this package is compliant with any other gamepad controllers which are able to publish the sensor_msgs/Joy
message.
This article covers the use of F710 Gamepad in a ROS 2 environment. If you are interested in ROS, please check out the ros1
branch in the joy2twist
repository.
The result of this demo will be the publication of a velocity messages on the ROS topic /cmd_vel
. An example with a mobile robot will be described below.
Lenovo Legion laptop running Ubuntu 22.04 with ROS 2 Humble natively installed.
Start guide
1. Plugin the device
Connect a small USB receiver to the USB port of your device (e.g. laptop).
You can verify that the device is connected from the command line:
lsusb | grep "Gamepad"
2. Download joy2twist
Docker image
docker pull husarion/joy2twist:humble
3. Create a configuration file
nano joy2twist.yaml
4. Paste the content inside
/**:
ros__parameters:
linear_velocity_factor:
fast: 1.0
regular: 0.5
slow: 0.2
angular_velocity_factor:
fast: 1.0
regular: 0.5
slow: 0.2
# This button mapping should be adjusted to the specific controller
# The following map is suited for Logitech F710
button_index_map:
axis:
angular_z: 2 # Right joystick
linear_x: 1 # Left joystick
linear_y: 0 # Left joystick
dead_man_switch: 4 # LB
fast_mode: 7 # RT
slow_mode: 5 # RB
5. Press ctrl + o and then ctrl + x to save and quit
6. Run the following Docker command
docker run -d \
--name joy2twist \
--restart unless-stopped \
--device /dev/input \
--volume $PWD/joy2twist.yaml:/joy2twist.yaml \
husarion/joy2twist:humble \
ros2 launch joy2twist gamepad_controller.launch.py joy2twist_params_file:=/joy2twist.yaml
Result
Now you should see the relevant ROS 2 topic:
user@hostname:~$ ros2 topic list
/cmd_vel
/diagnostics
/joy
/joy/set_feedback
/parameter_events
/rosout
By pressing buttons and tilting the Gamepad sticks you can check what is happening on the /joy
and /cmd_vel
topics:
ros2 topic echo /joy
ros2 topic echo /cmd_vel
Now, when your robot subscribes to the cmd_vel
topic, it will be automatically controlled by the F710 Gamepad. An example with a real robot is at the end of this article.
This is what the entire F710 Gamepad legend looks like in this configuration:
To stop a container type:
docker stop joy2twist
ROS API
In order for your robot to work with the joy2twist package, it must work on the following ROS topics for full compatibility. The joy
node receives signals from the physical Gamepad and publishes them in the form of a /joy
topic. The joy2twist
node is translating /joy
topic to /cmd_vel
topic with the following interface:
Publishes
/cmd_vel
(geometry_msgs/Twist)
Subscribes
/joy
(sensor_msgs/Joy)
Parameters
Following parameters change the joystick's axes mapped to given robot axes of freedom. For more information about parameter values, refer to the joy package wiki page.
~axis_linear_x
(int, default: 1)~axis_linear_y
(int, default: 0)~axis_angular_z
(int, default: 2)
The robot can be operated at 3 scales of speed depending on pressed buttons. It's possible to adjust velocity scaling factors using a config file. The units are m/s for linear movement and rad/s for angular movement.
fast
(float, default: 1)regular
(float, default: 0.5)slow
(float, default: 0.2)
Button mapping
Button | Function |
---|---|
LB | enable driving |
RB | slow driving mode |
RT | fast driving mode |
ROSbot example
You can use the F710 Gamepad with these Husarion robots for development and research:
- ROSbot XL (in the picture below),
- ROSbot 2R,
- ROSbot 2 PRO.
1. Plugin the device
Connect a small USB receiver to the USB port of ROSbot XL/2R
2. Clone the joy2twist
repository
git clone https://github.com/husarion/joy2twist.git
3. Run the example
- ROSbot XL
- ROSbot 2R
cd joy2twist/demo/single_robot
docker compose compose.rosbotxl.yaml up
cd joy2twist/demo/single_robot
docker compose compose.rosbot2r.yaml up
4. Control the ROSbot
In case of any problems visit joy2twist repository for more information.
Panther example
Panther is the bigger autonomous mobile robot and a platform dedicated for an outdoor environment. By default, the Panther robot comes with an F710 Gamepad. You can control the Panther with an additional safety function related to E-stop:
For more details, please visit the Panther Manual.
Other examples
- Gamepad control without PC (ROSbot 2R / 2 PRO)
- ROSbot Autonomy (ROSbot 2R / 2 PRO)
- Gamepad control without PC (ROSbot XL)
- ROSbot Autonomy (ROSbot XL)
Summary
In summary, controlling robots with gamepads is an interesting technology that can have many applications. It can be used for learning programming and robot control, as well as for improving safety in dangerous places or simply having fun. The joy2twist package is a great example of the application of the ROS environment in mobile robotics in practice.
Need help with this article or experiencing issues with software or hardware? 🤔
- Feel free to share your thoughts and questions on our Community Forum. 💬
- To contact service support, please use our dedicated Issue Form. 📝
- Alternatively, you can also contact our support team directly at: support@husarion.com. 📧