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

Fix part controller demo #546

Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
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
14 changes: 7 additions & 7 deletions docs/modules/controllers.rst
Original file line number Diff line number Diff line change
Expand Up @@ -222,19 +222,19 @@ Controller Settings

Loading a Controller
---------------------
By default, if no controller configuration is specified during environment creation, then ``JOINT_VELOCITY`` controllers with robot-specific configurations will be used.
By default, user will use the `load_composite_controller_config()` method to create a controller configuration.

Using a Default Controller Configuration
*****************************************
Any controller can be used with its default configuration, and can be easily loaded into a given environment by calling its name as shown below (where ``controller_name`` is one of acceptable controller ``type`` strings):
Any controller can be used with its default configuration, and can be easily loaded into a given environment by calling its name as shown below (where ``controller`` is one of acceptable controller ``type`` strings):

.. code-block:: python

import robosuite as suite
from robosuite import load_controller_config
from robosuite import load_composite_controller_config

# Load the desired controller's default config as a dict
config = load_controller_config(default_controller=controller_name)
# Load the desired controller config with default Basic controller
config = load_composite_controller_config(controller="BASIC")

# Create environment
env = suite.make("Lift", robots="Panda", controller_configs=config, ... )
Expand All @@ -248,13 +248,13 @@ A custom controller configuration can also be used by simply creating a new conf
.. code-block:: python

import robosuite as suite
from robosuite import load_controller_config
from robosuite import load_composite_controller_config

# Path to config file
controller_fpath = "/your/custom/config/filepath/here/filename.json"

# Import the file as a dict
config = load_controller_config(custom_fpath=controller_fpath)
config = load_composite_controller_config(controller=controller_fpath)

# Create environment
env = suite.make("Lift", robots="Panda", controller_configs=config, ... )
Expand Down
kevin-thankyou-lin marked this conversation as resolved.
Show resolved Hide resolved
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

do we need to change the key from body_parts to body_parts_controller_config I think if don't do this. This PR will have less changes

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think updating is fine for consistency?

Original file line number Diff line number Diff line change
Expand Up @@ -127,13 +127,13 @@ def load_composite_controller_config(controller: Optional[str] = None, robot: Op

validate_composite_controller_config(composite_controller_config)
body_parts_controller_configs = composite_controller_config.pop("body_parts_controller_configs", {})
composite_controller_config["body_parts"] = {}
composite_controller_config["body_parts_controller_configs"] = {}
for part_name, part_config in body_parts_controller_configs.items():
if part_name == "arms":
for arm_name, arm_config in part_config.items():
composite_controller_config["body_parts"][arm_name] = arm_config
composite_controller_config["body_parts_controller_configs"][arm_name] = arm_config
else:
composite_controller_config["body_parts"][part_name] = part_config
composite_controller_config["body_parts_controller_configs"][part_name] = part_config

return composite_controller_config

Expand Down
2 changes: 1 addition & 1 deletion robosuite/controllers/config/default/parts/ik_pose.json
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,4 @@
"ik_ori_limit": 0.05,
"interpolation": null,
"ramp_ratio": 0.2
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -12,4 +12,4 @@
"qpos_limits": null,
"interpolation": null,
"ramp_ratio": 0.2
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -7,4 +7,4 @@
"torque_limits": null,
"interpolation": null,
"ramp_ratio": 0.2
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -8,4 +8,4 @@
"velocity_limits": [-1,1],
"interpolation": null,
"ramp_ratio": 0.2
}
}
2 changes: 1 addition & 1 deletion robosuite/controllers/config/default/parts/osc_pose.json
Original file line number Diff line number Diff line change
Expand Up @@ -15,4 +15,4 @@
"control_delta": true,
"interpolation": null,
"ramp_ratio": 0.2
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -13,4 +13,4 @@
"control_delta": true,
"interpolation": null,
"ramp_ratio": 0.2
}
}
1 change: 1 addition & 0 deletions robosuite/robots/fixed_base_robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ def _load_controller(self):
robot_model=self.robot_model,
grippers={self.get_gripper_name(arm): self.gripper[arm] for arm in self.arms},
)
print("Loaded composite controller: {}".format(self.composite_controller))

self._load_arm_controllers()

Expand Down
9 changes: 7 additions & 2 deletions robosuite/robots/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,10 @@ def __init__(
self.composite_controller_config = composite_controller_config
else:
self.composite_controller_config = load_composite_controller_config(robot=robot_type)
self.part_controller_config = copy.deepcopy(self.composite_controller_config.get("body_parts", {}))

self.part_controller_config = copy.deepcopy(
self.composite_controller_config.get("body_parts_controller_configs", {})
)

self.gripper = self._input2dict(None)
self.gripper_type = self._input2dict(gripper_type)
Expand Down Expand Up @@ -145,7 +148,9 @@ def _postprocess_part_controller_config(self):
Remove unused parts that are not in the controller.
Called by _load_controller() function
"""
for part_name, controller_config in self.composite_controller_config.get("body_parts", {}).items():
for part_name, controller_config in self.composite_controller_config.get(
"body_parts_controller_configs", {}
).items():
if not self.has_part(part_name):
ROBOSUITE_DEFAULT_LOGGER.warn(
f'The config has defined for the controller "{part_name}", '
Expand Down
3 changes: 1 addition & 2 deletions robosuite/scripts/tune_joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -275,14 +275,13 @@ def print_command(char, info):
print_command("t", "Toggle between robot arms in the environment")
print_command("r", "Reset active arm joints to all 0s")
print_command("up/down", "incr/decrement the active joint angle")
print_command("right/left", "incr/decrement the delta joint angle per up/down keypress")
print("")

# Setup printing options for numbers
np.set_printoptions(formatter={"float": lambda x: "{0:0.3f}".format(x)})

# Define the controller
controller_config = robosuite.load_controller_config(default_controller="JOINT_POSITION")
controller_config = robosuite.load_composite_controller_config(controller="BASIC")

# make the environment
env = robosuite.make(
Expand Down
29 changes: 29 additions & 0 deletions robosuite/utils/input_utils.py
kevin-thankyou-lin marked this conversation as resolved.
Show resolved Hide resolved
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,35 @@ def choose_controller(part_controllers=False):
return controllers[k]


def choose_part_controller():
"""
Prints out part controller options, and returns the requested part controller name

Returns:
str: Chosen part controller name
"""
controllers = list(suite.ALL_PART_CONTROLLERS)

# Select controller to use
print("Here is a list of part controllers in the suite:\n")

for k, controller in enumerate(controllers):
print("[{}] {}".format(k, controller))
print()
try:
s = input(
"Choose a part controller for the robot " + "(enter a number from 0 to {}): ".format(len(controllers) - 1)
)
# parse input into a number within range
k = min(max(int(s), 0), len(controllers) - 1)
except:
k = 0
print("Input is not valid. Use {} by default.".format(controllers)[k])

# Return chosen controller
return controllers[k]


def choose_multi_arm_config():
"""
Prints out multi-arm environment configuration options, and returns the requested config name
Expand Down
2 changes: 1 addition & 1 deletion tests/test_controllers/test_variable_impedance.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ def test_variable_impedance():
np.random.seed(3)

composite_controller_config = load_composite_controller_config(controller=None, robot="Sawyer")
controller_config = composite_controller_config["body_parts"]["right"]
controller_config = composite_controller_config["body_parts_controller_configs"]["right"]
controller_config["type"] = controller_name
# Manually edit impedance settings
controller_config["impedance_mode"] = "variable"
Expand Down
Loading