Move an arm to a target pose
A robot arm needs to reach a specific position and orientation in 3D space, but joint angles alone do not tell you whether the end effector ends up where you want it, and a naive joint trajectory may swing through the table or the back wall. The motion service takes a target pose, solves inverse kinematics, and returns a collision-free path that respects the frame system and any obstacles you declare.
Prerequisites
- A running machine connected to Viam with an arm component configured
- Frame system configured for the arm
- (Optional) Obstacles defined for collision avoidance
Steps
1. Connect and get the motion service
from viam.robot.client import RobotClient
from viam.services.motion import MotionClient
from viam.proto.common import PoseInFrame, Pose
machine = await RobotClient.at_address(
"<MACHINE-ADDRESS>",
RobotClient.Options.with_api_key(
api_key="<API-KEY>",
api_key_id="<API-KEY-ID>"
)
)
motion_service = MotionClient.from_robot(machine, "builtin")
import (
"go.viam.com/rdk/services/motion"
"go.viam.com/rdk/referenceframe"
"go.viam.com/rdk/spatialmath"
"github.com/golang/geo/r3"
)
motionService, err := motion.FromProvider(machine, "builtin")
if err != nil {
logger.Fatal(err)
}
2. Define the target pose
A target pose has two parts: a position in millimeters and an orientation
vector. Which coordinate system those numbers live in depends on
reference_frame, so always set it explicitly. "world" puts the target in the
fixed world frame; "my-arm" puts it relative to the arm’s base.
# Move to a position 300mm right, 200mm forward, 400mm up
# Orientation: end effector pointing straight down
destination = PoseInFrame(
reference_frame="world",
pose=Pose(x=300, y=200, z=400, o_x=0, o_y=0, o_z=-1, theta=0)
)
// Move to a position 300mm right, 200mm forward, 400mm up
// Orientation: end effector pointing straight down
destination := referenceframe.NewPoseInFrame("world",
spatialmath.NewPose(
r3.Vector{X: 300, Y: 200, Z: 400},
&spatialmath.OrientationVectorDegrees{OX: 0, OY: 0, OZ: -1, Theta: 0},
))
3. Move the arm
await motion_service.move(
component_name="my-arm",
destination=destination,
)
print("Arm moved to target pose")
_, err = motionService.Move(ctx, motion.MoveReq{
ComponentName: "my-arm",
Destination: destination,
})
if err != nil {
logger.Fatal(err)
}
fmt.Println("Arm moved to target pose")
4. Move with obstacle avoidance
To make the planner avoid things in the workspace, pass a WorldState that
lists them. The planner checks every frame in the scene against every obstacle
you include.
from viam.proto.common import (
Vector3, RectangularPrism, Geometry,
GeometriesInFrame, WorldState
)
# Define a table obstacle
table = Geometry(
center=Pose(x=0, y=0, z=-20),
box=RectangularPrism(dims_mm=Vector3(x=800, y=600, z=40)),
label="table"
)
obstacles = GeometriesInFrame(
reference_frame="world",
geometries=[table]
)
world_state = WorldState(obstacles=[obstacles])
await motion_service.move(
component_name="my-arm",
destination=destination,
world_state=world_state
)
tableOrigin := spatialmath.NewPose(
r3.Vector{X: 0, Y: 0, Z: -20},
&spatialmath.OrientationVectorDegrees{OX: 0, OY: 0, OZ: 1, Theta: 0},
)
table, _ := spatialmath.NewBox(tableOrigin,
r3.Vector{X: 800, Y: 600, Z: 40}, "table")
obstaclesInFrame := referenceframe.NewGeometriesInFrame(
referenceframe.World, []spatialmath.Geometry{table})
worldState, _ := referenceframe.NewWorldState(
[]*referenceframe.GeometriesInFrame{obstaclesInFrame}, nil)
_, err = motionService.Move(ctx, motion.MoveReq{
ComponentName: "my-arm",
Destination: destination,
WorldState: worldState,
})
if err != nil {
logger.Fatal(err)
}
5. Verify the result
Read the arm’s current pose after moving to confirm it reached the target:
from viam.components.arm import Arm
arm = Arm.from_robot(machine, "my-arm")
current_pose = await arm.get_end_position()
print(f"Current position: x={current_pose.x:.1f}, "
f"y={current_pose.y:.1f}, z={current_pose.z:.1f}")
import "go.viam.com/rdk/components/arm"
myArm, err := arm.FromProvider(machine, "my-arm")
if err != nil {
logger.Fatal(err)
}
currentPose, err := myArm.EndPosition(ctx, nil)
if err != nil {
logger.Fatal(err)
}
pt := currentPose.Point()
fmt.Printf("Current position: x=%.1f, y=%.1f, z=%.1f\n",
pt.X, pt.Y, pt.Z)
Test from the command line
You can move the arm and check poses without writing code:
# Check the arm's current pose
viam machines part motion get-pose --part "my-machine-main" --component "my-arm"
# Move the arm to a new position (only specified values change)
viam machines part motion set-pose --part "my-machine-main" --component "my-arm" \
--x 300 --y 200 --z 400
Troubleshooting
What’s next
- Move with Constraints: keep the end effector on a straight line or at a fixed orientation.
- Avoid Obstacles: detailed obstacle configuration for complex workspaces.
- Pick an Object: combine motion planning with vision and gripper control.
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!