Skip to content

ROS2 turtlesim joystick

Rodja Trappe edited this page Sep 28, 2023 · 5 revisions

Introduction

In this example, we'll create an application that uses the NiceGUI joystick to control the turtlesim.

The source code of this example can be found here: turtlesim joystick

Prerequisites

Before getting started, make sure you have the following installed:

Code Explanation

The example consists of a simple ROS2 node that sends the virtual joystick input as a twist message to the turtlesim node.

Importing Libraries

import rclpy
from rclpy.node import Node
from rclpy.executors import ExternalShutdownException
from geometry_msgs.msg import Twist

from nicegui import app, globals, run, ui
import threading
from pathlib import Path

We import the necessary libraries, including ROS2, NiceGUI for the user interface, geometry_msgs.msg twist for the message and other required modules.

Creating a Class

class SimpleJoystick(Node):
    def __init__(self) -> None:
        super().__init__('joystick_node')
        self.publisher_ = self.create_publisher(Twist, 'turtle1/cmd_vel', 1)

We create a ROS2 node called SimpleJoystick that publishes the twist message on the topic turtle1/cmd_vel.

NiceGUI elements

We use NiceGUI to create a graphical user interface. The interface includes two ui.card() elements.

        #this is where we add nicegui elements
        with globals.index_client:
            #create a row
            with ui.row().classes('items-stretch'):
                #create a card with the joystick in it
                with ui.card().classes('w-80 text-center items-center'):
                    # NOTE: Joystick will be reworked in the future, so this is a temporary workaround for the size.
                    ui.add_head_html('<style>.my-joystick > div { width: 20em !important; height: 20em !important; }</style>')
                    ui.joystick(
                        color='blue',
                        size=50,
                        #Note: x has to be inverted. Negative values turn the turtle to the right.
                        on_move=lambda e: self.publish_speeds(-e.x, e.y),
                        on_end=lambda _: self.publish_speeds(0.0, 0.0),
                    ).classes('my-joystick')
                    
                    ui.label('Publish steering commands by dragging your mouse around in the blue field').classes('mt-6')

In the first card, we define the joystick to control the turtlesim. We also add a simple label with instructions.

                with ui.card().classes('w-44 text-center items-center'):
                    ui.label('Speeds').classes('text-2xl')
                    slider_props = 'readonly selection-color=transparent'

                    #create a slider & labelfor the linear speed
                    ui.label('linear velocity').classes('text-xs mb-[-1.8em]')
                    self.linear = ui.slider(min=-1, max=1, step=0.05, value=0).props(slider_props)
                    ui.label().bind_text_from(self.linear,'value', backward=lambda value: f'{value:.3f}')
                    
                    #create a slider & label for the angular speed
                    ui.label('angular velocity').classes('text-xs mb-[-1.8em]')
                    self.angular = ui.slider(min=-1, max=1, step=0.05, value=0).props(slider_props)
                    ui.label().bind_text_from(self.angular,'value', backward=lambda value: f'{value:.3f}')

The second card displays the velocities, with an ui.slider() and an ui.label() element for each velocity.

publishing the twist message

    #this function publishes the twist message
    def publish_speeds(self, x:float, y:float) -> None:
        msg = Twist()
        self.get_logger().info('Publishing1-> linear: "%f", angular: "%f"' % (y, x))
        #this is for the sliders
        self.linear.value = y
        self.angular.value = x
        #loading values into the message
        msg.linear.x = y
        msg.angular.z = x
        self.publisher_.publish(msg)

Before publishing the twist message, the joystick's values get saved in the value of the sliders.

Controlling the ROS2 Node

def ros_main() -> None:
    #Standart ROS2 node initialization
    print('Starting ROS2...', flush=True)

    rclpy.init()
    simple_joystick = SimpleJoystick()

    try:
        rclpy.spin(simple_joystick)
    except ExternalShutdownException:
        pass

The ROS2 node itself gets controlled by this function. This is basically the contents of your main() function in a normal ROS2 node.

Main Function

def main():
    pass  # This is originally used as the ROS entry point, but we give the control of the node to NiceGUI.

Usually, this is the entry point of the ROS2 node. ROS still wants to have this as an entry point set in the setup.py.

Running NiceGUI and Starting the node

app.on_startup(lambda: threading.Thread(target=ros_main).start())

# This is for the automatic reloading by NiceGUI/fastapi
run.APP_IMPORT_STRING = f'{__name__}:app'

# We add reload dirs to watch changes in our package
ui.run(title='Turtlesim Joystick',uvicorn_reload_dirs=str(Path(__file__).parent.resolve()))

The starting of the ROS2 node is handled by NiceGUI. The Node will be started with the app.on_startup() function. The node will be started in its own thread as well, since running NiceGUI and the ROS2 node in the same thread causes one to be blocked by the other. The second reason we do this is, that the ROS2 node gets restarted every time NiceGUI reloads itself.

How to use

The usage is quite simple, just run these commands in two terminals. Afterward, a browser window should have opened with the GUI running on localhost:8080.

Note: This node is not continuously sending. It will send a new twist command on change of the joystick.

Terminal1 :

ros2 run ros_nicegui_turtlesim_joystick joystick 

Terminal2 :

ros2 run turtlesim turtlesim_node 
Clone this wiki locally