Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Demo fixes #548

Merged
merged 23 commits into from
Nov 6, 2024
Merged
Show file tree
Hide file tree
Changes from 22 commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
0bc81a9
updates to allow numpy v2 to work
Abhiram824 Aug 31, 2024
4205f69
Add github issue bug report template
kevin-thankyou-lin Sep 6, 2024
cd7ba57
Update github issue bug report template
kevin-thankyou-lin Sep 6, 2024
0eec959
Update github issue bug report template 3
kevin-thankyou-lin Sep 6, 2024
c6fe6cc
Update github issue bug report template 4
kevin-thankyou-lin Sep 6, 2024
5f8aa5e
Add PR template
kevin-thankyou-lin Sep 6, 2024
e614a15
Update PR template
kevin-thankyou-lin Sep 6, 2024
cbe7f8a
Update bug-report.yml
kevin-thankyou-lin Sep 7, 2024
dfa5f31
Update xmlobject docs
kevin-thankyou-lin Sep 14, 2024
9a112b3
Merge branch 'master' of https://github.com/ARISE-Initiative/robosuit…
kevin-thankyou-lin Sep 14, 2024
b3ccef8
Create github issue template for feature-request.yml
kevin-thankyou-lin Sep 17, 2024
67d27c2
Update feature-request.yml
kevin-thankyou-lin Sep 17, 2024
f681960
Update feature-request.yml
kevin-thankyou-lin Sep 17, 2024
55865c4
Merge pull request #67 from ARISE-Initiative/numpy2_updates
kevin-thankyou-lin Sep 19, 2024
4087731
Merge branch 'public-master'
snasiriany Oct 31, 2024
9036ace
changes to make demo scripts working
Abhiram824 Nov 3, 2024
60f0966
updated device usage to match collect human demos script
Abhiram824 Nov 3, 2024
0e1db5b
add max frame rate feature to relevant demo scripts
snasiriany Nov 4, 2024
26539c1
Merge branch 'master' into demo_fixes
Abhiram824 Nov 6, 2024
885a2a5
cleanup demo fixes
Abhiram824 Nov 6, 2024
e47d07d
Merge branch 'master' of https://github.com/Abhiram824/robosuite
Abhiram824 Nov 6, 2024
c27afe4
Merge branch 'master' into demo_fixes
Abhiram824 Nov 6, 2024
b354731
renaming
Abhiram824 Nov 6, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ eggs/
lib/
lib64/
parts/
!robosuite/controllers/config/default/parts
!robosuite/controllers/parts
sdist/
var/
Expand Down
52 changes: 52 additions & 0 deletions robosuite/controllers/composite/composite_controller_factory.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
import copy
import json
import os
import pathlib
Expand All @@ -18,6 +19,57 @@ def validate_composite_controller_config(config: dict):
raise ValueError


def is_arm_controller_config(config: Dict):
"""
Checks if a controller config is an arm part config as a opposed to a composite
controller config.

Args:
config (dict): Controller configuration

Returns:
bool: True if the config is in the for the arm-only, False otherwise
"""

ARM_CONTROLLER_TYPES = ["JOINT_VELOCITY", "JOINT_TORQUE", "JOINT_POSITION", "OSC_POSITION", "OSC_POSE", "IK_POSE"]
kevin-thankyou-lin marked this conversation as resolved.
Show resolved Hide resolved
if "body_parts_controller_configs" not in config and "type" in config:
return config["type"] in ARM_CONTROLLER_TYPES
return False


def refactor_composite_controller_config(controller_config, robot_type, arms):
"""
Checks if a controller config is in the format from robosuite versions <= 1.4.1.
If this is the case, converts the controller config to the new composite controller
config format in robosuite versions >= 1.5. If the robot has a default
controller config use that and override the arms with the old controller config.
If not just use the old controller config for arms.

Args:
old_controller_config (dict): Old controller config

Returns:
dict: New controller config
"""
if not is_arm_controller_config(controller_config):
return controller_config

config_dir = pathlib.Path(robosuite.__file__).parent / "controllers/config/robots/"
name = robot_type.lower()
configs = os.listdir(config_dir)
if f"default_{name}.json" in configs:
new_controller_config = load_composite_controller_config(robot=name)
else:
new_controller_config = {}
new_controller_config["type"] = "BASIC"
new_controller_config["body_parts"] = {}

