viam.components.arm.client

Classes

ArmClient

gRPC client for an Arm component.

Module Contents

class viam.components.arm.client.ArmClient(name: str, channel: grpclib.client.Channel)[source]

Bases: viam.components.arm.Arm, viam.resource.rpc_client_base.ReconfigurableResourceRPCClientBase

gRPC client for an Arm component.

Used to communicate with an existing Arm implementation over gRPC.

channel
client
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=machine, name="my_arm")

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

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.

Return type:

Pose

For more information, see Arm component.

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=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)
Parameters:

pose (Pose) – 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.

For more information, see Arm component.

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

Get the JointPositions representing the current position of the arm.

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()
Returns:

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).

Return type:

JointPositions

For more information, see Arm component.

async move_to_joint_positions(positions: viam.proto.component.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=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)
Parameters:

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

For more information, see Arm component.

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=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 Arm component.

async is_moving(*, timeout: float | None = None, **kwargs) bool[source]

Get if the arm is currently moving.

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())
Returns:

Whether the arm is moving.

Return type:

bool

For more information, see Arm component.

async do_command(command: Mapping[str, Any], *, timeout: float | None = None, **kwargs) Mapping[str, viam.utils.ValueTypes][source]

Send/Receive arbitrary commands to the Resource

command = {"cmd": "test", "data1": 500}
result = await component.do_command(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_kinematics(*, extra: Dict[str, Any] | None = None, timeout: float | None = None, **kwargs) Tuple[viam.components.arm.KinematicsFileFormat.ValueType, bytes][source]

Get the kinematics information associated with the arm.

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]
Returns:

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.

Return type:

Tuple[KinematicsFileFormat.ValueType, bytes]

For more information, see Arm component.

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

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 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

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 = Arm.get_resource_name("my_arm")
Parameters:

name (str) – The name of the Resource

Returns:

The ResourceName of this Resource

Return type:

ResourceName

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()