Skip to main content

WidowX250s

Inherits from: Arm No class docstring.

Inherited methods

  • From Arm: setNamedPose, removeNamedPose, getNamedPose
  • From Robot: addSensor, cleanup

init

WidowX250s.__init__()
Initialize the WidowX robot arm. Note that the ROS node must already be running: ros2 launch interbotix_xsarm_control xsarm_control.launch.py robot_model:=wx250s

goToHomePose

WidowX250s.goToHomePose()
No docstring provided.

moveToHome

WidowX250s.moveToHome(moving_time: float = 2.0, accel_time: float = 0.75)
No docstring provided.
Arguments
moving_time (float)
float
No description provided.
accel_time (float)
float
No description provided.

torqueEnable

WidowX250s.torqueEnable(enable: bool = True)
Enable or disable torque for the robot arm. (useful if you want free-drive mode)
Arguments
enable (bool)
bool
Whether to enable torque. Defaults to True.

moveToDeltaPose

WidowX250s.moveToDeltaPose(delta_pose: Pose, blocking: bool = True, moving_time: float = 0.5, accel_time: float = 0.2) -> bool
Move the robot end effector by a relative pose offset from its current pose.
Arguments
delta_pose (Pose)
Pose
required
No description provided.
blocking (bool)
bool
Wait for movement to complete. Defaults to True.
moving_time (float)
float
Time to complete the movement. Defaults to 0.5.
accel_time (float)
float
Time to accelerate/decelerate. Defaults to 0.2.
Returns
bool
bool
True if the movement command was successful, False otherwise

moveToPose

WidowX250s.moveToPose(position: Position, orientation: Orientation, blocking: bool = True, moving_time: float = 2.0, accel_time: float = 0.5) -> bool
Move the robot end effector to a specified pose with respect to the base frame.
Arguments
position (Position)
Position
required
Target pose position (meters)
orientation (Orientation)
Orientation
required
Target pose orientation
blocking (bool)
bool
Wait for movement to complete. Defaults to True.
moving_time (float)
float
Time to complete the movement (seconds). Defaults to 2.0s.
accel_time (float)
float
Time to spend accelerating and decelerating (seconds). Defaults to 0.5s.
Returns
bool
bool
True if the movement command was successful, False otherwise
Raises
ValueError
If moving_time or accel_time are not positive floats or integers

moveToNamedPose

WidowX250s.moveToNamedPose(pose_name: str, blocking: bool = True, moving_time: float = 2.0, accel_time: float = 0.75)
Move the robot to the joint angles of a named pose.
Arguments
pose_name (str)
str
required
Name of the pose to move to. Options are “home”, “sleep”.
blocking (bool)
bool
Wait for movement to complete. Defaults to True.
moving_time (float)
float
Time to complete the movement. Defaults to 2.0.
accel_time (float)
float
Time to accelerate/decelerate. Defaults to 0.75.
Returns
bool
True if the movement command was successful, False otherwise

moveByVelocity

WidowX250s.moveByVelocity(linear_velocity: Velocity, angular_velocity: Velocity, frame: str = 'body')
Move the robot end effector with specified velocities.
Arguments
linear_velocity (Velocity)
Velocity
required
Linear velocity components
angular_velocity (Velocity)
Velocity
required
Angular velocity components
frame (str)
str
No description provided.

grasp

WidowX250s.grasp()
Close the gripper to grasp an object (blocking).

release

WidowX250s.release()
Open the gripper to release an object (blocking).

setGripperPosition

WidowX250s.setGripperPosition(position: float)
Set the gripper position in the range from 0 (closed) to 1 (open) (blocking).
Arguments
position (float)
float
required
No description provided.

goToSleepPose

WidowX250s.goToSleepPose()
Move arm to sleep pose.

shutdown

WidowX250s.shutdown()
Shutdown the robot safely Moves arm to sleep pose then destroys the ROS node.

getEndEffectorPose

WidowX250s.getEndEffectorPose()
Get the current end effector pose with respect to the base frame.
Returns
Pose
Current end effector position and orientation

getPosition

WidowX250s.getPosition()
Get the current end effector position with respect to the robot base (meters)
Returns
Position
Current end effector position with respect to the robot base

getState

WidowX250s.getState()
Get the complete state of the robot as one large dictionary.
Returns
dict
Current state of the robot containing: - joint_positions: 6-element list, Current joint positions (radians) - end_effector_pose: homogenous matrix, Current end effector pose with respect to the robot base

stop

WidowX250s.stop()
Stop any movement of the robot (soft emergency-stop). Commands the robot to maintain its current position.

getOrientation

WidowX250s.getOrientation()
Get the current end effector orientation with respect to the robot base.
Returns
Orientation
Current end effector orientation with respect to the robot base

getJointAngles

WidowX250s.getJointAngles()
Get current joint angles.
Returns
list
List of current joint angles in radians

setJointAngles

WidowX250s.setJointAngles(angles: list, blocking: bool = True, moving_time: float = 2.0, accel_time: float = 0.5) -> bool
Set joint angles directly.
Arguments
angles (list)
list
required
List of target joint angles in radians
blocking (bool)
bool
Wait for movement to complete. Defaults to True.
moving_time (float)
float
Time to complete the movement. Defaults to None.
accel_time (float)
float
Time to accelerate/decelerate. Defaults to None.
Returns
bool
bool
True if position was commanded; False if it wasn’t due to being outside limits

getImage

WidowX250s.getImage(camera_name: str, image_type: str) -> Image
No docstring provided.
Arguments
camera_name (str)
str
required
No description provided.
image_type (str)
str
required
No description provided.
Returns
returns
Image