for arm in arms:
new_controller_config["body_parts"][arm] = copy.deepcopy(controller_config)
new_controller_config["body_parts"][arm]["gripper"] = {"type": "GRIP"}
return new_controller_config


def load_composite_controller_config(controller: Optional[str] = None, robot: Optional[str] = None) -> Optional[Dict]:
"""
Utility function that loads the desired composite controller and returns the loaded configuration as a dict
Expand Down
7 changes: 7 additions & 0 deletions robosuite/controllers/config/default/parts/ik_pose.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
{
"type" : "IK_POSE",
"ik_pos_limit": 0.02,
"ik_ori_limit": 0.05,
"interpolation": null,
"ramp_ratio": 0.2
}
15 changes: 15 additions & 0 deletions robosuite/controllers/config/default/parts/joint_position.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
{
"type": "JOINT_POSITION",
"input_max": 1,
"input_min": -1,
"output_max": 0.05,
"output_min": -0.05,
"kp": 50,
"damping_ratio": 1,
"impedance_mode": "fixed",
"kp_limits": [0, 300],
"damping_ratio_limits": [0, 10],
"qpos_limits": null,
"interpolation": null,
"ramp_ratio": 0.2
}
10 changes: 10 additions & 0 deletions robosuite/controllers/config/default/parts/joint_torque.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
{
"type": "JOINT_TORQUE",
"input_max": 1,
"input_min": -1,
"output_max": 0.1,
"output_min": -0.1,
"torque_limits": null,
"interpolation": null,
"ramp_ratio": 0.2
}
11 changes: 11 additions & 0 deletions robosuite/controllers/config/default/parts/joint_velocity.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
{
"type" : "JOINT_VELOCITY",
"input_max": 1,
"input_min": -1,
"output_max": 0.5,
"output_min": -0.5,
"kp": 3.0,
"velocity_limits": [-1,1],
"interpolation": null,
"ramp_ratio": 0.2
}
18 changes: 18 additions & 0 deletions robosuite/controllers/config/default/parts/osc_pose.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
{
"type": "OSC_POSE",
"input_max": 1,
"input_min": -1,
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
"kp": 150,
"damping_ratio": 1,
"impedance_mode": "fixed",
"kp_limits": [0, 300],
"damping_ratio_limits": [0, 10],
"position_limits": null,
"orientation_limits": null,
"uncouple_pos_ori": true,
"control_delta": true,
"interpolation": null,
"ramp_ratio": 0.2
}
16 changes: 16 additions & 0 deletions robosuite/controllers/config/default/parts/osc_position.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
{
"type": "OSC_POSITION",
"input_max": 1,
"input_min": -1,
"output_max": [0.05, 0.05, 0.05],
"output_min": [-0.05, -0.05, -0.05],
"kp": 150,
"damping_ratio": 1,
"impedance_mode": "fixed",
"kp_limits": [0, 300],
"damping_ratio_limits": [0, 10],
"position_limits": null,
"control_delta": true,
"interpolation": null,
"ramp_ratio": 0.2
}
4 changes: 2 additions & 2 deletions robosuite/controllers/parts/controller_factory.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ def load_part_controller_config(custom_fpath=None, default_controller=None):

# Store the default controller config fpath associated with the requested controller
custom_fpath = os.path.join(
os.path.dirname(__file__), "..", "controllers/config/parts/{}.json".format(default_controller.lower())
os.path.dirname(__file__), "..", "config/default/parts/{}.json".format(default_controller.lower())
)

# Assert that the fpath to load the controller is not empty
Expand Down Expand Up @@ -122,7 +122,7 @@ def arm_controller_factory(name, params):
ori_interpolator = deepcopy(interpolator)
ori_interpolator.set_states(dim=4, ori="quat")

from robosuite.controllers.arm.ik import InverseKinematicsController
from robosuite.controllers.parts.arm.ik import InverseKinematicsController

return InverseKinematicsController(
interpolator_pos=interpolator,
Expand Down
13 changes: 11 additions & 2 deletions robosuite/demos/demo_collect_and_playback_data.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ def collect_random_trajectory(env, timesteps=1000, max_fr=None):
time.sleep(diff)


def playback_trajectory(env, ep_dir):
def playback_trajectory(env, ep_dir, max_fr=None):
"""Playback data from an episode.

