robosuite.devices package#
Submodules#
robosuite.devices.device module#
- class robosuite.devices.device.Device(env)#
Bases:
object
Base class for all robot controllers. Defines basic interface for all controllers to adhere to. Also contains shared logic for managing multiple and/or multiarmed robots.
- property active_arm#
- property active_arm_index#
- property base_mode#
- get_arm_action(robot, arm, norm_delta, goal_update_mode='target')#
- abstract get_controller_state() Dict #
Returns the current state of the device, a dictionary of pos, orn, grasp, and reset.
- property grasp#
- input2action(mirror_actions=False) Dict | None #
Converts an input from an active device into a valid action sequence that can be fed into an env.step() call
If a reset is triggered from the device, immediately returns None. Else, returns the appropriate action
- Parameters:
mirror_actions (bool) – actions corresponding to viewing robot from behind. first axis: left/right. second axis: back/forward. third axis: down/up.
- Returns:
- Dictionary of actions to be fed into env.step()
if reset is triggered, returns None
- Return type:
Optional[Dict]
- abstract start_control()#
Method that should be called externally before controller can start receiving commands.
robosuite.devices.dualsense module#
Driver class for DualSense controller.
This class provides a driver support to DualSense on macOS. In particular, we assume you are using a DualSense Wireless by default.
- class robosuite.devices.dualsense.ConnectionType(value)#
Bases:
IntFlag
An enumeration.
- BT01 = 2#
- BT31 = 4#
- UNKNOWN = 8#
- USB = 1#
- classmethod to_string(value) str #
- class robosuite.devices.dualsense.DSState#
Bases:
object
- setDPadState(dpad_state: int) None #
Sets the dpad state variables according to the integers that was read from the controller
- Parameters:
dpad_state (int) – integer number representing the dpad state, actually a 4-bit number,[0,8]
- class robosuite.devices.dualsense.DualSense(*args: Any, **kwargs: Any)#
Bases:
Device
A minimalistic driver class for DualSense with HID library.
Note: Use hid.enumerate() to view all USB human interface devices (HID). Make sure DualSense is detected before running the script. You can look up its vendor/product id from this method.
You can test your DualSense in https://hardwaretester.com/gamepad and https://nondebug.github.io/dualsense/dualsense-explorer.html DualSense HID protocol refer to nondebug/dualsense
- Parameters:
env (RobotEnv) – The environment which contains the robot(s) to control using this device.
pos_sensitivity (float) – Magnitude of input position command scaling
rot_sensitivity (float) – Magnitude of scale input rotation commands scaling
reverse_xy (bool) – Whether to reverse the effect of the x and y axes of the joystick. It is used to handle the case that the left/right and front/back sides of the view are opposite to the LX and LY of the joystick(Push LX up but the robot move left in your view)
- property control#
Grabs current pose of DualSense
- Returns:
6-DoF control value
- Return type:
np.array
- property control_gripper#
Maps internal states into gripper commands.
- Returns:
Whether we’re using single click and hold or not
- Return type:
float
- get_controller_state()#
Grabs the current state of the 3D mouse.
- Returns:
A dictionary containing dpos, orn, unmodified orn, grasp, and reset
- Return type:
dict
- run()#
Listener method that keeps pulling new messages.
- start_control()#
Method that should be called externally before controller can start receiving commands.
- robosuite.devices.dualsense.scale_to_control(x, axis_scale=128, min_v=-1.0, max_v=1.0)#
Normalize raw HID readings to target range.
- Parameters:
x (int) – Raw reading from HID
axis_scale (float) – (Inverted) scaling factor for mapping raw input value
min_v (float) – Minimum limit after scaling
max_v (float) – Maximum limit after scaling
- Returns:
Clipped, scaled input from HID
- Return type:
float
robosuite.devices.keyboard module#
robosuite.devices.mjgui module#
- class robosuite.devices.mjgui.MJGUI(*args: Any, **kwargs: Any)#
Bases:
Device
Class for ‘device’ involving mujoco viewer and mocap bodies being dragged by user’s mouse.
- Parameters:
env (RobotEnv) – The environment which contains the robot(s) to control using this device.
- get_controller_state()#
Grabs the current state of the keyboard. :returns: A dictionary containing dpos, orn, unmodified orn, grasp, and reset :rtype: dict
- input2action() Dict[str, ndarray] #
Uses mocap body poses to determine action for robot. Obtain input_type (i.e. absolute actions or delta actions) and input_ref_frame (i.e. world frame, base frame or eef frame) from the controller itself.
- start_control()#
Method that should be called externally before controller can start receiving commands.
- robosuite.devices.mjgui.get_mocap_pose(sim, mocap_name: str = 'target') Tuple[ndarray, ndarray] #
- robosuite.devices.mjgui.set_mocap_pose(sim, target_pos: ndarray | None = None, target_mat: ndarray | None = None, mocap_name: str = 'target')#