Move an arm by setting joint positions
Cartesian motion asks “what pose should the end effector reach?” and lets the planner pick the joint angles that get there. Joint-space motion asks “what configuration should the arm be in?” and skips the planner entirely. The two are different tools. You reach for joint-space when:
- You already know the joint angles (from a previous capture, a teach-pendant run, or a saved configuration).
- You want to avoid the planner picking an unexpected IK solution that causes a wrist flip or elbow reconfiguration.
- You want predictable motion between two configurations you both control.
- You are building a control loop that computes its own joint targets.
A caveat before you dive in. Joint-space moves bypass the motion planner. No obstacle avoidance, no constraint satisfaction, no path smoothing. If the commanded configuration makes the arm swing through the table or your workspace fixture, the arm will swing through the table. Joint-space is for configurations you have already verified safe.
Before you start
- A configured arm component and an SDK client.
- You know the joint angles you want. For a 6-DOF arm, this is six values; for a 7-DOF arm, seven; and so on.
- You have verified the target is within joint limits. The arm’s kinematics file declares per-joint min and max; values outside the limits produce an error.
MoveToJointPositions
Drives every joint to a single target configuration in one call. Blocks until done or cancelled.
from viam.components.arm import Arm
from viam.proto.component.arm import JointPositions
my_arm = Arm.from_robot(machine, "my-arm")
# Joint angles in degrees. Revolute joint values are degrees;
# prismatic joint values are millimeters.
positions = JointPositions(values=[0, -45, 90, 0, 45, 0])
await my_arm.move_to_joint_positions(positions)
import (
"math"
"go.viam.com/rdk/components/arm"
"go.viam.com/rdk/referenceframe"
)
myArm, err := arm.FromProvider(machine, "my-arm")
if err != nil {
logger.Fatal(err)
}
// Go's Input type is an alias for float64, storing radians for revolute joints.
targets := []referenceframe.Input{
0,
-math.Pi / 4, // -45 degrees
math.Pi / 2, // 90 degrees
0,
math.Pi / 4, // 45 degrees
0,
}
if err := myArm.MoveToJointPositions(ctx, targets, nil); err != nil {
logger.Fatal(err)
}
Units: Python uses degrees, Go uses radians
This is the single most common source of joint-position bugs in Viam arm
code. The proto wire format and the Python SDK use degrees for revolute
joints and millimeters for prismatic joints. The Go SDK uses
referenceframe.Input, which stores radians for revolute joints. Conversion
happens at the wire boundary, so Python values of 90 and Go values of
math.Pi / 2 both command the same angle.
MoveThroughJointPositions
Drives the arm through a sequence of joint configurations in order,
with optional per-motion velocity and acceleration limits through
MoveOptions.
SDK availability
MoveThroughJointPositions is available in the Go SDK and through
the proto, but is not currently exposed by the Python SDK. Python
callers who need the same behavior must call each waypoint with
move_to_joint_positions in sequence.
import (
"math"
"go.viam.com/rdk/components/arm"
"go.viam.com/rdk/referenceframe"
)
waypoints := [][]referenceframe.Input{
{0, -math.Pi / 4, math.Pi / 2, 0, math.Pi / 4, 0},
{0, 0, math.Pi / 2, 0, 0, 0},
{0, math.Pi / 4, 0, 0, -math.Pi / 4, 0},
}
// Go MoveOptions uses radians per second. The proto wire format uses
// degrees, but the SDK field names and values are in radians.
options := &arm.MoveOptions{
MaxVelRads: 30.0 * math.Pi / 180, // Cap every joint at 30 deg/s.
MaxAccRads: 60.0 * math.Pi / 180, // Cap every joint at 60 deg/s^2.
}
if err := myArm.MoveThroughJointPositions(ctx, waypoints, options, nil); err != nil {
logger.Fatal(err)
}
The Python SDK does not expose MoveThroughJointPositions. Use a loop
with move_to_joint_positions for the equivalent behavior:
from viam.components.arm import Arm
from viam.proto.component.arm import JointPositions
my_arm = Arm.from_robot(machine, "my-arm")
waypoints = [
JointPositions(values=[0, -45, 90, 0, 45, 0]),
JointPositions(values=[0, 0, 90, 0, 0, 0]),
JointPositions(values=[0, 45, 0, 0, -45, 0]),
]
for wp in waypoints:
await my_arm.move_to_joint_positions(wp)
Without MoveOptions you cannot cap velocity or acceleration per call
from Python; the arm uses its module’s default speed profile.
MoveOptions fields
| Field | Type | Description |
|---|---|---|
max_vel_degs_per_sec | double (optional) | Uniform velocity cap across every joint, in degrees per second. |
max_acc_degs_per_sec2 | double (optional) | Uniform acceleration cap across every joint, in degrees per second squared. |
max_vel_degs_per_sec_joints | []double (repeated) | Per-joint velocity caps. Length must match the arm’s degrees of freedom. Overrides the uniform cap when set. |
max_acc_degs_per_sec2_joints | []double (repeated) | Per-joint acceleration caps. Length must match the arm’s degrees of freedom. Overrides the uniform cap when set. |
Per-joint fields take precedence over global fields. Pass nil
options to use the module’s default motion profile.
The field names above are the proto field names, also used by the Python
SDK. The Go SDK arm.MoveOptions struct uses shorter names and stores
values in radians: MaxVelRads, MaxAccRads, MaxVelRadsJoints,
MaxAccRadsJoints. The conversion happens at the wire boundary.
Reading current joint positions
Use GetJointPositions to capture the arm’s current configuration
before commanding a new one:
current = await my_arm.get_joint_positions()
print([v for v in current.values])
current, err := myArm.JointPositions(ctx, nil)
if err != nil {
logger.Fatal(err)
}
logger.Infof("joint positions (radians): %v", current)
Pair GetJointPositions with MoveToJointPositions to capture a pose
by hand (teach-by-demonstration) and replay it programmatically.
Joint-space moves compared to motion.Move
| Motion path | Use when |
|---|---|
arm.MoveToJointPositions | You know the joint angles you want. |
arm.MoveThroughJointPositions (Go) | You have a sequence of joint targets and want per-call velocity or acceleration caps. |
arm.MoveToPosition | You have a Cartesian target pose but don’t need obstacle avoidance. |
motion.Move | You have a Cartesian target and want obstacle avoidance, constraints, and IK picked by the planner. |
Joint-space moves are the right call when you need to control the posture of the arm precisely. They do not protect against collisions with obstacles, the environment, or the arm’s own body beyond what the arm module itself enforces.
Troubleshooting
What’s next
- Move an arm to a pose:
Cartesian motion with obstacle avoidance through
motion.Move. - Move with constraints: Cartesian motion with linear or orientation constraints.
- Arm kinematics: the kinematic file that declares joint limits.
- Motion service API: the alternative path through the motion service for Cartesian moves.
Was this page helpful?
Glad to hear it! If you have any other feedback please let us know:
We're sorry about that. To help us improve, please tell us what we can do better:
Thank you!