Args:
Expand All @@ -69,13 +69,22 @@ def playback_trajectory(env, ep_dir):
dic = np.load(state_file)
states = dic["states"]
for state in states:
start = time.time()
env.sim.set_state_from_flattened(state)
env.sim.forward()
env.viewer.update()
kevin-thankyou-lin marked this conversation as resolved.
Show resolved Hide resolved
env.render()
t += 1
if t % 100 == 0:
print(t)

if max_fr is not None:
elapsed = time.time() - start
diff = 1 / max_fr - elapsed
if diff > 0:
time.sleep(diff)
env.close()


if __name__ == "__main__":

Expand Down Expand Up @@ -120,4 +129,4 @@ def playback_trajectory(env, ep_dir):
_ = input("Press any key to begin the playback...")
print("Playing back the data...")
data_directory = env.ep_directory
playback_trajectory(env, data_directory)
playback_trajectory(env, data_directory, args.max_fr)
9 changes: 7 additions & 2 deletions robosuite/demos/demo_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
from typing import Dict

import robosuite as suite
from robosuite.controllers.composite.composite_controller_factory import refactor_composite_controller_config
from robosuite.utils.input_utils import *

MAX_FR = 25 # max frame rate for running simluation
Expand Down Expand Up @@ -92,10 +93,14 @@
joint_dim = 6 if options["robots"] == "UR5e" else (16 if options["robots"] == "GR1" else 7)

# Choose controller
controller_name = choose_controller()
controller_name = choose_controller(part_controllers=True)

# Load the desired controller
options["controller_configs"] = suite.load_part_controller_config(default_controller=controller_name)
arm_controller_config = suite.load_part_controller_config(default_controller=controller_name)
robot = options["robots"][0] if isinstance(options["robots"], list) else options["robots"]
options["controller_configs"] = refactor_composite_controller_config(
arm_controller_config, robot, ["right", "left"]
)

