Configuração do Software
instalação do SDK orca_core, configuração do driver USB, API de controle de dedos individuais, interface de mão ROS2, leitura de sensor tátil e simulação MuJoCo. Desde uma instalação nova do Python até todos os 17 articulações se movendo.
Ir para uma seção:
Instalação do SDK orca_core
orca_core é o SDK oficial Python para a Mão Orca. É instalável via pip e suporta Python 3.9+. Não é necessário ROS para controle básico de articulações.
Crie um ambiente virtual
python -m venv ~/.venvs/orca
source ~/.venvs/orca/bin/activate # Windows: .venvs\orca\Scripts\activate
Instalar via pip
pip install orca-core
Instalar via Poetry (recomendado para desenvolvimento)
git clone https://github.com/orcahand/orca_core.git
cd orca_core
poetry install
Verificar instalação e encontrar sua mão
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)
"
Controle de Dedo Individual
A OrcaHand classe expõe todas as 17 articulações via acessores nomeados de dedo e articulação. O modo de controle padrão é current_based_position.
Conectar e ler todas as posições das articulações
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()
Mover articulações individuais
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()
Definir várias articulações simultaneamente
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()
Primitivas de Apreensão Integradas
orca_core vem com primitivas de apreensão calibradas para tarefas comuns de manipulação. Estas são a maneira mais rápida de testar a apreensão básica antes de implementar políticas personalizadas.
Usando primitivas de apreensão
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()
Interpolar entre apreensões
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()
Interface de Mão ROS2
A orca_ros2 pacote fornece uma interface completa ROS2 para controle coordenado de braço + mão. Publica estados das articulações e aceita comandos de trajetória das articulações.
Instalar 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
Iniciar o nó do driver da mão
source ~/orca_ws/install/setup.bash
ros2 launch orca_ros2 orca_hand.launch.py \
port:=/dev/ttyUSB0 \
handedness:=right
Inscrever-se no tópico de estado das articulações
ros2 topic echo /orca_hand/joint_states
Enviar comando de posição conjunta
ros2 topic pub /orca_hand/joint_command \
sensor_msgs/msg/JointState \
'{name: ["index_mcp", "index_pip"], position: [1.22, 1.05]}'
Lançamento coordenado de braço + mão (com OpenArm)
ros2 launch orca_ros2 openarm_orca.launch.py \
arm_can_interface:=can0 \
hand_port:=/dev/ttyUSB0 \
handedness:=right
Isso lança tanto o openarm_ros2 driver do braço quanto o orca_ros2 driver da mão sob um único namespace, permitindo a execução coordenada de trajetórias através do MoveIt2.
Leitura do Sensor Táctil
A Mão Orca opcionalmente monta sensores táctiles na ponta dos dedos (Paxini ou compatíveis). Os dados táctiles fluem independentemente por uma conexão USB separada.
Lendo a força de contato da ponta do dedo
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()
Limite de detecção de contato
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)
Simulação MuJoCo
A Mão Orca é enviada com modelos MuJoCo MJCF calibrados — mão esquerda, mão direita e uma cena bimanual. A simulação compartilha nomes de juntas e espaços de ação idênticos ao hardware real.
Instalar e executar a simulação
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()
"
Transferência de simulação para o real
Os nomes das juntas no modelo MJCF correspondem exatamente ao orca_core SDK. Uma política treinada em simulação em primitivas de preensão pode ser implantada diretamente no hardware real — a única diferença é a latência serial USB (~3ms) em comparação com o tempo de passo da física.
Problemas Comuns
Geralmente, um cabo em cadeia não está totalmente encaixado em uma junção entre os módulos dos dedos. O barramento STS é uma cadeia — uma conexão ruim derruba todos os servos a jusante.
Correção:
# 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()
"
Um dedo não pode se estender ou flexionar completamente. O roteamento do tendão está muito apertado de um lado. Ocorre mais comumente após a remontagem.
Correção:
# 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
O nó do driver orca_ros2 foi iniciado, mas não está publicando estados das juntas. Normalmente, é um problema de permissão de porta ou uma sessão conflitante do orca_core.
Correção:
# 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