Arm API

The arm API allows you to give commands to your arm components for linear motion planning, including self-collision prevention and obstacle avoidance.

The arm component supports the following methods:

Method NameDescription
GetEndPositionGet the current position of the arm as a pose.
MoveToPositionMove the end of the arm to the desired pose, relative to the base of the arm.
MoveToJointPositionsMove each joint on the arm to the position specified in positions.
GetJointPositionsGet the current position of each joint on the arm.
GetKinematicsGet the kinematics information associated with the arm as the format and byte contents of the kinematics file.
IsMovingGet if the arm is currently moving.
StopStop all motion of the arm.
GetGeometriesGet all the geometries associated with the arm in its current configuration, in the frame of the arm.
ReconfigureReconfigure this resource.
DoCommandExecute model-specific commands that are not otherwise defined by the component API.
GetResourceNameGet the ResourceName for this arm with the given name.
CloseSafely shut down the resource and prevent further use.

Establish a connection

To get started using Viam’s SDKs to connect to and control your machine, go to your machine’s page on the Viam app, navigate to the CONNECT tab’s Code sample page, select your preferred programming language, and copy the sample code.

When executed, this sample code creates a connection to your machine as a client.

The following examples assume you have an arm called "my_arm" configured as a component of your machine. If your arm has a different name, change the name in the code.

Be sure to import the arm package for the SDK you are using:

from viam.components.arm import Arm
# To use move_to_position:
from viam.proto.common import Pose
# To use move_to_joint_positions:
from viam.proto.component.arm import JointPositions
import (
  "go.viam.com/rdk/components/arm"
  // To use MoveToPosition:
  "go.viam.com/rdk/referenceframe"
  "go.viam.com/rdk/spatialmath"
  // To use MoveToJointPositions ("armapi" name optional, but necessary if importing other packages called "v1"):
  armapi "go.viam.com/api/component/arm/v1"
)

API

GetEndPosition

Get the current position of the arm as a pose.

Parameters:

  • extra (Mapping[str, Any]) (optional): Extra options to pass to the underlying RPC call.
  • timeout (float) (optional): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

  • (viam.components.arm.Pose): A representation of the arm’s current position as a 6 DOF (six degrees of freedom) pose. The Pose is composed of values for location and orientation with respect to the origin. Location is expressed as distance, which is represented by x, y, and z coordinate values. Orientation is expressed as an orientation vector, which is represented by o_x, o_y, o_z, and theta values.

Example:

my_arm = Arm.from_robot(robot=machine, name="my_arm")

# Get the end position of the arm as a Pose.
pos = await my_arm.get_end_position()

For more information, see the Python SDK Docs.

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

  • (spatialmath.Pose): A representation of the arm’s current position as a 6 DOF (six degrees of freedom) pose. The Pose is composed of values for location and orientation with respect to the origin. Location is expressed as distance, which is represented by x, y, and z coordinate values. Orientation is expressed as an orientation vector, which is represented by o_x, o_y, o_z, and theta values.
  • (error): An error, if one occurred.

Example:

myArm, err := arm.FromRobot(machine, "my_arm")
// Get the end position of the arm as a Pose.
pos, err := myArm.EndPosition(context.Background(), nil)

For more information, see the Go SDK Docs.

Parameters:

Returns:

Example:

final currentPose = await myArm.endPosition();

For more information, see the Flutter SDK Docs.

MoveToPosition

Move the end of the arm to the desired pose, relative to the base of the arm.

Parameters:

  • pose (viam.components.arm.Pose) (required): The destination Pose for the arm. The Pose is composed of values for location and orientation with respect to the origin. Location is expressed as distance, which is represented by x, y, and z coordinate values. Orientation is expressed as an orientation vector, which is represented by o_x, o_y, o_z, and theta values.
  • extra (Mapping[str, Any]) (optional): Extra options to pass to the underlying RPC call.
  • timeout (float) (optional): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

  • None.

Example:

my_arm = Arm.from_robot(robot=machine, name="my_arm")

# Create a Pose for the arm.
examplePose = Pose(x=5, y=5, z=5, o_x=5, o_y=5, o_z=5, theta=20)

# Move your arm to the Pose.
await my_arm.move_to_position(pose=examplePose)

For more information, see the Python SDK Docs.

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • pose (spatialmath.Pose): A representation of the arm’s destination position as a 6 DOF (six degrees of freedom) pose. The Pose is composed of values for location and orientation with respect to the origin. Location is expressed as distance, which is represented by x, y, and z coordinate values. Orientation is expressed as an orientation vector, which is represented by o_x, o_y, o_z, and theta values.
  • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

  • (error): An error, if one occurred.

Example:

myArm, err := arm.FromRobot(machine, "my_arm")
// Create a Pose for the arm.
examplePose := spatialmath.NewPose(
        r3.Vector{X: 5, Y: 5, Z: 5},
        &spatialmath.OrientationVectorDegrees{OX: 5, OY: 5, Theta: 20},
)

