Arm

class pyrobot.robots.arm.Arm(configs, ns='')[source]

Bases: object

This is a parent class on which the robot specific Arm classes would be built.

__init__(configs, ns='')[source]

Constructor for Arm parent class.

Parameters

configs – configurations for arm

get_joint_angle(joint)[source]

Return the joint angle of the ‘joint’

Parameters

joint (string) – joint name

Returns

joint angle

Return type

float

get_joint_angles()[source]

Return the joint angles

Returns

joint_angles

Return type

np.ndarray

get_joint_torque(joint)[source]

Return the joint torque of the ‘joint’

Parameters

joint (string) – joint name

Returns

joint torque

Return type

float

get_joint_torques()[source]

Return the joint torques

Returns

joint_torques

Return type

np.ndarray

get_joint_velocities()[source]

Return the joint velocities

Returns

joint_vels

Return type

np.ndarray

get_joint_velocity(joint)[source]

Return the joint velocity of the ‘joint’

Parameters

joint (string) – joint name

Returns

joint velocity

Return type

float

abstract go_home()[source]

Reset robot to default home position

set_joint_positions(positions, wait=True, **kwargs)[source]

Sets the desired joint angles for all arm joints

Parameters
  • positions (list) – list of length #of joints, angles in radians

  • plan (bool) – whether to use moveit to plan a path. Without planning, there is no collision checking and each joint will move to its target joint position directly.

  • wait (bool) – if True, it will wait until the desired joint positions are achieved

Returns

True if successful; False otherwise (timeout, etc.)

Return type

bool

set_joint_torques(torques, **kwargs)[source]

Sets the desired joint torques for all arm joints

Parameters

torques (list) – target joint torques

set_joint_velocities(velocities, **kwargs)[source]

Sets the desired joint velocities for all arm joints

Parameters

velocities (list) – target joint velocities