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: |
|
|---|
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: |
|
|---|---|
| Return result: | Returns True if command succeeded, False otherwise |
| Return type: | bool |
set_joint_torque(joint_name, value)[source]¶| Parameters: |
|
|---|---|
| Returns: | sucessful or not |
| Return type: | bool |