Software Setup
orca_core SDK installation, USB driver setup, individual finger control API, ROS2 hand interface, tactile sensor reading, and MuJoCo simulation. From a fresh Python install to all 17 joints moving.
Jump to a section:
orca_core SDK Installation
orca_core is the official Python SDK for the Orca Hand. It is installable via pip and supports Python 3.9+. No ROS required for basic joint control.
Create a virtual environment
python -m venv ~/.venvs/orca
source ~/.venvs/orca/bin/activate # Windows: .venvs\orca\Scripts\activate
Install via pip
pip install orca-core
Install via Poetry (recommended for development)
git clone https://github.com/orcahand/orca_core.git
cd orca_core
poetry install
Verify installation and find your hand
python -c "from orca_core import OrcaHand; print('orca_core installed OK')"
# Find the USB serial port
python -c "
from orca_core import OrcaHand
# Lists available ports
import serial.tools.list_ports
ports = list(serial.tools.list_ports.comports())
for p in ports:
print(p)
"
Individual Finger Control
The OrcaHand class exposes all 17 joints via named finger and joint accessors. Control mode defaults to current_based_position.
Connect and read all joint positions
from orca_core import OrcaHand
hand = OrcaHand(port="/dev/ttyUSB0", handedness="right")
hand.connect()
# Read all joint positions (returns dict of joint_name: position_deg)
positions = hand.get_positions()
print(positions)
# e.g. {'thumb_abduct': 0.0, 'thumb_mcp': 15.2, ...}
hand.disconnect()
Move individual joints
from orca_core import OrcaHand
import time
hand = OrcaHand(port="/dev/ttyUSB0", handedness="right")
hand.connect()
hand.enable_all()
# Move thumb MCP joint to 45 degrees
hand.set_position("thumb_mcp", 45.0)
time.sleep(0.5)
# Move index finger MCP to 60 degrees
hand.set_position("index_mcp", 60.0)
time.sleep(0.5)
# Open all fingers
hand.open_all()
time.sleep(1.0)
hand.disable_all()
hand.disconnect()
Set multiple joints simultaneously
from orca_core import OrcaHand
hand = OrcaHand(port="/dev/ttyUSB0", handedness="right")
hand.connect()
hand.enable_all()
# Command all 17 joints at once (dict of joint_name: target_deg)
pose = {
"thumb_abduct": 30.0,
"thumb_mcp": 45.0,
"thumb_pip": 30.0,
"thumb_dip": 20.0,
"index_mcp": 70.0,
"index_pip": 60.0,
"index_dip": 40.0,
# ... remaining joints
}
hand.set_positions(pose)
hand.disable_all()
hand.disconnect()
Built-in Grasp Primitives
orca_core ships with calibrated grasp primitives for common manipulation tasks. These are the fastest way to test basic grasping before implementing custom policies.
Using grasp primitives
from orca_core import OrcaHand
from orca_core.grasps import GraspLibrary
import time
hand = OrcaHand(port="/dev/ttyUSB0", handedness="right")
hand.connect()
hand.enable_all()
grasps = GraspLibrary()
# Open hand
hand.execute_grasp(grasps.open)
time.sleep(1.0)
# Power grasp (whole-hand wrap)
hand.execute_grasp(grasps.power_grasp)
time.sleep(1.0)
# Precision pinch (thumb + index tip)
hand.execute_grasp(grasps.precision_pinch)
time.sleep(1.0)
# Tripod grasp (thumb + index + middle)
hand.execute_grasp(grasps.tripod)
time.sleep(1.0)
# Lateral pinch (thumb side against index lateral)
hand.execute_grasp(grasps.lateral_pinch)
time.sleep(1.0)
hand.open_all()
hand.disable_all()
hand.disconnect()
Interpolate between grasps
from orca_core import OrcaHand
from orca_core.grasps import GraspLibrary
import time, numpy as np
hand = OrcaHand(port="/dev/ttyUSB0", handedness="right")
hand.connect()
hand.enable_all()
grasps = GraspLibrary()
# Smoothly interpolate from open to power grasp over 30 steps
for alpha in np.linspace(0, 1, 30):
pose = grasps.interpolate(grasps.open, grasps.power_grasp, alpha)
hand.set_positions(pose)
time.sleep(0.05)
hand.disable_all()
hand.disconnect()
ROS2 Hand Interface
The orca_ros2 package provides a full ROS2 interface for coordinated arm + hand control. It publishes joint states and accepts joint trajectory commands.
Install orca_ros2
mkdir -p ~/orca_ws/src && cd ~/orca_ws/src
git clone https://github.com/orcahand/orca_ros2.git
cd ~/orca_ws
source /opt/ros/humble/setup.bash
colcon build --symlink-install
Launch the hand driver node
source ~/orca_ws/install/setup.bash
ros2 launch orca_ros2 orca_hand.launch.py \
port:=/dev/ttyUSB0 \
handedness:=right
Subscribe to joint state topic
ros2 topic echo /orca_hand/joint_states
Send joint position command
ros2 topic pub /orca_hand/joint_command \
sensor_msgs/msg/JointState \
'{name: ["index_mcp", "index_pip"], position: [1.22, 1.05]}'
Coordinated arm + hand launch (with OpenArm)
ros2 launch orca_ros2 openarm_orca.launch.py \
arm_can_interface:=can0 \
hand_port:=/dev/ttyUSB0 \
handedness:=right
This launches both the openarm_ros2 arm driver and the orca_ros2 hand driver under a single namespace, enabling coordinated trajectory execution through MoveIt2.
Tactile Sensor Reading
The Orca Hand optionally mounts fingertip tactile sensors (Paxini or compatible). Tactile data streams independently over a separate USB connection.
Reading fingertip contact force
from orca_core import OrcaHand
from orca_core.sensors import TactileSensorArray
hand = OrcaHand(port="/dev/ttyUSB0", handedness="right")
tactile = TactileSensorArray(port="/dev/ttyUSB1") # separate USB port
hand.connect()
tactile.connect()
hand.enable_all()
import time
for _ in range(100):
# Returns dict of finger_name: contact_force_N
forces = tactile.read_forces()
positions = hand.get_positions()
print(f"Index force: {forces.get('index', 0):.3f} N | "
f"Index MCP: {positions['index_mcp']:.1f} deg")
time.sleep(0.01)
hand.disable_all()
hand.disconnect()
tactile.disconnect()
Contact detection threshold
from orca_core.sensors import TactileSensorArray
tactile = TactileSensorArray(port="/dev/ttyUSB1")
tactile.connect()
# Set contact detection threshold per finger (in N)
tactile.set_threshold(finger="index", threshold_n=0.1)
tactile.set_threshold(finger="thumb", threshold_n=0.15)
# Returns True when contact exceeds threshold
in_contact = tactile.is_in_contact("index")
print("Index in contact:", in_contact)
MuJoCo Simulation
The Orca Hand ships with calibrated MuJoCo MJCF models — left hand, right hand, and a bimanual scene. The simulation shares identical joint names and action spaces with real hardware.
Install and run the simulation
pip install mujoco
pip install orca-core[sim] # or: pip install orca-mujoco
# Clone the MuJoCo model package
git clone https://github.com/orcahand/orcahand_description.git
# Launch the right-hand sim
python -c "
import mujoco, mujoco.viewer
import numpy as np
model = mujoco.MjModel.from_xml_path('orcahand_description/mjcf/orca_right.xml')
data = mujoco.MjData(model)
with mujoco.viewer.launch_passive(model, data) as viewer:
while viewer.is_running():
mujoco.mj_step(model, data)
viewer.sync()
"
Sim-to-real transfer
Joint names in the MJCF model match the orca_core SDK exactly. A policy trained in simulation on grasp primitives can be deployed directly to real hardware — the only difference is USB serial latency (~3ms) vs. physics step timing.
Common Issues
Usually a daisy-chain cable is not fully seated at a junction between finger modules. The STS bus is a chain — one bad connection drops all downstream servos.
Fix:
# Scan to see which servo IDs are found
python -c "
from orca_core import OrcaHand
hand = OrcaHand(port='/dev/ttyUSB0', handedness='right')
hand.connect()
ids = hand.scan_motors()
print('Found IDs:', ids) # should be 1..17
hand.disconnect()
"
A finger cannot fully extend or flex. Tendon routing is too tight on one side. Occurs most commonly after reassembly.
Fix:
# Check joint limits — move each joint to its range manually
python -c "
from orca_core import OrcaHand
hand = OrcaHand(port='/dev/ttyUSB0')
hand.connect()
# Enable compliance mode — move finger by hand to feel the limits
hand.set_compliance_mode(finger='index', enabled=True)
"
# If finger hits hard limit below expected range,
# loosen the extensor tendon by 0.5 turns at the tendon anchor
The orca_ros2 driver node launched but is not publishing joint states. Usually a port permission issue or conflicting orca_core session.
Fix:
# 1. Ensure no other orca_core session has the port open
# Close any Python scripts using the hand first
# 2. Add USB serial permissions (Linux)
sudo usermod -aG dialout $USER # log out and back in
# 3. Re-launch with explicit port
ros2 launch orca_ros2 orca_hand.launch.py port:=/dev/ttyUSB0
# 4. Check topic
ros2 topic hz /orca_hand/joint_states # should be ~100 Hz