viam.components.arm

Submodules

Package Contents

Classes

KinematicsFileFormat

Pose

Pose is a combination of location and orientation.

JointPositions

Abstract base class for protocol messages.

Arm

Arm represents a physical robot arm that exists in three-dimensional space.

class viam.components.arm.KinematicsFileFormat

Bases: _KinematicsFileFormat

class viam.components.arm.Pose(*, x: float = ..., y: float = ..., z: float = ..., o_x: float = ..., o_y: float = ..., o_z: float = ..., theta: float = ...)

Bases: google.protobuf.message.Message

Pose is a combination of location and orientation. Location is expressed as distance which is represented by x , y, z coordinates. Orientation is expressed as an orientation vector which is represented by o_x, o_y, o_z and theta. The o_x, o_y, o_z coordinates represent the point on the cartesian unit sphere that the end of the arm is pointing to (with the origin as reference). That unit vector forms an axis around which theta rotates. This means that incrementing / decrementing theta will perform an inline rotation of the end effector. Theta is defined as rotation between two planes: the first being defined by the origin, the point (0,0,1), and the rx, ry, rz point, and the second being defined by the origin, the rx, ry, rz point and the local Z axis. Therefore, if theta is kept at zero as the north/south pole is circled, the Roll will correct itself to remain in-line.

x: float

millimeters from the origin

y: float

millimeters from the origin

z: float

millimeters from the origin

o_x: float

z component of a vector defining axis of rotation

o_y: float

x component of a vector defining axis of rotation

o_z: float

y component of a vector defining axis of rotation

theta: float

degrees

class viam.components.arm.JointPositions(*, values: collections.abc.Iterable[float] | None = ...)

Bases: google.protobuf.message.Message

Abstract base class for protocol messages.

Protocol message classes are almost always generated by the protocol compiler. These generated types subclass Message and implement the methods shown below.

property values: google.protobuf.internal.containers.RepeatedScalarFieldContainer[float]

A list of joint positions. Rotations values are in degrees, translational values in mm. The numbers are ordered spatially from the base toward the end effector This is used in GetJointPositionsResponse and MoveToJointPositionsRequest

class viam.components.arm.Arm(name: str)[source]

Bases: viam.components.component_base.ComponentBase

Arm represents a physical robot arm that exists in three-dimensional space.

This acts as an abstract base class for any drivers representing specific arm implementations. This cannot be used on its own. If the __init__() function is overridden, it must call the super().__init__() function.

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
SUBTYPE: Final
abstract async get_end_position(*, extra: Dict[str, Any] | None = None, timeout: float | None = None, **kwargs) viam.components.arm.Pose[source]

Get the current position of the end of the arm expressed as a Pose.

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

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

The location and orientation of the arm described as a Pose.

Return type:

Pose

abstract async move_to_position(pose: viam.components.arm.Pose, *, extra: Dict[str, Any] | None = None, timeout: float | None = None, **kwargs)[source]

Move the end of the arm to the Pose specified in pose.

my_arm = Arm.from_robot(robot=robot, 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)
Parameters:

pose (Pose) – The destination Pose for the arm.

abstract async move_to_joint_positions(positions: viam.components.arm.JointPositions, *, extra: Dict[str, Any] | None = None, timeout: float | None = None, **kwargs)[source]

Move each joint on the arm to the corresponding angle specified in positions.

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

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

# Declare a new JointPositions with these values.
jointPos = arm.move_to_joint_positions(
    JointPositions(values=[0.0, 45.0, 0.0, 0.0, 0.0]))

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

positions (JointPositions) – The destination JointPositions for the arm.

abstract async get_joint_positions(*, extra: Dict[str, Any] | None = None, timeout: float | None = None, **kwargs) viam.components.arm.JointPositions[source]

Get the JointPositions representing the current position of the arm.

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

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

The current JointPositions for the arm.

Return type:

JointPositions

abstract async stop(*, extra: Dict[str, Any] | None = None, timeout: float | None = None, **kwargs)[source]

Stop all motion of the arm. It is assumed that the arm stops immediately.

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

# Stop all motion of the arm. It is assumed that the arm stops immediately.
await my_arm.stop()
abstract async is_moving() bool[source]

Get if the arm is currently moving.

my_arm = Arm.from_robot(robot=robot, 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(my_arm.is_moving())
Returns:

Whether the arm is moving.

Return type:

bool

abstract async get_kinematics(*, extra: Dict[str, Any] | None = None, timeout: float | None = None) Tuple[viam.components.arm.KinematicsFileFormat.ValueType, bytes][source]

Get the kinematics information associated with the arm.

my_arm = Arm.from_robot(robot=robot, 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]
Returns:

  • KinematicsFileFormat.ValueType: The format of the file, either in URDF format or Viam’s kinematic parameter format (spatial vector algebra).

  • bytes: The byte contents of the file.

Return type:

Tuple[KinematicsFileFormat.ValueType, bytes]

classmethod from_robot(robot: viam.robot.client.RobotClient, name: str) typing_extensions.Self

Get the component named name from the provided robot.

Parameters:
  • robot (RobotClient) – The robot

  • name (str) – The name of the component

Returns:

The component, if it exists on the robot

Return type:

Self

abstract async do_command(command: Mapping[str, ValueTypes], *, timeout: float | None = None, **kwargs) Mapping[str, ValueTypes]

Send/Receive arbitrary commands to the Resource

command = {"cmd": "test", "data1": 500}
result = component.do(command)
Parameters:

command (Mapping[str, ValueTypes]) – The command to execute

Raises:

NotImplementedError – Raised if the Resource does not support arbitrary commands

Returns:

Result of the executed command

Return type:

Mapping[str, ValueTypes]

async get_geometries(*, extra: Dict[str, Any] | None = None, timeout: float | None = None) List[viam.proto.common.Geometry]

Get all geometries associated with the Component, in their current configuration, in the frame of the Component.

geometries = await component.get_geometries()

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

The geometries associated with the Component.

Return type:

List[Geometry]

classmethod get_resource_name(name: str) viam.proto.common.ResourceName

Get the ResourceName for this Resource with the given name

# Can be used with any resource, using an arm as an example
my_arm_name = my_arm.get_resource_name("my_arm")
Parameters:

name (str) – The name of the Resource

get_operation(kwargs: Mapping[str, Any]) viam.operations.Operation

Get the Operation associated with the currently running function.

When writing custom resources, you should get the Operation by calling this function and check to see if it’s cancelled. If the Operation is cancelled, then you can perform any necessary (terminating long running tasks, cleaning up connections, etc. ).

Parameters:

kwargs (Mapping[str, Any]) – The kwargs object containing the operation

Returns:

The operation associated with this function

Return type:

viam.operations.Operation

async close()

Safely shut down the resource and prevent further use.

Close must be idempotent. Later configuration may allow a resource to be “open” again. If a resource does not want or need a close function, it is assumed that the resource does not need to return errors when future non-Close methods are called.

await component.close()