Skip to main content
A draggable 3D gizmo (powered by drei’s PivotControls) that drives inverse kinematics. Drag the gizmo to move the robot’s end-effector. Requires a controller from useIkController().

Usage

import { useIkController, IkGizmo } from "mujoco-react";

function MyScene() {
  const ik = useIkController({ siteName: "tcp", numJoints: 7 });

  return ik ? <IkGizmo controller={ik} /> : null;
}

Custom Site

Override the site tracked by this gizmo (defaults to the controller’s siteName):
<IkGizmo controller={ik} siteName="left_hand" scale={0.25} />

Custom Drag Handler

<IkGizmo
  controller={ik}
  onDrag={(pos, quat) => {
    // Consumer handles the response — IK is NOT auto-enabled
    console.log("Target:", pos, quat);
  }}
/>

Props

controller
IkContextValue
required
The IK controller value returned by useIkController().
siteName
string
default:"controller's siteName"
MuJoCo site to track. Defaults to the useIkController config’s site.
scale
number
default:"0.18"
Visual scale of the gizmo handles.
onDrag
(pos: THREE.Vector3, quat: THREE.Quaternion) => void
Custom drag callback. When provided, the gizmo does not automatically enable IK — the consumer is responsible for handling the drag.

Behavior

When not dragging:
  • The gizmo tracks the MuJoCo site’s world position and orientation each frame
  • It “follows” the end-effector as the robot moves
When dragging (no onDrag prop):
  • IK is automatically enabled via controller.setIkEnabled(true)
  • The gizmo’s position/orientation is written to the IK target
  • The IK solver runs each frame to compute joint angles
  • OrbitControls are disabled during drag
When dragging (with onDrag prop):
  • The onDrag callback fires with position and quaternion
  • IK is NOT automatically enabled — the consumer decides what to do
  • OrbitControls are disabled during drag

Programmatic Control

Use the controller value from useIkController():
const ik = useIkController({ siteName: "tcp", numJoints: 7 });

// Animate the gizmo to a position over 500ms
ik?.moveTarget(new THREE.Vector3(0.5, 0, 0.3), 500);

// Snap the gizmo to current site position
ik?.syncTargetToSite();

// Enable/disable IK solving
ik?.setIkEnabled(true);

Notes

  • Requires a controller prop from useIkController()
  • The IK solver respects numJoints from the controller config
  • Disable IK with controller.setIkEnabled(false) when using custom control (e.g., useBeforePhysicsStep)