Software-Setup

orca_core SDK-Installation, USB-Treiber-Setup, individuelle Fingersteuerungs-API, ROS2-Handschnittstelle, taktile Sensorlesung und MuJoCo-Simulation. Von einer neuen Python-Installation bis hin zur Bewegung aller 17 Gelenke.

Zu einem Abschnitt springen:

Schritt 1 – SDK-Installation

orca_core SDK-Installation

orca_core ist das offizielle Python SDK für die Orca Hand. Es ist über pip installierbar und unterstützt Python 3.9+. Für die grundlegende Gelenksteuerung ist kein ROS erforderlich.

Erstellen Sie eine virtuelle Umgebung

python -m venv ~/.venvs/orca
source ~/.venvs/orca/bin/activate   # Windows: .venvs\orca\Scripts\activate

Per Pip installieren

pip install orca-core

Installation über Poetry (für die Entwicklung empfohlen)

git clone https://github.com/orcahand/orca_core.git
cd orca_core
poetry install

Überprüfen Sie die Installation und finden Sie Ihre 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)
"
Schritt 2 – Fingersteuerungs-API

Individuelle Fingersteuerung

Der OrcaHand Die Klasse macht alle 17 Gelenke über benannte Finger- und Gelenk-Accessoren verfügbar. Der Steuermodus ist standardmäßig auf current_based_position.

Alle Gelenkpositionen anschließen und ablesen

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()

Einzelne Gelenke bewegen

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()

Mehrere Gelenke gleichzeitig einstellen

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()
Schritt 3 – Primitive erfassen

Eingebaute Griff-Primitive

orca_core Wird mit kalibrierten Greifgrundelementen für häufige Manipulationsaufgaben geliefert. Dies ist die schnellste Möglichkeit, grundlegende Kenntnisse zu testen, bevor benutzerdefinierte Richtlinien implementiert werden.

Verwendung von Greifprimitiven

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()

Zwischen Griffen interpolieren

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()
Schritt 4 – ROS2-Integration

ROS2-Handschnittstelle

Der orca_ros2 Das Paket bietet eine vollständige ROS2-Schnittstelle für eine koordinierte Arm- und Handsteuerung. Es veröffentlicht gemeinsame Zustände und akzeptiert gemeinsame Flugbahnbefehle.

Installieren Sie 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

Starten Sie den Handtreiberknoten

source ~/orca_ws/install/setup.bash
ros2 launch orca_ros2 orca_hand.launch.py \
  port:=/dev/ttyUSB0 \
  handedness:=right

Abonnieren Sie das gemeinsame Landesthema

ros2 topic echo /orca_hand/joint_states

Gelenkpositionsbefehl senden

ros2 topic pub /orca_hand/joint_command \
  sensor_msgs/msg/JointState \
  '{name: ["index_mcp", "index_pip"], position: [1.22, 1.05]}'

Koordinierter Arm- und Handstart (mit OpenArm)

ros2 launch orca_ros2 openarm_orca.launch.py \
  arm_can_interface:=can0 \
  hand_port:=/dev/ttyUSB0 \
  handedness:=right

Dadurch werden beide gestartet openarm_ros2 Armfahrer und der orca_ros2 Handtreiber unter einem einzigen Namensraum, der eine koordinierte Trajektorienausführung durch MoveIt2 ermöglicht.

Schritt 5 – Taktile Sensoren

Taktile Sensorablesung

Die Orca Hand ist optional mit Fingerspitzen-Tastsensoren (Paxini oder kompatibel) ausgestattet. Taktile Datenströme unabhängig über eine separate USB-Verbindung.

Ablesen der Kontaktkraft der Fingerspitze

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()

Schwellenwert für die Kontakterkennung

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)
Optional – Simulation

MuJoCo-Simulation

Die Orca-Hand wird mit kalibrierten MuJoCo MJCF-Modellen geliefert – linke Hand, rechte Hand und eine bimanuelle Szene. Die Simulation teilt identische Gelenknamen und Aktionsräume mit realer Hardware.

Installieren Sie die Simulation und führen Sie sie aus

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-Übertragung

Gemeinsame Namen im MJCF-Modell stimmen mit überein orca_core SDK genau. Eine in der Simulation von Griffprimitiven trainierte Richtlinie kann direkt auf realer Hardware eingesetzt werden – der einzige Unterschied besteht in der seriellen USB-Latenz (~3 ms) im Vergleich zum physikalischen Schritt-Timing.

Fehlerbehebung

Häufige Probleme

Fehler 1 Einige Finger reagieren nicht – teilweiser Servo-Scan

Normalerweise sitzt ein Daisy-Chain-Kabel nicht vollständig an einer Verbindungsstelle zwischen Fingermodulen. Der STS-Bus ist eine Kette – eine schlechte Verbindung lässt alle nachgeschalteten Servos fallen.

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()
"
Fehler 2 Finger stößt an harte Grenzen – Sehnenüberspannung

Ein Finger kann sich nicht vollständig strecken oder beugen. Die Sehnenführung ist auf einer Seite zu eng. Tritt am häufigsten nach dem Zusammenbau auf.

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
Fehler 3 ROS2 joint_states-Thema wird nicht veröffentlicht

Der orca_ros2-Treiberknoten wurde gestartet, veröffentlicht jedoch keine gemeinsamen Zustände. Normalerweise liegt ein Problem mit der Portberechtigung oder eine widersprüchliche orca_core-Sitzung vor.

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

Funktioniert die Software? Beginnen Sie mit der Datenerfassung.

Sobald sich alle 17 Gelenke bewegen, besteht der nächste Schritt darin, Episoden geschickter Manipulation aufzuzeichnen.