Swift is a light-weight browser-based simulator built on top of the Robotics Toolbox for Python. This simulator provides robotics-specific functionality for rapid prototyping of algorithms, research, and education. Built using Python and Javascript, Swift is cross-platform (Linux, MacOS, and Windows) while also leveraging the ubiquity and support of these languages.
Through the Robotics Toolbox for Python, Swift can visualise over 30 supplied robot models: well-known contemporary robots from Franka-Emika, Kinova, Universal Robotics, Rethink as well as classical robots such as the Puma 560 and the Stanford arm. Swift is under development and will support mobile robots in the future.
Swift provides:
Swift is designed to be controlled through the Robotics Toolbox for Python. By installing the toolbox through PyPI, swift is installed as a dependency
pip3 install roboticstoolbox-python
Otherwise, Swift can be install by
pip3 install swift-sim
Available options are:
nb
provides the ability for Swift to be embedded within a Jupyter Notebookvision
implements an RTC communication strategy allowing for visual feedback from Swift and allows Swift to be run on Google ColabPut the options in a comma-separated list like
pip3 install swift-sim[optionlist]
To install the latest version from GitHub
git clone https://github.com/jhavl/swift.git
cd swift
pip3 install -e .
We will load a model of the Franka-Emika Panda robot and plot it. We set the joint angles of the robot into the ready joint configuration qr.
import roboticstoolbox as rp
panda = rp.models.Panda()
panda.plot(q=panda.qr)
We will load a model of the Franka-Emika Panda robot and make it travel towards a goal pose defined by the variable Tep.
import roboticstoolbox as rtb
import spatialmath as sm
import numpy as np
from swift import Swift
# Make and instance of the Swift simulator and open it
env = Swift()
env.launch(realtime=True)
# Make a panda model and set its joint angles to the ready joint configuration
panda = rtb.models.Panda()
panda.q = panda.qr
# Set a desired and effector pose an an offset from the current end-effector pose
Tep = panda.fkine(panda.q) * sm.SE3.Tx(0.2) * sm.SE3.Ty(0.2) * sm.SE3.Tz(0.45)
# Add the robot to the simulator
env.add(panda)
# Simulate the robot while it has not arrived at the goal
arrived = False
while not arrived:
# Work out the required end-effector velocity to go towards the goal
v, arrived = rtb.p_servo(panda.fkine(panda.q), Tep, 1)
# Set the Panda's joint velocities
panda.qd = np.linalg.pinv(panda.jacobe(panda.q)) @ v
# Step the simulator by 50 milliseconds
env.step(0.05)
To embed within a Jupyter Notebook Cell, use the browser="notebook"
option when launching the simulator.
# Try this example within a Jupyter Notebook Cell!
import roboticstoolbox as rtb
import spatialmath as sm
import numpy as np
from swift import Swift
# Make and instance of the Swift simulator and open it
env = Swift()
env.launch(realtime=True, browser="notebook")
# Make a panda model and set its joint angles to the ready joint configuration
panda = rtb.models.Panda()
panda.q = panda.qr
# Set a desired and effector pose an an offset from the current end-effector pose
Tep = panda.fkine(panda.q) * sm.SE3.Tx(0.2) * sm.SE3.Ty(0.2) * sm.SE3.Tz(0.45)
# Add the robot to the simulator
env.add(panda)
# Simulate the robot while it has not arrived at the goal
arrived = False
while not arrived:
# Work out the required end-effector velocity to go towards the goal
v, arrived = rtb.p_servo(panda.fkine(panda.q), Tep, 1)
# Set the Panda's joint velocities
panda.qd = np.linalg.pinv(panda.jacobe(panda.q)) @ v
# Step the simulator by 50 milliseconds
env.step(0.05)
CRICOS No. 00213J