// Move your arm to the Pose.
err = myArm.MoveToPosition(context.Background(), examplePose, nil)

For more information, see the Go SDK Docs.

Parameters:

Returns:

Example:

// Create a pose for the arm to move to
final targetPose = Pose.fromBuffer([12, 0, 400, 0, 0, 1, 90]);

// Move the arm to the pose
await myArm.moveToPosition(targetPose);

For more information, see the Flutter SDK Docs.

MoveToJointPositions

Move each joint on the arm to the position specified in positions.

Parameters:

  • positions (viam.proto.component.arm.JointPositions) (required): The destination JointPositions for the arm.
  • extra (Mapping[str, Any]) (optional): Extra options to pass to the underlying RPC call.
  • timeout (float) (optional): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

  • None.

Example:

my_arm = Arm.from_robot(robot=machine, name="my_arm")

# Declare a list of values with your desired rotational value for each joint on
# the arm. This example is for a 5dof arm.
degrees = [0.0, 45.0, 0.0, 0.0, 0.0]

# Declare a new JointPositions with these values.
jointPos = JointPositions(values=degrees)

# Move each joint of the arm to the position these values specify.
await my_arm.move_to_joint_positions(positions=jointPos)

For more information, see the Python SDK Docs.

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • positionDegs (*pb.JointPositions): The desired position of each joint of the arm at the end of movement. JointPositions can have one attribute, values, a list of joint positions with rotational values (degrees) and translational values (mm).
  • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

  • (error): An error, if one occurred.

Example:

// Assumes you have imported "go.viam.com/api/component/arm/v1" as `componentpb`
myArm, err := arm.FromRobot(machine, "my_arm")

// Declare an array of values with your desired rotational value for each joint on the arm.
degrees := []float64{4.0, 5.0, 6.0}

// Declare a new JointPositions with these values.
jointPos := &componentpb.JointPositions{Values: degrees}

// Move each joint of the arm to the position these values specify.
err = myArm.MoveToJointPositions(context.Background(), jointPos, nil)

For more information, see the Go SDK Docs.

Parameters:

Returns:

Example:

// Create a list of joint angles for each arm joint
List<double> targetPositions = [180, 90, 15.75, 30, 90, 0];

// Move the arm joints to those angles
await myArm.moveToJointPositions(targetPositions);

For more information, see the Flutter SDK Docs.

GetJointPositions

Get the current position of each joint on the arm.

Parameters:

  • extra (Mapping[str, Any]) (optional): Extra options to pass to the underlying RPC call.
  • timeout (float) (optional): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

  • (viam.proto.component.arm.JointPositions): The current JointPositions for the arm. JointPositions can have one attribute, values, a list of joint positions with rotational values (degrees) and translational values (mm).

Example:

my_arm = Arm.from_robot(robot=machine, name="my_arm")

# Get the current position of each joint on the arm as JointPositions.
pos = await my_arm.get_joint_positions()

For more information, see the Python SDK Docs.

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

Example:

myArm , err := arm.FromRobot(machine, "my_arm")

// Get the current position of each joint on the arm as JointPositions.
pos, err := myArm.JointPositions(context.Background(), nil)

For more information, see the Go SDK Docs.

Parameters:

Returns:

Example:

List<double> currentJointPositions = await myArm.moveToJointPosition();

For more information, see the Flutter SDK Docs.

GetKinematics

Get the kinematics information associated with the arm as the format and byte contents of the kinematics file.

Parameters:

  • extra (Mapping[str, Any]) (optional): Extra options to pass to the underlying RPC call.
  • timeout (float) (optional): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

  • (Tuple[KinematicsFileFormat.ValueType, bytes]): A tuple containing two values; the first [0] value represents the format of the file, either in URDF format (KinematicsFileFormat.KINEMATICS_FILE_FORMAT_URDF) or Viam’s kinematic parameter format (spatial vector algebra) (KinematicsFileFormat.KINEMATICS_FILE_FORMAT_SVA), and the second [1] value represents the byte contents of the file.

Example:

my_arm = Arm.from_robot(robot=machine, name="my_arm")

# Get the kinematics information associated with the arm.
kinematics = await my_arm.get_kinematics()

# Get the format of the kinematics file.
k_file = kinematics[0]

# Get the byte contents of the file.
k_bytes = kinematics[1]

For more information, see the Python SDK Docs.

IsMoving

Get if the arm is currently moving.

Parameters:

  • timeout (float) (optional): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

  • (bool): Whether the arm is moving.

Example:

my_arm = Arm.from_robot(robot=machine, name="my_arm")

# Stop all motion of the arm. It is assumed that the arm stops immediately.
await my_arm.stop()

