LoCoBot Arm

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

Bases: pyrobot.robots.arm.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, ns='')[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_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