airobot.arm.arm

class airobot.arm.arm.ARM(cfgs, eetool_cfg=None)[source]

Bases: object

Base class for robots.

Parameters:
  • cfgs (YACS CfgNode) – configurations for the robot
  • eetool_cfg (dict) – arguments to pass in the constructor of the end effector tool class. Defaults to None
Variables:
  • cfgs (YACS CfgNode) – configurations for the robot
  • eetool (EndEffectorTool) – end effector tool
compute_ik(pos, ori=None, *args, **kwargs)[source]

Compute the inverse kinematics solution given the position and orientation of the end effector.

Parameters:
  • pos (list or np.ndarray) – position (shape: \([3,]\))
  • ori (list or np.ndarray) – orientation. It can be euler angles ([roll, pitch, yaw], shape: \([4,]\)), or quaternion ([qx, qy, qz, qw], shape: \([4,]\)), or rotation matrix (shape: \([3, 3]\)). If it’s None, the solver will use the current end effector orientation as the target orientation
Returns:

list – inverse kinematics solution (joint angles)

get_ee_pose()[source]

Return the end effector pose.

Returns:4-element tuple containing
  • np.ndarray: x, y, z position of the EE (shape: \([3]\))
  • np.ndarray: quaternion representation ([x, y, z, w]) of the EE orientation (shape: \([4]\))
  • np.ndarray: rotation matrix representation of the EE orientation (shape: \([3, 3]\))
  • np.ndarray: euler angle representation of the EE orientation (roll, pitch, yaw with static reference frame) (shape: \([3]\))
get_jpos(joint_name=None)[source]

Return the joint position(s).

Parameters:joint_name (str) – If it’s None, it will return joint positions of all the actuated joints. Otherwise, it will return the joint position of the specified joint
Returns:One of the following
  • float: joint position given joint_name
  • list: joint positions if joint_name is None
get_jtorq(joint_name=None)[source]

Return the joint torque(s).

Parameters:joint_name (str) – If it’s None, it will return joint torques of all the actuated joints. Otherwise, it will return the joint torque of the specified joint
Returns:One of the following
  • float: joint torque given joint_name
  • list: joint torques if joint_name is None
get_jvel(joint_name=None)[source]

Return the joint velocity(ies).

Parameters:joint_name (str) – If it’s None, it will return joint velocities of all the actuated joints. Otherwise, it will return the joint velocity of the specified joint
Returns:One of the following
  • float: joint velocity given joint_name
  • list: joint velocities if joint_name is None
go_home()[source]

Move the robot arm to a pre-defined home pose.

move_ee_xyz(delta_xyz, eef_step=0.005, *args, **kwargs)[source]

Move the end-effector in a straight line without changing the orientation.

Parameters:
  • delta_xyz (list or np.ndarray) – movement in x, y, z directions
  • eef_step (float) – interpolation interval along delta_xyz. Interpolate a point every eef_step distance between the two end points
Returns:

bool – A boolean variable representing if the action is successful at the moment when the function exits

set_ee_pose(pos=None, ori=None, *args, **kwargs)[source]

Move the end effector to the specifed pose.

Parameters:
  • pos (list or np.ndarray) – Desired x, y, z positions in the robot’s base frame to move to (shape: \([3,]\))
  • ori (list or np.ndarray, optional) – It can be euler angles ([roll, pitch, yaw], shape: \([4,]\)), or quaternion ([qx, qy, qz, qw], shape: \([4,]\)), or rotation matrix (shape: \([3, 3]\)). If it’s None, the solver will use the current end effector orientation as the target orientation
Returns:

bool – A boolean variable representing if the action is successful at the moment when the function exits

set_jpos(position, joint_name=None, *args, **kwargs)[source]

Move the arm to the specified joint position(s).

Parameters:
  • position (float or list or flattened np.ndarray) – desired joint position(s)
  • joint_name (str) – If not provided, position should be a list and all the actuated joints will be moved to the specified positions. If provided, only the specified joint will be moved to the desired joint position
  • wait (bool) – whether to block the code and wait for the action to complete
Returns:

bool – A boolean variable representing if the action is successful at the moment when the function exits

set_jtorq(torque, joint_name=None, *args, **kwargs)[source]

Apply torque(s) to the joint(s).

Parameters:
  • torque (float or list or flattened np.ndarray) – torque value(s) for the joint(s)
  • joint_name (str) – specify the joint on which the torque is applied. If it’s not provided(None), it will apply the torques on the actuated joints on the arm. Otherwise, only the specified joint will be applied with the given torque.
  • wait (bool) – whether to block the code and wait for the action to complete
Returns:

bool – A boolean variable representing if the action is successful at the moment when the function exits

set_jvel(velocity, joint_name=None, *args, **kwargs)[source]

Move the arm with the specified joint velocity(ies).

Parameters:
  • velocity (float or list or flattened np.ndarray) – desired joint velocity(ies)
  • joint_name (str) – If not provided, velocity should be a list and all the actuated joints will be moved in the specified velocities. If provided, only the specified joint will be moved in the desired joint velocity
  • wait (bool) – whether to block the code and wait for the action to complete
Returns:

bool – A boolean variable representing if the action is successful at the moment when the function exits