Arm

class locobot.arm.LoCoBotArm(configs, control_mode='position', moveit_planner='ESTkConfigDefault', use_moveit=True)[source]

Bases: pyrobot.core.Arm

This class has functionality to control a robotic arm in joint and task space (with and without any motion planning), for position/velocity/torque control, etc.

__init__(configs, control_mode='position', moveit_planner='ESTkConfigDefault', use_moveit=True)[source]

The constructor for LoCoBotArm class.

Parameters:
  • configs (YACS CfgNode) – configurations read from config file
  • control_mode (string) – Choose between ‘position’, ‘velocity’ and ‘torque’ control
  • moveit_planner (string) – Planner name for moveit, only used if planning_mode = ‘moveit’.
  • use_moveit (bool) – use moveit or not, default is True
go_home(plan=False)[source]

Commands robot to home position

Parameters:plan (bool) – use moveit to plan the path or not
set_ee_pose_pitch_roll(position, pitch, roll=None, plan=True, wait=True, numerical=True, **kwargs)[source]

Commands robot arm to desired end-effector pose (w.r.t. ‘ARM_BASE_FRAME’). Computes IK solution in joint space and calls set_joint_positions. Will wait for command to complete if wait is set to True.

Parameters:
  • position (np.ndarray) – position of the end effector (shape: \([3,]\))
  • pitch (float) – pitch angle
  • roll (float) – roll angle
  • plan (bool) – use moveit the plan a path to move to the desired pose
  • wait (bool) – wait until the desired pose is achieved
  • numerical (bool) – use numerical inverse kinematics solver or analytical inverse kinematics solver
Return result:

Returns True if command succeeded, False otherwise

Return type:

bool

set_joint_torque(joint_name, value)[source]
Parameters:
  • joint_name (string) – joint name ([‘joint_1’, ‘joint_2’, ‘joint_3’, ‘joint_4’‘])
  • value (float) – torque value in Nm
Returns:

sucessful or not

Return type:

bool

set_joint_torques(torques, **kwargs)[source]

Sets the desired joint torques for all arm joints.

Parameters:torques (list) – target joint torques, list of len 4 populated with torque to be applied on first 4 joints of arm in Nm
set_joint_velocities(velocities, **kwargs)[source]

Sets the desired joint velocities for all arm joints

Parameters:velocities (list) – target joint velocities