# Define the pre-defined controller actions to use (action_dim, num_test_steps, test_value)
controller_settings = {
Expand Down
99 changes: 49 additions & 50 deletions robosuite/demos/demo_device_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@

import robosuite as suite
from robosuite import load_composite_controller_config
from robosuite.controllers.composite.composite_controller import WholeBody
from robosuite.wrappers import VisualizationWrapper

if __name__ == "__main__":
Expand All @@ -108,7 +109,12 @@
parser.add_argument("--arm", type=str, default="right", help="Which arm to control (eg bimanual) 'right' or 'left'")
parser.add_argument("--switch-on-grasp", action="store_true", help="Switch gripper control on gripper action")
parser.add_argument("--toggle-camera-on-grasp", action="store_true", help="Switch camera angle on gripper action")
parser.add_argument("--controller", type=str, default="BASIC", help="Choice of controller. Can be 'ik' or 'osc'")
parser.add_argument(
"--controller",
type=str,
default=None,
help="Choice of controller. Can be generic (eg. 'BASIC' or 'WHOLE_BODY_MINK_IK') or json file (see robosuite/controllers/config for examples) or None to get the robot's default controller if it exists",
)
parser.add_argument("--device", type=str, default="keyboard")
parser.add_argument("--pos-sensitivity", type=float, default=1.0, help="How much to scale position user inputs")
parser.add_argument("--rot-sensitivity", type=float, default=1.0, help="How much to scale rotation user inputs")
Expand Down Expand Up @@ -168,6 +174,10 @@
from robosuite.devices import SpaceMouse

device = SpaceMouse(env=env, pos_sensitivity=args.pos_sensitivity, rot_sensitivity=args.rot_sensitivity)
elif args.device == "mjgui":
from robosuite.devices.mjgui import MJGUI

device = MJGUI(env=env)
else:
raise Exception("Invalid device choice: choose either 'keyboard' or 'spacemouse'.")

Expand All @@ -185,65 +195,54 @@

# Initialize device control
device.start_control()
action_dict = device.input2action()

# get key with "delta" in it
action_key = [key for key in action_dict.keys() if "delta" in key]
assert len(action_key) == 1, "Error: Key with 'delta' in it not found!"
action_key = action_key[0]
gripper_key = [key for key in action_dict.keys() if "gripper" in key]
assert len(gripper_key) == 1, "Error: Key with 'gripper' in it not found!"
gripper_key = gripper_key[0]

all_prev_gripper_actions = [
{
f"{robot_arm}_gripper": np.repeat([0], robot.gripper[robot_arm].dof)
for robot_arm in robot.arms
if robot.gripper[robot_arm].dof > 0
}
for robot in env.robots
]

# Loop until we get a reset from the input or the task completes
while True:
start = time.time()

# Set active robot
active_robot = env.robots[0] if args.config == "bimanual" else env.robots[args.arm == "left"]
active_robot = env.robots[device.active_robot]

# Get the newest action
action_dict = device.input2action()
input_ac_dict = device.input2action()

# If action_dict is none, then this a reset so we should break
if action_dict is None:
# If action is none, then this a reset so we should break
if input_ac_dict is None:
break

action = action_dict[action_key]
grasp = action_dict[gripper_key]

# If the current grasp is active (1) and last grasp is not (-1) (i.e.: grasping input just pressed),
# toggle arm control and / or camera viewing angle if requested
if last_grasp < 0 < grasp:
if args.switch_on_grasp:
args.arm = "left" if args.arm == "right" else "right"
if args.toggle_camera_on_grasp:
cam_id = (cam_id + 1) % num_cam
env.viewer.set_camera(camera_id=cam_id)
# Update last grasp
last_grasp = grasp

# Fill out the rest of the action space if necessary
rem_action_dim = env.action_dim - action.size
if rem_action_dim > 0:
# Initialize remaining action space
rem_action = np.zeros(rem_action_dim)
# This is a multi-arm setting, choose which arm to control and fill the rest with zeros
if args.arm == "right":
action = np.concatenate([action, rem_action])
elif args.arm == "left":
action = np.concatenate([rem_action, action])
from copy import deepcopy

action_dict = deepcopy(input_ac_dict) # {}
# set arm actions
for arm in active_robot.arms:
if isinstance(active_robot.composite_controller, WholeBody): # input type passed to joint_action_policy
controller_input_type = active_robot.composite_controller.joint_action_policy.input_type
else:
controller_input_type = active_robot.part_controllers[arm].input_type

if controller_input_type == "delta":
action_dict[arm] = input_ac_dict[f"{arm}_delta"]
elif controller_input_type == "absolute":
action_dict[arm] = input_ac_dict[f"{arm}_abs"]
else:
# Only right and left arms supported
print(
"Error: Unsupported arm specified -- "
"must be either 'right' or 'left'! Got: {}".format(args.arm)
)
elif rem_action_dim < 0:
# We're in an environment with no gripper action space, so trim the action space to be the action dim
action = action[: env.action_dim]

# Step through the simulation and render
obs, reward, done, info = env.step(action)
raise ValueError

# Maintain gripper state for each robot but only update the active robot with action
env_action = [robot.create_action_vector(all_prev_gripper_actions[i]) for i, robot in enumerate(env.robots)]
env_action[device.active_robot] = active_robot.create_action_vector(action_dict)
env_action = np.concatenate(env_action)
for gripper_ac in all_prev_gripper_actions[device.active_robot]:
all_prev_gripper_actions[device.active_robot][gripper_ac] = action_dict[gripper_ac]

env.step(env_action)
env.render()

# limit frame rate if necessary
Expand Down
4 changes: 3 additions & 1 deletion robosuite/demos/demo_domain_randomization.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@
Script to showcase domain randomization functionality.
"""

import mujoco

import robosuite.macros as macros
from robosuite.utils.input_utils import *
from robosuite.wrappers import DomainRandomizationWrapper
Expand All @@ -10,7 +12,7 @@
macros.USING_INSTANCE_RANDOMIZATION = True

if __name__ == "__main__":

assert mujoco.__version__ == "3.1.1", "Script requires mujoco-py version 3.1.1 to run"
# Create dict to hold options that will be passed to env creation call
options = {}

Expand Down
Loading
Loading