# Print if the arm is currently moving.
print(await my_arm.is_moving())

For more information, see the Python SDK Docs.

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.

Returns:

  • (bool): Whether this resource is moving (true) or not (false).
  • (error): An error, if one occurred.

Example:

// This example shows using IsMoving with an arm component.
myArm, err := arm.FromRobot(machine, "my_arm")

// Stop all motion of the arm. It is assumed that the arm stops immediately.
myArm.Stop(context.Background(), nil)

// Log if the arm is currently moving.
is_moving, err := myArm.IsMoving(context.Background())
logger.Info(is_moving)

For more information, see the Go SDK Docs.

Parameters:

  • None.

Returns:

Example:

bool isArmMoving = await myArm.isMoving();

For more information, see the Flutter SDK Docs.

Stop

Stop all motion of the arm.

Parameters:

  • extra (Mapping[str, Any]) (optional): Extra options to pass to the underlying RPC call.
  • timeout (float) (optional): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

  • None.

Example:

my_arm = Arm.from_robot(robot=machine, name="my_arm")

# Stop all motion of the arm. It is assumed that the arm stops immediately.
await my_arm.stop()

For more information, see the Python SDK Docs.

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

  • (error): An error, if one occurred.

Example:

// This example shows using Stop with an arm component.
myArm, err := arm.FromRobot(machine, "my_arm")

// Stop all motion of the arm. It is assumed that the arm stops immediately.
err = myArm.Stop(context.Background(), nil)

For more information, see the Go SDK Docs.

Parameters:

Returns:

Example:

await myArm.stop();

For more information, see the Flutter SDK Docs.

GetGeometries

Get all the geometries associated with the arm in its current configuration, in the frame of the arm. The motion and navigation services use the relative position of inherent geometries to configured geometries representing obstacles for collision detection and obstacle avoidance while motion planning.

Parameters:

  • extra (Mapping[str, Any]) (optional): Extra options to pass to the underlying RPC call.
  • timeout (float) (optional): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

Example:

geometries = await my_arm.get_geometries()

if geometries:
    # Get the center of the first geometry
    print(f"Pose of the first geometry's centerpoint: {geometries[0].center}")

For more information, see the Python SDK Docs.

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

Example:

// This example shows using Geometries with an arm component.
myArm, err := arm.FromRobot(machine, "my_arm")

geometries, err := myArm.Geometries(context.Background(), nil)

if len(geometries) > 0 {
   // Get the center of the first geometry
   elem := geometries[0]
   fmt.Println("Pose of the first geometry's center point:", elem.Pose())
}

For more information, see the Go SDK Docs.

Reconfigure

Reconfigure this resource. Reconfigure must reconfigure the resource atomically and in place.

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • deps (Dependencies): The resource dependencies.
  • conf (Config): The resource configuration.

Returns:

  • (error): An error, if one occurred.

For more information, see the Go SDK Docs.

DoCommand

Execute model-specific commands that are not otherwise defined by the component API. For built-in models, model-specific commands are covered with each model’s documentation. If you are implementing your own arm and add features that have no built-in API method, you can access them with DoCommand.

Parameters:

  • command (Mapping[str, ValueTypes]) (required): The command to execute.
  • timeout (float) (optional): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

  • (Mapping[str, viam.utils.ValueTypes]): Result of the executed command.

Raises:

  • (NotImplementedError): Raised if the Resource does not support arbitrary commands.

Example:

command = {"cmd": "test", "data1": 500}
result = await my_arm.do_command(command)

For more information, see the Python SDK Docs.

Parameters:

Returns:

Example:

myArm, err := arm.FromRobot(machine, "my_arm")

command := map[string]interface{}{"cmd": "test", "data1": 500}
result, err := myArm.DoCommand(context.Background(), command)

For more information, see the Go SDK Docs.

Parameters:

Returns:

Example:

// Example using doCommand with an arm component
const command = {'cmd': 'test', 'data1': 500};
var result = myArm.doCommand(command);

For more information, see the Flutter SDK Docs.

GetResourceName

Get the ResourceName for this arm with the given name.

Parameters:

  • name (str) (required): The name of the Resource.

Returns:

Example:

my_arm_name = Arm.get_resource_name("my_arm")

For more information, see the Python SDK Docs.

Parameters:

Returns:

For more information, see the Flutter SDK Docs.

Close

Safely shut down the resource and prevent further use.

Parameters:

  • None.

Returns:

  • None.

Example:

await my_arm.close()

For more information, see the Python SDK Docs.

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.

Returns:

  • (error): An error, if one occurred.

Example:

myArm, err := arm.FromRobot(machine, "my_arm")

err = myArm.Close(context.Background())

For more information, see the Go SDK Docs.

Have questions, or want to meet other people working on robots? Join our Community Discord.

If you notice any issues with the documentation, feel free to file an issue or edit this file.