- 2025-06-06: Our paper is released in arxiv. You can cite by:
@misc{dong2025gexdemocratizingdexterityfullyactuated,
title={GEX: Democratizing Dexterity with Fully-Actuated Dexterous Hand and Exoskeleton Glove},
author={Yunlong Dong and Xing Liu and Jun Wan and Zelin Deng},
year={2025},
eprint={2506.04982},
archivePrefix={arXiv},
primaryClass={cs.RO},
url={https://arxiv.org/abs/2506.04982},
}Libgex uses dynamixel SDK to control the motors in Python via OpenRB-150 control board through TTL at 1M bps. And libgex uses PyBullet to calculate the forward kinematics and inverse kinematics of the GX11 and EX12.
pip install pyserial
pip install pybulletRecommended using URDFly to visualize the URDF.
Or drag folder libgex/gx11 or libgex/ex11 into http://urdf.robotsfan.com/ to visualize the URDF.
GX11 has 3 joints in finger1(thumb), 4 joints in finger2(index), 4 joints in finger3(middle).
Or use https://github.com/openrr/urdf-viz to visualize the URDF and display the link name and axes.
EX12 has 4 joints in finger1(thumb), 4 joints in finger2(index), 4 joints in finger3(middle).
The 4 joints design in thumb enable the exoskeleton glove to be better attached to the human thumb tip.
python demo_gx11.pypython demo_ex12.pyfrom libgex.libgx11 import Hand
import time
hand = Hand(port='/dev/ttyACM0') # COM* for Windows, ttyACM* or ttyUSB* for Linux, if in Linux, check the port number with `ls /dev/tty*`, then run `sudo chmod 777 /dev/ttyACM*`
hand.connect(curr_limit=500, goal_current=300, goal_pwm=300) # will torque on all the motors, goal_pwm changes the speed, max 855
hand.home() # home the hand
hand.motors[0].setj(90) # unit degree
print(hand.getj()) # print all the joints angles in degreefrom libgex.libex12 import Glove
from libgex.utils import search_ports
import time
port = search_ports()[0]
glove = Glove('/dev/ttyACM1') # COM* for Windows, ttyACM* or ttyUSB* for Linux, if in Linux, check the port number with `ls /dev/tty*`, then run `sudo chmod 777 /dev/ttyACM*`
glove.connect(init=False) # do not torque on glove yet.
print(glove.fk_finger1()) # get the thumb tip xyz position in base_link frame (bottom of the palm), unit m
All the contorl commands are in libgex/libgx11.py and libgex/libex12.py
Pybullet is used to handle forward kinematics and inverse kinematics, you can pass vis=True to toggle visualization in pybullet by:
from libgex.libex12 import Glove
glove = Glove('/dev/ttyACM1', vis=True) # COM* for Windows, ttyACM* or ttyUSB* for Linux
glove.connect(init=False) # do not torque on glove yet.
while True:
glove.fk_finger1() # get the thumb tip xyz position in base_link frame (bottom of the palm), unit m
glove.fk_finger2() # get the index tip xyz position in base_link frame (bottom of the palm), unit m
glove.fk_finger3() # get the middle tip xyz position in base_link frame (bottom of the palm), unit m
time.sleep(0.1)Then you can move ex12 to see the corresponding movement in pybullet.
https://github.com/Democratizing-Dexterous/ExoskeletonGloveEX12
https://github.com/Democratizing-Dexterous/DexterousHandGX11
https://github.com/ROBOTIS-GIT/DynamixelSDK
Leap Hand


