Skip to content

Latest commit

 

History

History
204 lines (139 loc) · 6.92 KB

README.md

File metadata and controls

204 lines (139 loc) · 6.92 KB

Joy2Twist

Dockerized ROS node allowing control of ROS-powered mobile robots with Logitech F710 gamepad. Joy2Twist node is converting sensor_msgs/Joy message to geometry_msgs/Twist in order to provide velocity commands for the mobile robot. Therefore this package is compliant (but not supported by Husarion) with any other gamepad controller which is able to publish the sensor_msgs/Joy message.

Setup joy

Connect joy via nano USB receiver and make sure it is in DirectInput Mode (switch in front of the pad with letters D and X, select D).

To test if joy works, use jstest /dev/input/js0. If the output is:

jstest: No such file or directory

See ls /dev/input | grep js and find your joy number. If it differs, apply changes in compose.yaml and launch file.

Button mapping

Gamepad legend

Button Function
LB enable driving
RB slow driving mode
RT fast driving mode

If neither RB nor RT is pressed, the robot operates in regular driving mode.

To drive robot use sticks. By default, linear X and Y are held by the left stick. Angular Z is controlled with the right stick.

Emergency stop

Button Function
A Reset E-stop
B Trigger E-stop
LT Enable E-stop reset

Note

Handle of robot's emergency stop is available only when ~e_stop/present parameter is set true. This functionality will work with any robot configured as follows:

  • publishes robot's E-stop state using ROS topic of type std_msgs/Bool.
  • allows resetting robot's E-stop using ROS service of type std_srvs/Trigger.
  • allows triggering robot's E-stop using ROS service of type std_srvs/Trigger.

Topic and services names can be configured using ROS parameters, see Parameters for more info.


ROS node API

ROS node is translating joy topic to cmd_vel topic.

Publish

  • cmd_vel (geometry_msgs/Twist)

Subscribe

  • joy (sensor_msgs/Joy)

Parameters

Following parameters change joystick axes mapped to given robot axes of freedom.

  • ~input_index_map.axis.linear_x (string, default: "B1")
  • ~input_index_map.axis.linear_y (string, default: "B0")
  • ~input_index_map.axis.angular_z (string, default: "B3")

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)

The node can be configured using parameters described below to work with robots equipped with an E-stop interface. An example configuration for a robot with an E-stop interface can be found in panther config file.

  • ~e_stop/present (bool, default: false)
  • ~e_stop/topic (string, default: e_stop)
  • ~e_stop/reset_srv (string, default: e_stop_reset)
  • ~e_stop/trigger_srv (string, default: e_stop_trigger)

Input mapping

Buttons on the controller can be mapped to different functions by providing an YAML config file with an input_index_map key.

Each entry under input_index_map should have a string value with following consecutive fields:

  • optional input negation: !,
  • input type: A for an axis or B for a button,
  • axis/button number.
fast_mode: '!A5' # RT
slow_mode: 'B5' # RB

In the example above slow_mode button has been mapped to a button (B) with index 5 on the gamepad and fast_mode button has been mapped to an axis (A) with index 5.

Mapping an axis as a button will result in the axis being treated as a binary button with a small dead-zone threshold (0.05).

Usage of triggers as buttons may require inverting the axis with a negation sign ! to activate function after pressing the trigger as their values decrease from 1 to -1 during actuation.

For reference, see the default DirectInput config file and the Husarion UGV (XInput) config file.

Docker image

Build/Publish Docker Image

ROS2 distro Supported architectures
iron linux/amd64, linux/arm64
humble linux/amd64, linux/arm64

Available on Docker Hub

Demo

Controlling ROSbot XL with a Logitech F710 Gamepad

  1. Flash the right firmware:

    docker stop rosbot-xl microros || true && \
    docker run --rm -it --privileged \
    --mount type=bind,source=/dev/ttyUSBDB,target=/dev/ttyUSBDB \
    husarion/rosbot-xl:humble-0.8.2-20230913 \
    flash-firmware.py -p /dev/ttyUSBDB
  2. Connect Logitech F710 dongle to the ROSbot XL and run (on ROSbot):

    cd joy2twist/demo/single_robot
    docker compose -f compose.rosbotxl.yaml up

Controlling ROSbot 2R with a Logitech F710 Gamepad

  1. Flash the right firmware:

    docker stop rosbot microros || true && docker run \
    --rm -it --privileged \
    husarion/rosbot:humble-0.6.1-20230712 \
    flash-firmware.py /root/firmware.bin
  2. Connect Logitech F710 dongle to the ROSbot 2R and run (on ROSbot):

    cd joy2twist/demo/single_robot
    docker compose -f compose.rosbot2r.yaml up

Different namespace demo with a Logitech F710 gamepad

Connect a Logitech F710 USB dongle to your PC. Clone this repo to your PC and go to the joy2twist/demo/ directory and run in a separate terminal:

./sync_with_robot.sh <YOUR_ROSBOT_IP>

Change the namespace in the multiple_robots/.env file:

ROS_NAMESPACE=robot1

Now SSH to your robot:

ssh husarion@<YOUR_ROSBOT_IP>

Go to the folder /home/husarion/demo/multiple_robots, and launch the container for ROSbot:

docker compose -f compose.rosbot2r.yaml up

Topic filtering

If you will then check on the PC the available ROS 2 nodes you will get:

$ ros2 topic list
/parameter_events
/robot1/cmd_vel
/rosout

Note that nly the single /robot1/cmd_vel topic is available outside the robot thanks to the configuration from the ros2router_config.yaml file.

To control the robot by using the teleop, just run: ros2 run teleop_twist_keyboard teleop_twist_keyboard __ns:=/robot1

To run the joy2twist container execute the following command on your PC in the joy2twist/demo/multiple_robots directory:

docker compose -f compose.pc.yaml up