Add files using upload-large-folder tool
Browse filesThis view is limited to 50 files because it contains too many changes. See raw diff
- robosuite/controllers/__init__.py +15 -0
- robosuite/controllers/composite/__init__.py +19 -0
- robosuite/controllers/composite/composite_controller.py +588 -0
- robosuite/controllers/composite/composite_controller_factory.py +156 -0
- robosuite/controllers/config/default/composite/basic.json +97 -0
- robosuite/controllers/config/default/composite/hybrid_mobile_base.json +97 -0
- robosuite/controllers/config/default/composite/whole_body_ik.json +115 -0
- robosuite/controllers/config/default/composite/whole_body_mink_ik.json +101 -0
- robosuite/controllers/config/default/parts/ik_pose.json +7 -0
- robosuite/controllers/config/default/parts/joint_position.json +15 -0
- robosuite/controllers/config/default/parts/joint_torque.json +10 -0
- robosuite/controllers/config/default/parts/joint_velocity.json +11 -0
- robosuite/controllers/config/default/parts/osc_pose.json +19 -0
- robosuite/controllers/config/default/parts/osc_position.json +17 -0
- robosuite/controllers/config/robots/default_baxter.json +51 -0
- robosuite/controllers/config/robots/default_gr1.json +118 -0
- robosuite/controllers/config/robots/default_gr1_fixed_lower_body.json +101 -0
- robosuite/controllers/config/robots/default_gr1_floating_body.json +65 -0
- robosuite/controllers/config/robots/default_iiwa.json +29 -0
- robosuite/controllers/config/robots/default_kinova3.json +29 -0
- robosuite/controllers/config/robots/default_panda.json +29 -0
- robosuite/controllers/config/robots/default_panda_dex.json +30 -0
- robosuite/controllers/config/robots/default_pandaomron.json +38 -0
- robosuite/controllers/config/robots/default_pandaomron_whole_body_ik.json +116 -0
- robosuite/controllers/config/robots/default_sawyer.json +29 -0
- robosuite/controllers/config/robots/default_spotwitharm.json +43 -0
- robosuite/controllers/config/robots/default_tiago.json +101 -0
- robosuite/controllers/config/robots/default_tiago_whole_body_ik.json +92 -0
- robosuite/controllers/config/robots/default_ur5e.json +29 -0
- robosuite/controllers/parts/__init__.py +0 -0
- robosuite/controllers/parts/arm/__init__.py +2 -0
- robosuite/controllers/parts/arm/ik.py +584 -0
- robosuite/controllers/parts/arm/osc.py +584 -0
- robosuite/controllers/parts/controller.py +347 -0
- robosuite/controllers/parts/controller_factory.py +232 -0
- robosuite/controllers/parts/generic/__init__.py +3 -0
- robosuite/controllers/parts/generic/joint_pos.py +312 -0
- robosuite/controllers/parts/generic/joint_tor.py +181 -0
- robosuite/controllers/parts/generic/joint_vel.py +223 -0
- robosuite/controllers/parts/gripper/__init__.py +1 -0
- robosuite/controllers/parts/gripper/gripper_controller.py +234 -0
- robosuite/controllers/parts/gripper/simple_grip.py +213 -0
- robosuite/controllers/parts/mobile_base/__init__.py +1 -0
- robosuite/controllers/parts/mobile_base/joint_vel.py +383 -0
- robosuite/controllers/parts/mobile_base/mobile_base_controller.py +249 -0
- robosuite/demos/demo_collect_and_playback_data.py +132 -0
- robosuite/demos/demo_composite_robot.py +85 -0
- robosuite/demos/demo_control.py +185 -0
- robosuite/demos/demo_device_control.py +307 -0
- robosuite/demos/demo_domain_randomization.py +78 -0
robosuite/controllers/__init__.py
ADDED
|
@@ -0,0 +1,15 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
from .parts.controller_factory import controller_factory, load_part_controller_config
|
| 2 |
+
from .composite import composite_controller_factory, ALL_COMPOSITE_CONTROLLERS
|
| 3 |
+
from .composite.composite_controller_factory import load_composite_controller_config
|
| 4 |
+
|
| 5 |
+
|
| 6 |
+
PART_CONTROLLER_INFO = {
|
| 7 |
+
"JOINT_VELOCITY": "Joint Velocity",
|
| 8 |
+
"JOINT_TORQUE": "Joint Torque",
|
| 9 |
+
"JOINT_POSITION": "Joint Position",
|
| 10 |
+
"OSC_POSITION": "Operational Space Control (Position Only)",
|
| 11 |
+
"OSC_POSE": "Operational Space Control (Position + Orientation)",
|
| 12 |
+
"IK_POSE": "Inverse Kinematics Control (Position + Orientation) (Note: must have PyBullet installed)",
|
| 13 |
+
}
|
| 14 |
+
|
| 15 |
+
ALL_PART_CONTROLLERS = PART_CONTROLLER_INFO.keys()
|
robosuite/controllers/composite/__init__.py
ADDED
|
@@ -0,0 +1,19 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
from .composite_controller import CompositeController, HybridMobileBase, WholeBodyIK
|
| 2 |
+
from .composite_controller import REGISTERED_COMPOSITE_CONTROLLERS_DICT
|
| 3 |
+
|
| 4 |
+
ALL_COMPOSITE_CONTROLLERS = REGISTERED_COMPOSITE_CONTROLLERS_DICT.keys()
|
| 5 |
+
|
| 6 |
+
|
| 7 |
+
def composite_controller_factory(type, sim, robot_model, grippers):
|
| 8 |
+
assert type in REGISTERED_COMPOSITE_CONTROLLERS_DICT, f"{type} controller is specified, but not imported or loaded"
|
| 9 |
+
# Note: Currently we assume that the init arguments are same for all composite controllers. The situation might change given new controllers in the future, and we will adjust accodingly.
|
| 10 |
+
|
| 11 |
+
# The default composite controllers are explicitly initialized without using the COMPOSITE_CONTORLLERS
|
| 12 |
+
if type == "BASIC":
|
| 13 |
+
return CompositeController(sim, robot_model, grippers)
|
| 14 |
+
elif type == "HYBRID_MOBILE_BASE":
|
| 15 |
+
return HybridMobileBase(sim, robot_model, grippers)
|
| 16 |
+
elif type == "WHOLE_BODY_IK":
|
| 17 |
+
return WholeBodyIK(sim, robot_model, grippers)
|
| 18 |
+
else:
|
| 19 |
+
return REGISTERED_COMPOSITE_CONTROLLERS_DICT[type](sim, robot_model, grippers)
|
robosuite/controllers/composite/composite_controller.py
ADDED
|
@@ -0,0 +1,588 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import json
|
| 2 |
+
import re
|
| 3 |
+
from collections import OrderedDict
|
| 4 |
+
from typing import Dict, Optional, Tuple
|
| 5 |
+
|
| 6 |
+
import numpy as np
|
| 7 |
+
|
| 8 |
+
from robosuite.controllers import controller_factory
|
| 9 |
+
from robosuite.models.grippers.gripper_model import GripperModel
|
| 10 |
+
from robosuite.models.robots.robot_model import RobotModel
|
| 11 |
+
from robosuite.utils.binding_utils import MjSim
|
| 12 |
+
from robosuite.utils.ik_utils import IKSolver, get_nullspace_gains
|
| 13 |
+
from robosuite.utils.log_utils import ROBOSUITE_DEFAULT_LOGGER
|
| 14 |
+
|
| 15 |
+
REGISTERED_COMPOSITE_CONTROLLERS_DICT = {}
|
| 16 |
+
|
| 17 |
+
|
| 18 |
+
def register_composite_controller(target_class):
|
| 19 |
+
if not hasattr(target_class, "name"):
|
| 20 |
+
ROBOSUITE_DEFAULT_LOGGER.warning(
|
| 21 |
+
"The name of the composite controller is not specified. Using the class name as the key."
|
| 22 |
+
)
|
| 23 |
+
key = "_".join(re.sub(r"([A-Z0-9])", r" \1", target_class.__name__).split()).upper()
|
| 24 |
+
else:
|
| 25 |
+
key = target_class.name
|
| 26 |
+
REGISTERED_COMPOSITE_CONTROLLERS_DICT[key] = target_class
|
| 27 |
+
return target_class
|
| 28 |
+
|
| 29 |
+
|
| 30 |
+
@register_composite_controller
|
| 31 |
+
class CompositeController:
|
| 32 |
+
"""This is the parent class for all composite controllers. If you want to develop an advanced version of your controller, you should subclass from this composite controller."""
|
| 33 |
+
|
| 34 |
+
name = "BASIC"
|
| 35 |
+
|
| 36 |
+
def __init__(self, sim: MjSim, robot_model: RobotModel, grippers: Dict[str, GripperModel]):
|
| 37 |
+
# TODO: grippers repeat with members inside robot_model. Currently having this additioanl field to make naming query easy.
|
| 38 |
+
self.sim = sim
|
| 39 |
+
self.robot_model = robot_model
|
| 40 |
+
|
| 41 |
+
self.grippers = grippers
|
| 42 |
+
|
| 43 |
+
self.part_controllers = OrderedDict()
|
| 44 |
+
|
| 45 |
+
self._action_split_indexes = OrderedDict()
|
| 46 |
+
|
| 47 |
+
self.part_controller_config = None
|
| 48 |
+
|
| 49 |
+
self.arms = self.robot_model.arms
|
| 50 |
+
|
| 51 |
+
self._applied_action_dict = {}
|
| 52 |
+
|
| 53 |
+
def load_controller_config(
|
| 54 |
+
self, part_controller_config, composite_controller_specific_config: Optional[Dict] = None
|
| 55 |
+
):
|
| 56 |
+
self.composite_controller_specific_config = composite_controller_specific_config
|
| 57 |
+
body_part_ordering = self.composite_controller_specific_config.get("body_part_ordering", None)
|
| 58 |
+
if body_part_ordering is not None:
|
| 59 |
+
self.part_controller_config = OrderedDict()
|
| 60 |
+
assert len(body_part_ordering) == len(part_controller_config)
|
| 61 |
+
for part_name in body_part_ordering:
|
| 62 |
+
self.part_controller_config[part_name] = part_controller_config[part_name]
|
| 63 |
+
else:
|
| 64 |
+
self.part_controller_config = part_controller_config
|
| 65 |
+
|
| 66 |
+
self.part_controllers.clear()
|
| 67 |
+
self._action_split_indexes.clear()
|
| 68 |
+
self._init_controllers()
|
| 69 |
+
self._validate_composite_controller_specific_config()
|
| 70 |
+
self.setup_action_split_idx()
|
| 71 |
+
|
| 72 |
+
def _init_controllers(self):
|
| 73 |
+
for part_name in self.part_controller_config.keys():
|
| 74 |
+
controller_params = self.part_controller_config[part_name]
|
| 75 |
+
self.part_controllers[part_name] = controller_factory(
|
| 76 |
+
part_name=part_name,
|
| 77 |
+
controller_type=self.part_controller_config[part_name]["type"],
|
| 78 |
+
controller_params=controller_params,
|
| 79 |
+
)
|
| 80 |
+
|
| 81 |
+
def _validate_composite_controller_specific_config(self):
|
| 82 |
+
"""Some aspects of composite controller specific configs, if they exist,
|
| 83 |
+
may only be verified once the part controller are initialized."""
|
| 84 |
+
pass
|
| 85 |
+
|
| 86 |
+
def setup_action_split_idx(self):
|
| 87 |
+
previous_idx = 0
|
| 88 |
+
last_idx = 0
|
| 89 |
+
for part_name, controller in self.part_controllers.items():
|
| 90 |
+
if part_name in self.grippers.keys():
|
| 91 |
+
last_idx += self.grippers[part_name].dof
|
| 92 |
+
else:
|
| 93 |
+
last_idx += controller.control_dim
|
| 94 |
+
self._action_split_indexes[part_name] = (previous_idx, last_idx)
|
| 95 |
+
previous_idx = last_idx
|
| 96 |
+
|
| 97 |
+
def set_goal(self, all_action):
|
| 98 |
+
for part_name, controller in self.part_controllers.items():
|
| 99 |
+
start_idx, end_idx = self._action_split_indexes[part_name]
|
| 100 |
+
action = all_action[start_idx:end_idx]
|
| 101 |
+
if part_name in self.grippers.keys():
|
| 102 |
+
action = self.grippers[part_name].format_action(action)
|
| 103 |
+
controller.set_goal(action)
|
| 104 |
+
|
| 105 |
+
def reset(self):
|
| 106 |
+
for part_name, controller in self.part_controllers.items():
|
| 107 |
+
controller.reset_goal()
|
| 108 |
+
|
| 109 |
+
def run_controller(self, enabled_parts):
|
| 110 |
+
self.update_state()
|
| 111 |
+
self._applied_action_dict.clear()
|
| 112 |
+
for part_name, controller in self.part_controllers.items():
|
| 113 |
+
if enabled_parts.get(part_name, False):
|
| 114 |
+
self._applied_action_dict[part_name] = controller.run_controller()
|
| 115 |
+
|
| 116 |
+
return self._applied_action_dict
|
| 117 |
+
|
| 118 |
+
def get_control_dim(self, part_name):
|
| 119 |
+
if part_name not in self.part_controllers:
|
| 120 |
+
return 0
|
| 121 |
+
else:
|
| 122 |
+
return self.part_controllers[part_name].control_dim
|
| 123 |
+
|
| 124 |
+
def get_controller_base_pose(self, controller_name):
|
| 125 |
+
"""
|
| 126 |
+
Get the base position and orientation of a specified controller's part. Note: this pose may likely differ from
|
| 127 |
+
the robot base's pose.
|
| 128 |
+
|
| 129 |
+
Args:
|
| 130 |
+
controller_name (str): The name of the controller, used to look up part-specific information.
|
| 131 |
+
|
| 132 |
+
Returns:
|
| 133 |
+
tuple[np.ndarray, np.ndarray]: A tuple containing:
|
| 134 |
+
- base_pos (np.ndarray): The 3D position of the part's center in world coordinates (shape: (3,)).
|
| 135 |
+
- base_ori (np.ndarray): The 3x3 rotation matrix representing the part's orientation in world coordinates.
|
| 136 |
+
|
| 137 |
+
Details:
|
| 138 |
+
- Uses the controller's `naming_prefix` and `part_name` to construct the corresponding site name.
|
| 139 |
+
- Queries the simulation (`self.sim`) for the site's position (`site_xpos`) and orientation (`site_xmat`).
|
| 140 |
+
- The site orientation matrix is reshaped from a flat array of size 9 to a 3x3 rotation matrix.
|
| 141 |
+
"""
|
| 142 |
+
naming_prefix = self.part_controllers[controller_name].naming_prefix
|
| 143 |
+
part_name = self.part_controllers[controller_name].part_name
|
| 144 |
+
base_pos = np.array(self.sim.data.site_xpos[self.sim.model.site_name2id(f"{naming_prefix}{part_name}_center")])
|
| 145 |
+
base_ori = np.array(
|
| 146 |
+
self.sim.data.site_xmat[self.sim.model.site_name2id(f"{naming_prefix}{part_name}_center")].reshape([3, 3])
|
| 147 |
+
)
|
| 148 |
+
return base_pos, base_ori
|
| 149 |
+
|
| 150 |
+
def update_state(self):
|
| 151 |
+
for arm in self.arms:
|
| 152 |
+
base_pos, base_ori = self.get_controller_base_pose(controller_name=arm)
|
| 153 |
+
self.part_controllers[arm].update_origin(base_pos, base_ori)
|
| 154 |
+
|
| 155 |
+
def get_controller(self, part_name):
|
| 156 |
+
return self.part_controllers[part_name]
|
| 157 |
+
|
| 158 |
+
@property
|
| 159 |
+
def action_limits(self):
|
| 160 |
+
low, high = [], []
|
| 161 |
+
for part_name, controller in self.part_controllers.items():
|
| 162 |
+
if part_name not in self.arms:
|
| 163 |
+
if part_name in self.grippers.keys():
|
| 164 |
+
low_g, high_g = (
|
| 165 |
+
[-1] * self.grippers[part_name].dof,
|
| 166 |
+
[1] * self.grippers[part_name].dof,
|
| 167 |
+
)
|
| 168 |
+
low, high = np.concatenate([low, low_g]), np.concatenate([high, high_g])
|
| 169 |
+
else:
|
| 170 |
+
control_dim = controller.control_dim
|
| 171 |
+
low_c, high_c = ([-1] * control_dim, [1] * control_dim)
|
| 172 |
+
low, high = np.concatenate([low, low_c]), np.concatenate([high, high_c])
|
| 173 |
+
else:
|
| 174 |
+
low_c, high_c = controller.control_limits
|
| 175 |
+
low, high = np.concatenate([low, low_c]), np.concatenate([high, high_c])
|
| 176 |
+
return low, high
|
| 177 |
+
|
| 178 |
+
def create_action_vector(self, action_dict):
|
| 179 |
+
"""
|
| 180 |
+
A helper function that creates the action vector given a dictionary
|
| 181 |
+
"""
|
| 182 |
+
full_action_vector = np.zeros(self.action_limits[0].shape)
|
| 183 |
+
for part_name, action_vector in action_dict.items():
|
| 184 |
+
if part_name not in self._action_split_indexes:
|
| 185 |
+
ROBOSUITE_DEFAULT_LOGGER.debug(f"{part_name} is not specified in the action space")
|
| 186 |
+
continue
|
| 187 |
+
start_idx, end_idx = self._action_split_indexes[part_name]
|
| 188 |
+
if end_idx - start_idx == 0:
|
| 189 |
+
# skipping not controlling actions
|
| 190 |
+
continue
|
| 191 |
+
assert len(action_vector) == (end_idx - start_idx), ROBOSUITE_DEFAULT_LOGGER.error(
|
| 192 |
+
f"Action vector for {part_name} is not the correct size. Expected {end_idx - start_idx} for {part_name}, got {len(action_vector)}"
|
| 193 |
+
)
|
| 194 |
+
full_action_vector[start_idx:end_idx] = action_vector
|
| 195 |
+
return full_action_vector
|
| 196 |
+
|
| 197 |
+
def create_action_dict_from_action_vector(self, action_vector):
|
| 198 |
+
action_dict = {}
|
| 199 |
+
for part_name, (start_idx, end_idx) in self._action_split_indexes.items():
|
| 200 |
+
action_dict[part_name] = action_vector[start_idx:end_idx]
|
| 201 |
+
return action_dict
|
| 202 |
+
|
| 203 |
+
def get_action_info(self):
|
| 204 |
+
action_index_info = []
|
| 205 |
+
action_dim_info = []
|
| 206 |
+
for part_name, (
|
| 207 |
+
start_idx,
|
| 208 |
+
end_idx,
|
| 209 |
+
) in self._action_split_indexes.items():
|
| 210 |
+
action_dim_info.append(f"{part_name}: {(end_idx - start_idx)} dim")
|
| 211 |
+
action_index_info.append(f"{part_name}: {start_idx}:{end_idx}")
|
| 212 |
+
|
| 213 |
+
return action_index_info, action_dim_info
|
| 214 |
+
|
| 215 |
+
def print_action_info(self):
|
| 216 |
+
action_index_info, action_dim_info = self.get_action_info()
|
| 217 |
+
action_index_info_str = ", ".join(action_index_info)
|
| 218 |
+
action_dim_info_str = ", ".join(action_dim_info)
|
| 219 |
+
ROBOSUITE_DEFAULT_LOGGER.info(f"Action Dimensions: [{action_dim_info_str}]")
|
| 220 |
+
ROBOSUITE_DEFAULT_LOGGER.info(f"Action Indices: [{action_index_info_str}]")
|
| 221 |
+
|
| 222 |
+
def get_action_info_dict(self):
|
| 223 |
+
info_dict = {}
|
| 224 |
+
info_dict["Action Dimension"] = self.action_limits[0].shape
|
| 225 |
+
info_dict.update(dict(self._action_split_indexes))
|
| 226 |
+
return info_dict
|
| 227 |
+
|
| 228 |
+
def print_action_info_dict(self, name: str = ""):
|
| 229 |
+
info_dict = self.get_action_info_dict()
|
| 230 |
+
info_dict_str = f"\nAction Info for {name}:\n\n{json.dumps(dict(info_dict), indent=4)}"
|
| 231 |
+
ROBOSUITE_DEFAULT_LOGGER.info(info_dict_str)
|
| 232 |
+
|
| 233 |
+
|
| 234 |
+
@register_composite_controller
|
| 235 |
+
class HybridMobileBase(CompositeController):
|
| 236 |
+
name = "HYBRID_MOBILE_BASE"
|
| 237 |
+
|
| 238 |
+
def set_goal(self, all_action):
|
| 239 |
+
action_mode = all_action[-1]
|
| 240 |
+
if action_mode > 0:
|
| 241 |
+
update_wrt_origin = True
|
| 242 |
+
else:
|
| 243 |
+
update_wrt_origin = False
|
| 244 |
+
|
| 245 |
+
for part_name, controller in self.part_controllers.items():
|
| 246 |
+
start_idx, end_idx = self._action_split_indexes[part_name]
|
| 247 |
+
action = all_action[start_idx:end_idx]
|
| 248 |
+
if part_name in self.grippers.keys():
|
| 249 |
+
action = self.grippers[part_name].format_action(action)
|
| 250 |
+
|
| 251 |
+
if part_name in self.arms and hasattr(controller, "set_goal_update_mode"):
|
| 252 |
+
"""
|
| 253 |
+
Query the last action dimension to determine if using
|
| 254 |
+
base mode (value > 0) or arm mode (value < 1).
|
| 255 |
+
If in base mode, update the new arm goal based on current desired goal,
|
| 256 |
+
to have the arm tracking with the reset of the moving base
|
| 257 |
+
as closely as possible without lagging or overshooting.
|
| 258 |
+
"""
|
| 259 |
+
action_mode = all_action[-1]
|
| 260 |
+
if action_mode > 0:
|
| 261 |
+
goal_update_mode = "desired"
|
| 262 |
+
else:
|
| 263 |
+
goal_update_mode = "achieved"
|
| 264 |
+
controller.set_goal_update_mode(goal_update_mode)
|
| 265 |
+
|
| 266 |
+
controller.set_goal(action)
|
| 267 |
+
|
| 268 |
+
@property
|
| 269 |
+
def action_limits(self):
|
| 270 |
+
low, high = super().action_limits
|
| 271 |
+
return np.concatenate((low, [-1])), np.concatenate((high, [1]))
|
| 272 |
+
|
| 273 |
+
def create_action_vector(self, action_dict):
|
| 274 |
+
"""
|
| 275 |
+
A helper function that creates the action vector given a dictionary
|
| 276 |
+
"""
|
| 277 |
+
full_action_vector = np.zeros(self.action_limits[0].shape)
|
| 278 |
+
for part_name, action_vector in action_dict.items():
|
| 279 |
+
if part_name not in self._action_split_indexes:
|
| 280 |
+
ROBOSUITE_DEFAULT_LOGGER.debug(f"{part_name} is not specified in the action space")
|
| 281 |
+
continue
|
| 282 |
+
start_idx, end_idx = self._action_split_indexes[part_name]
|
| 283 |
+
if end_idx - start_idx == 0:
|
| 284 |
+
# skipping not controlling actions
|
| 285 |
+
continue
|
| 286 |
+
assert len(action_vector) == (end_idx - start_idx), ROBOSUITE_DEFAULT_LOGGER.error(
|
| 287 |
+
f"Action vector for {part_name} is not the correct size. Expected {end_idx - start_idx} for {part_name}, got {len(action_vector)}"
|
| 288 |
+
)
|
| 289 |
+
full_action_vector[start_idx:end_idx] = action_vector
|
| 290 |
+
full_action_vector[-1] = action_dict.get("base_mode", -1)
|
| 291 |
+
return full_action_vector
|
| 292 |
+
|
| 293 |
+
|
| 294 |
+
@register_composite_controller
|
| 295 |
+
class WholeBody(CompositeController):
|
| 296 |
+
name = "WHOLE_BODY_COMPOSITE"
|
| 297 |
+
|
| 298 |
+
def __init__(self, sim: MjSim, robot_model: RobotModel, grippers: Dict[str, GripperModel]):
|
| 299 |
+
super().__init__(sim, robot_model, grippers)
|
| 300 |
+
|
| 301 |
+
self.joint_action_policy: IKSolver = None
|
| 302 |
+
# TODO: handle different types of joint action policies; joint_action_policy maps
|
| 303 |
+
# task space actions (such as end effector poses) to joint actions (such as joint angles or joint torques)
|
| 304 |
+
|
| 305 |
+
self._whole_body_controller_action_split_indexes: OrderedDict = OrderedDict()
|
| 306 |
+
|
| 307 |
+
def _init_controllers(self):
|
| 308 |
+
for part_name in self.part_controller_config.keys():
|
| 309 |
+
controller_params = self.part_controller_config[part_name]
|
| 310 |
+
self.part_controllers[part_name] = controller_factory(
|
| 311 |
+
part_name=part_name,
|
| 312 |
+
controller_type=self.part_controller_config[part_name]["type"],
|
| 313 |
+
controller_params=controller_params,
|
| 314 |
+
)
|
| 315 |
+
# for whole body composite controller, validate before init_joint_action_policy
|
| 316 |
+
self._validate_composite_controller_specific_config()
|
| 317 |
+
self._init_joint_action_policy()
|
| 318 |
+
|
| 319 |
+
def _init_joint_action_policy(self):
|
| 320 |
+
"""Joint action policy initialization.
|
| 321 |
+
|
| 322 |
+
Joint action policy converts input targets (such as end-effector poses, head poses) to joint actions
|
| 323 |
+
(such as joint angles or joint torques).
|
| 324 |
+
|
| 325 |
+
Examples of joint_action_policy could be an IK policy, a neural network policy, a model predictive controller, etc.
|
| 326 |
+
"""
|
| 327 |
+
raise NotImplementedError("WholeBody CompositeController requires a joint action policy")
|
| 328 |
+
|
| 329 |
+
def setup_action_split_idx(self):
|
| 330 |
+
"""
|
| 331 |
+
Action split indices for the underlying factorized controllers.
|
| 332 |
+
|
| 333 |
+
WholeBody controller takes in a different action space from the
|
| 334 |
+
underlying factorized controllers for individual body parts.
|
| 335 |
+
"""
|
| 336 |
+
previous_idx = 0
|
| 337 |
+
last_idx = 0
|
| 338 |
+
# add joint_action_policy related body parts' action split index first
|
| 339 |
+
for part_name in self.composite_controller_specific_config["actuation_part_names"]:
|
| 340 |
+
try:
|
| 341 |
+
last_idx += self.part_controllers[part_name].control_dim
|
| 342 |
+
except KeyError as e:
|
| 343 |
+
import ipdb
|
| 344 |
+
|
| 345 |
+
ipdb.set_trace()
|
| 346 |
+
raise KeyError(f"Part name '{part_name}' not found in part_controllers: {e}")
|
| 347 |
+
self._action_split_indexes[part_name] = (previous_idx, last_idx)
|
| 348 |
+
previous_idx = last_idx
|
| 349 |
+
|
| 350 |
+
for part_name, controller in self.part_controllers.items():
|
| 351 |
+
if part_name not in self.composite_controller_specific_config["actuation_part_names"]:
|
| 352 |
+
if part_name in self.grippers.keys():
|
| 353 |
+
last_idx += self.grippers[part_name].dof
|
| 354 |
+
else:
|
| 355 |
+
last_idx += controller.control_dim
|
| 356 |
+
self._action_split_indexes[part_name] = (previous_idx, last_idx)
|
| 357 |
+
previous_idx = last_idx
|
| 358 |
+
|
| 359 |
+
self.setup_whole_body_controller_action_split_idx()
|
| 360 |
+
|
| 361 |
+
def setup_whole_body_controller_action_split_idx(self):
|
| 362 |
+
"""
|
| 363 |
+
Action split indices for the composite controller's input action space.
|
| 364 |
+
|
| 365 |
+
WholeBodyIK composite controller takes in a different action space from the
|
| 366 |
+
underlying factorized controllers.
|
| 367 |
+
"""
|
| 368 |
+
# add joint_action_policy's action split indexes first
|
| 369 |
+
self._whole_body_controller_action_split_indexes.update(self.joint_action_policy.action_split_indexes())
|
| 370 |
+
|
| 371 |
+
# prev and last index correspond to the IK solver indexes' last index
|
| 372 |
+
previous_idx = last_idx = list(self._whole_body_controller_action_split_indexes.values())[-1][-1]
|
| 373 |
+
for part_name, controller in self.part_controllers.items():
|
| 374 |
+
if part_name in self.composite_controller_specific_config["actuation_part_names"]:
|
| 375 |
+
continue
|
| 376 |
+
if part_name in self.grippers.keys():
|
| 377 |
+
last_idx += self.grippers[part_name].dof
|
| 378 |
+
else:
|
| 379 |
+
last_idx += controller.control_dim
|
| 380 |
+
self._whole_body_controller_action_split_indexes[part_name] = (previous_idx, last_idx)
|
| 381 |
+
previous_idx = last_idx
|
| 382 |
+
|
| 383 |
+
def set_goal(self, all_action):
|
| 384 |
+
if self.composite_controller_specific_config.get("skip_wbc_action", False):
|
| 385 |
+
super().set_goal(all_action)
|
| 386 |
+
return
|
| 387 |
+
|
| 388 |
+
target_qpos = self.joint_action_policy.solve(all_action[: self.joint_action_policy.control_dim])
|
| 389 |
+
# create new all_action vector with the IK solver's actions first
|
| 390 |
+
all_action = np.concatenate([target_qpos, all_action[self.joint_action_policy.control_dim :]])
|
| 391 |
+
for part_name, controller in self.part_controllers.items():
|
| 392 |
+
start_idx, end_idx = self._action_split_indexes[part_name]
|
| 393 |
+
action = all_action[start_idx:end_idx]
|
| 394 |
+
if part_name in self.grippers.keys():
|
| 395 |
+
action = self.grippers[part_name].format_action(action)
|
| 396 |
+
controller.set_goal(action)
|
| 397 |
+
|
| 398 |
+
def update_state(self):
|
| 399 |
+
# no need for extra update state here, since Jacobians are computed inside the controllers of individual body parts
|
| 400 |
+
return
|
| 401 |
+
|
| 402 |
+
@property
|
| 403 |
+
def action_limits(self):
|
| 404 |
+
"""
|
| 405 |
+
Returns the action limits for the whole body controller.
|
| 406 |
+
Corresponds to each term in the action vector passed to env.step().
|
| 407 |
+
"""
|
| 408 |
+
if self.composite_controller_specific_config.get("skip_wbc_action", False):
|
| 409 |
+
return super().action_limits
|
| 410 |
+
|
| 411 |
+
low, high = [], []
|
| 412 |
+
# assumption: IK solver's actions come first
|
| 413 |
+
low_c, high_c = self.joint_action_policy.control_limits
|
| 414 |
+
low, high = np.concatenate([low, low_c]), np.concatenate([high, high_c])
|
| 415 |
+
for part_name, controller in self.part_controllers.items():
|
| 416 |
+
# Exclude terms that the IK solver handles
|
| 417 |
+
if part_name in self.composite_controller_specific_config["actuation_part_names"]:
|
| 418 |
+
continue
|
| 419 |
+
if part_name not in self.arms:
|
| 420 |
+
if part_name in self.grippers.keys():
|
| 421 |
+
low_g, high_g = (
|
| 422 |
+
[-1] * self.grippers[part_name].dof,
|
| 423 |
+
[1] * self.grippers[part_name].dof,
|
| 424 |
+
)
|
| 425 |
+
low, high = np.concatenate([low, low_g]), np.concatenate([high, high_g])
|
| 426 |
+
else:
|
| 427 |
+
control_dim = controller.control_dim
|
| 428 |
+
low_c, high_c = ([-1] * control_dim, [1] * control_dim)
|
| 429 |
+
low, high = np.concatenate([low, low_c]), np.concatenate([high, high_c])
|
| 430 |
+
else:
|
| 431 |
+
low_c, high_c = controller.control_limits
|
| 432 |
+
low, high = np.concatenate([low, low_c]), np.concatenate([high, high_c])
|
| 433 |
+
return low, high
|
| 434 |
+
|
| 435 |
+
def create_action_vector(self, action_dict: Dict[str, np.ndarray]) -> np.ndarray:
|
| 436 |
+
if self.composite_controller_specific_config.get("skip_wbc_action", False):
|
| 437 |
+
return super().create_action_vector(action_dict)
|
| 438 |
+
|
| 439 |
+
full_action_vector = np.zeros(self.action_limits[0].shape)
|
| 440 |
+
for part_name, action_vector in action_dict.items():
|
| 441 |
+
if part_name not in self._whole_body_controller_action_split_indexes:
|
| 442 |
+
ROBOSUITE_DEFAULT_LOGGER.debug(f"{part_name} is not specified in the action space")
|
| 443 |
+
continue
|
| 444 |
+
start_idx, end_idx = self._whole_body_controller_action_split_indexes[part_name]
|
| 445 |
+
if end_idx - start_idx == 0:
|
| 446 |
+
# skipping not controlling actions
|
| 447 |
+
continue
|
| 448 |
+
assert len(action_vector) == (end_idx - start_idx), ROBOSUITE_DEFAULT_LOGGER.error(
|
| 449 |
+
f"Action vector for {part_name} is not the correct size. Expected {end_idx - start_idx} for {part_name}, got {len(action_vector)}"
|
| 450 |
+
)
|
| 451 |
+
full_action_vector[start_idx:end_idx] = action_vector
|
| 452 |
+
return full_action_vector
|
| 453 |
+
|
| 454 |
+
def create_action_dict_from_action_vector(self, action_vector):
|
| 455 |
+
if self.composite_controller_specific_config.get("skip_wbc_action", False):
|
| 456 |
+
return super().create_action_dict_from_action_vector(action_vector)
|
| 457 |
+
|
| 458 |
+
action_dict = {}
|
| 459 |
+
for part_name, (start_idx, end_idx) in self._whole_body_controller_action_split_indexes.items():
|
| 460 |
+
action_dict[part_name] = action_vector[start_idx:end_idx]
|
| 461 |
+
return action_dict
|
| 462 |
+
|
| 463 |
+
def get_action_info(self):
|
| 464 |
+
if self.composite_controller_specific_config.get("skip_wbc_action", False):
|
| 465 |
+
return super().get_action_info()
|
| 466 |
+
|
| 467 |
+
action_index_info = []
|
| 468 |
+
action_dim_info = []
|
| 469 |
+
for part_name, (
|
| 470 |
+
start_idx,
|
| 471 |
+
end_idx,
|
| 472 |
+
) in self._whole_body_controller_action_split_indexes.items():
|
| 473 |
+
action_dim_info.append(f"{part_name}: {(end_idx - start_idx)} dim")
|
| 474 |
+
action_index_info.append(f"{part_name}: {start_idx}:{end_idx}")
|
| 475 |
+
return action_index_info, action_dim_info
|
| 476 |
+
|
| 477 |
+
def print_action_info(self):
|
| 478 |
+
if self.composite_controller_specific_config.get("skip_wbc_action", False):
|
| 479 |
+
return super().print_action_info()
|
| 480 |
+
|
| 481 |
+
action_index_info, action_dim_info = self.get_action_info()
|
| 482 |
+
action_index_info_str = ", ".join(action_index_info)
|
| 483 |
+
action_dim_info_str = ", ".join(action_dim_info)
|
| 484 |
+
ROBOSUITE_DEFAULT_LOGGER.info(f"Action Dimensions: [{action_dim_info_str}]")
|
| 485 |
+
ROBOSUITE_DEFAULT_LOGGER.info(f"Action Indices: [{action_index_info_str}]")
|
| 486 |
+
|
| 487 |
+
def get_action_info_dict(self):
|
| 488 |
+
if self.composite_controller_specific_config.get("skip_wbc_action", False):
|
| 489 |
+
return super().get_action_info_dict()
|
| 490 |
+
|
| 491 |
+
info_dict = {}
|
| 492 |
+
info_dict["Action Dimension"] = self.action_limits[0].shape
|
| 493 |
+
info_dict.update(dict(self._whole_body_controller_action_split_indexes))
|
| 494 |
+
return info_dict
|
| 495 |
+
|
| 496 |
+
def get_action_info_dict(self):
|
| 497 |
+
if self.composite_controller_specific_config.get("skip_wbc_action", False):
|
| 498 |
+
return super().get_action_info_dict()
|
| 499 |
+
|
| 500 |
+
info_dict = {}
|
| 501 |
+
info_dict["Action Dimension"] = self.action_limits[0].shape
|
| 502 |
+
info_dict.update(dict(self._whole_body_controller_action_split_indexes))
|
| 503 |
+
return info_dict
|
| 504 |
+
|
| 505 |
+
def print_action_info_dict(self, name: str = ""):
|
| 506 |
+
if self.composite_controller_specific_config.get("skip_wbc_action", False):
|
| 507 |
+
return super().print_action_info_dict(name)
|
| 508 |
+
|
| 509 |
+
info_dict = self.get_action_info_dict()
|
| 510 |
+
info_dict_str = f"\nAction Info for {name}:\n\n{json.dumps(dict(info_dict), indent=4)}"
|
| 511 |
+
ROBOSUITE_DEFAULT_LOGGER.info(info_dict_str)
|
| 512 |
+
|
| 513 |
+
|
| 514 |
+
@register_composite_controller
|
| 515 |
+
class WholeBodyIK(WholeBody):
|
| 516 |
+
name = "WHOLE_BODY_IK"
|
| 517 |
+
|
| 518 |
+
def __init__(self, sim: MjSim, robot_model: RobotModel, grippers: Dict[str, GripperModel]):
|
| 519 |
+
super().__init__(sim, robot_model, grippers)
|
| 520 |
+
|
| 521 |
+
def _validate_composite_controller_specific_config(self) -> None:
|
| 522 |
+
# Check that all actuation_part_names exist in part_controllers
|
| 523 |
+
original_ik_controlled_parts = self.composite_controller_specific_config["actuation_part_names"]
|
| 524 |
+
self.valid_ik_controlled_parts = []
|
| 525 |
+
valid_ref_names = []
|
| 526 |
+
|
| 527 |
+
assert (
|
| 528 |
+
"ref_name" in self.composite_controller_specific_config
|
| 529 |
+
), "The 'ref_name' key is missing from composite_controller_specific_config."
|
| 530 |
+
|
| 531 |
+
for part in original_ik_controlled_parts:
|
| 532 |
+
if part in self.part_controllers:
|
| 533 |
+
self.valid_ik_controlled_parts.append(part)
|
| 534 |
+
else:
|
| 535 |
+
ROBOSUITE_DEFAULT_LOGGER.warning(
|
| 536 |
+
f"Part '{part}' specified in 'actuation_part_names' "
|
| 537 |
+
"does not exist in part_controllers. Removing ..."
|
| 538 |
+
)
|
| 539 |
+
|
| 540 |
+
# Update the configuration with only the valid parts
|
| 541 |
+
self.composite_controller_specific_config["actuation_part_names"] = self.valid_ik_controlled_parts
|
| 542 |
+
|
| 543 |
+
# Loop through ref_names and validate against mujoco model
|
| 544 |
+
original_ref_names = self.composite_controller_specific_config.get("ref_name", [])
|
| 545 |
+
for ref_name in original_ref_names:
|
| 546 |
+
if ref_name in self.sim.model.site_names: # Check if the site exists in the mujoco model
|
| 547 |
+
valid_ref_names.append(ref_name)
|
| 548 |
+
else:
|
| 549 |
+
ROBOSUITE_DEFAULT_LOGGER.warning(
|
| 550 |
+
f"Reference name '{ref_name}' specified in configuration"
|
| 551 |
+
" does not exist in the mujoco model. Removing ..."
|
| 552 |
+
)
|
| 553 |
+
|
| 554 |
+
# Update the configuration with only the valid reference names
|
| 555 |
+
self.composite_controller_specific_config["ref_name"] = valid_ref_names
|
| 556 |
+
|
| 557 |
+
def _init_joint_action_policy(self):
|
| 558 |
+
joint_names: str = []
|
| 559 |
+
for part_name in self.composite_controller_specific_config["actuation_part_names"]:
|
| 560 |
+
if part_name in self.part_controllers:
|
| 561 |
+
joint_names += self.part_controllers[part_name].joint_names
|
| 562 |
+
else:
|
| 563 |
+
ROBOSUITE_DEFAULT_LOGGER.warning(
|
| 564 |
+
f"{part_name} is not a valid part name in part_controllers." " Skipping this part for IK control."
|
| 565 |
+
)
|
| 566 |
+
|
| 567 |
+
# Compute nullspace gains, Kn.
|
| 568 |
+
Kn = get_nullspace_gains(joint_names, self.composite_controller_specific_config["nullspace_joint_weights"])
|
| 569 |
+
mocap_bodies = []
|
| 570 |
+
robot_config = {
|
| 571 |
+
"end_effector_sites": self.composite_controller_specific_config["ref_name"],
|
| 572 |
+
"joint_names": joint_names,
|
| 573 |
+
"mocap_bodies": mocap_bodies,
|
| 574 |
+
"nullspace_gains": Kn,
|
| 575 |
+
}
|
| 576 |
+
self.joint_action_policy = IKSolver(
|
| 577 |
+
model=self.sim.model._model,
|
| 578 |
+
data=self.sim.data._data,
|
| 579 |
+
robot_config=robot_config,
|
| 580 |
+
damping=self.composite_controller_specific_config.get("ik_pseudo_inverse_damping", 5e-2),
|
| 581 |
+
integration_dt=self.composite_controller_specific_config.get("ik_integration_dt", 0.1),
|
| 582 |
+
max_dq=self.composite_controller_specific_config.get("ik_max_dq", 4),
|
| 583 |
+
max_dq_torso=self.composite_controller_specific_config.get("ik_max_dq_torso", 0.2),
|
| 584 |
+
input_rotation_repr=self.composite_controller_specific_config.get("ik_input_rotation_repr", "axis_angle"),
|
| 585 |
+
input_ref_frame=self.composite_controller_specific_config.get("ik_input_ref_frame", "world"),
|
| 586 |
+
input_type=self.composite_controller_specific_config.get("ik_input_type", "axis_angle"),
|
| 587 |
+
debug=self.composite_controller_specific_config.get("verbose", False),
|
| 588 |
+
)
|
robosuite/controllers/composite/composite_controller_factory.py
ADDED
|
@@ -0,0 +1,156 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import copy
|
| 2 |
+
import json
|
| 3 |
+
import os
|
| 4 |
+
import pathlib
|
| 5 |
+
from typing import Dict, Literal, Optional
|
| 6 |
+
|
| 7 |
+
import robosuite
|
| 8 |
+
from robosuite.controllers.composite.composite_controller import REGISTERED_COMPOSITE_CONTROLLERS_DICT
|
| 9 |
+
from robosuite.controllers.parts.controller_factory import load_part_controller_config
|
| 10 |
+
from robosuite.utils.log_utils import ROBOSUITE_DEFAULT_LOGGER
|
| 11 |
+
|
| 12 |
+
|
| 13 |
+
def validate_composite_controller_config(config: dict):
|
| 14 |
+
# Check top-level keys
|
| 15 |
+
required_keys = ["type", "body_parts"]
|
| 16 |
+
for key in required_keys:
|
| 17 |
+
if key not in config:
|
| 18 |
+
ROBOSUITE_DEFAULT_LOGGER.error(f"Missing top-level key: {key}")
|
| 19 |
+
raise ValueError
|
| 20 |
+
|
| 21 |
+
|
| 22 |
+
def is_part_controller_config(config: Dict):
|
| 23 |
+
"""
|
| 24 |
+
Checks if a controller config is a part config as a opposed to a composite
|
| 25 |
+
controller config.
|
| 26 |
+
|
| 27 |
+
Args:
|
| 28 |
+
config (dict): Controller configuration
|
| 29 |
+
|
| 30 |
+
Returns:
|
| 31 |
+
bool: True if the config is in the for the arm-only, False otherwise
|
| 32 |
+
"""
|
| 33 |
+
|
| 34 |
+
PART_CONTROLLER_TYPES = ["JOINT_VELOCITY", "JOINT_TORQUE", "JOINT_POSITION", "OSC_POSITION", "OSC_POSE", "IK_POSE"]
|
| 35 |
+
if "body_parts" not in config and "type" in config:
|
| 36 |
+
return config["type"] in PART_CONTROLLER_TYPES
|
| 37 |
+
return False
|
| 38 |
+
|
| 39 |
+
|
| 40 |
+
def refactor_composite_controller_config(controller_config, robot_type, arms):
|
| 41 |
+
"""
|
| 42 |
+
Checks if a controller config is in the format from robosuite versions <= 1.4.1.
|
| 43 |
+
If this is the case, converts the controller config to the new composite controller
|
| 44 |
+
config format in robosuite versions >= 1.5. If the robot has a default
|
| 45 |
+
controller config use that and override the arms with the old controller config.
|
| 46 |
+
If not just use the old controller config for arms.
|
| 47 |
+
|
| 48 |
+
Args:
|
| 49 |
+
old_controller_config (dict): Old controller config
|
| 50 |
+
|
| 51 |
+
Returns:
|
| 52 |
+
dict: New controller config
|
| 53 |
+
"""
|
| 54 |
+
if not is_part_controller_config(controller_config):
|
| 55 |
+
return controller_config
|
| 56 |
+
|
| 57 |
+
config_dir = pathlib.Path(robosuite.__file__).parent / "controllers/config/robots/"
|
| 58 |
+
name = robot_type.lower()
|
| 59 |
+
configs = os.listdir(config_dir)
|
| 60 |
+
if f"default_{name}.json" in configs:
|
| 61 |
+
new_controller_config = load_composite_controller_config(robot=name)
|
| 62 |
+
else:
|
| 63 |
+
new_controller_config = {}
|
| 64 |
+
new_controller_config["type"] = "BASIC"
|
| 65 |
+
new_controller_config["body_parts"] = {}
|
| 66 |
+
|
| 67 |
+
for arm in arms:
|
| 68 |
+
new_controller_config["body_parts"][arm] = copy.deepcopy(controller_config)
|
| 69 |
+
new_controller_config["body_parts"][arm]["gripper"] = {"type": "GRIP"}
|
| 70 |
+
return new_controller_config
|
| 71 |
+
|
| 72 |
+
|
| 73 |
+
def load_composite_controller_config(controller: Optional[str] = None, robot: Optional[str] = None) -> Optional[Dict]:
|
| 74 |
+
"""
|
| 75 |
+
Utility function that loads the desired composite controller and returns the loaded configuration as a dict
|
| 76 |
+
|
| 77 |
+
Args:
|
| 78 |
+
controller: Name or path of the controller to load.
|
| 79 |
+
If None, robot must be specified and we load the robot's default controller in controllers/config/robots/.
|
| 80 |
+
If specified, must be a valid controller name or path to a controller config file.
|
| 81 |
+
robot: Name of the robot to load the controller for.
|
| 82 |
+
|
| 83 |
+
Returns:
|
| 84 |
+
dict: Controller configuration
|
| 85 |
+
|
| 86 |
+
Raises:
|
| 87 |
+
FileNotFoundError: If the controller file is not found
|
| 88 |
+
"""
|
| 89 |
+
# Determine the controller file path
|
| 90 |
+
if controller is None:
|
| 91 |
+
assert robot is not None, "If controller is None, robot must be specified."
|
| 92 |
+
# Load robot's controller
|
| 93 |
+
robot_name = _get_robot_name(robot)
|
| 94 |
+
controller_fpath = (
|
| 95 |
+
pathlib.Path(robosuite.__file__).parent / f"controllers/config/robots/default_{robot_name}.json"
|
| 96 |
+
)
|
| 97 |
+
if not os.path.exists(controller_fpath):
|
| 98 |
+
controller_fpath = (
|
| 99 |
+
pathlib.Path(robosuite.__file__).parent / "controllers/config/default/composite/basic.json"
|
| 100 |
+
)
|
| 101 |
+
elif isinstance(controller, str):
|
| 102 |
+
if controller.endswith(".json"):
|
| 103 |
+
# Use the specified path directly
|
| 104 |
+
controller_fpath = controller
|
| 105 |
+
else:
|
| 106 |
+
assert (
|
| 107 |
+
controller in REGISTERED_COMPOSITE_CONTROLLERS_DICT
|
| 108 |
+
), f"Controller {controller} not found in COMPOSITE_CONTROLLERS_DICT"
|
| 109 |
+
# Load from robosuite/controllers/config/default/composite/
|
| 110 |
+
controller_name = controller.lower()
|
| 111 |
+
controller_fpath = (
|
| 112 |
+
pathlib.Path(robosuite.__file__).parent / f"controllers/config/default/composite/{controller_name}.json"
|
| 113 |
+
)
|
| 114 |
+
else:
|
| 115 |
+
raise ValueError("Controller must be None or a string.")
|
| 116 |
+
|
| 117 |
+
# Attempt to load the controller
|
| 118 |
+
try:
|
| 119 |
+
with open(controller_fpath) as f:
|
| 120 |
+
composite_controller_config = json.load(f)
|
| 121 |
+
ROBOSUITE_DEFAULT_LOGGER.info(f"Loading controller configuration from: {controller_fpath}")
|
| 122 |
+
except FileNotFoundError:
|
| 123 |
+
ROBOSUITE_DEFAULT_LOGGER.error(
|
| 124 |
+
f"Error opening controller filepath at: {controller_fpath}. Please check filepath and try again."
|
| 125 |
+
)
|
| 126 |
+
raise
|
| 127 |
+
|
| 128 |
+
validate_composite_controller_config(composite_controller_config)
|
| 129 |
+
body_parts_controller_configs = composite_controller_config.pop("body_parts", {})
|
| 130 |
+
composite_controller_config["body_parts"] = {}
|
| 131 |
+
for part_name, part_config in body_parts_controller_configs.items():
|
| 132 |
+
if part_name == "arms":
|
| 133 |
+
for arm_name, arm_config in part_config.items():
|
| 134 |
+
composite_controller_config["body_parts"][arm_name] = arm_config
|
| 135 |
+
else:
|
| 136 |
+
composite_controller_config["body_parts"][part_name] = part_config
|
| 137 |
+
|
| 138 |
+
return composite_controller_config
|
| 139 |
+
|
| 140 |
+
|
| 141 |
+
def _get_robot_name(robot: str) -> str:
|
| 142 |
+
"""Helper function to get the standardized robot name."""
|
| 143 |
+
if "GR1FloatingBody" in robot:
|
| 144 |
+
return "gr1_floating_body"
|
| 145 |
+
elif "GR1FixedLowerBody" in robot:
|
| 146 |
+
return "gr1_fixed_lower_body"
|
| 147 |
+
elif "GR1" in robot:
|
| 148 |
+
return "gr1"
|
| 149 |
+
elif "G1" in robot:
|
| 150 |
+
return "g1"
|
| 151 |
+
elif "H1" in robot:
|
| 152 |
+
return "h1"
|
| 153 |
+
elif "PandaDex" in robot:
|
| 154 |
+
return "panda_dex"
|
| 155 |
+
else:
|
| 156 |
+
return robot.lower()
|
robosuite/controllers/config/default/composite/basic.json
ADDED
|
@@ -0,0 +1,97 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "BASIC",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP"
|
| 25 |
+
}
|
| 26 |
+
},
|
| 27 |
+
"left": {
|
| 28 |
+
"type": "OSC_POSE",
|
| 29 |
+
"input_max": 1,
|
| 30 |
+
"input_min": -1,
|
| 31 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 32 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 33 |
+
"kp": 150,
|
| 34 |
+
"damping_ratio": 1,
|
| 35 |
+
"impedance_mode": "fixed",
|
| 36 |
+
"kp_limits": [0, 300],
|
| 37 |
+
"damping_ratio_limits": [0, 10],
|
| 38 |
+
"position_limits": null,
|
| 39 |
+
"orientation_limits": null,
|
| 40 |
+
"uncouple_pos_ori": true,
|
| 41 |
+
"input_type": "delta",
|
| 42 |
+
"input_ref_frame": "base",
|
| 43 |
+
"interpolation": null,
|
| 44 |
+
"ramp_ratio": 0.2,
|
| 45 |
+
"gripper": {
|
| 46 |
+
"type": "GRIP"
|
| 47 |
+
}
|
| 48 |
+
}
|
| 49 |
+
},
|
| 50 |
+
"torso": {
|
| 51 |
+
"type" : "JOINT_POSITION",
|
| 52 |
+
"input_max": 1,
|
| 53 |
+
"input_min": -1,
|
| 54 |
+
"output_max": 0.5,
|
| 55 |
+
"output_min": -0.5,
|
| 56 |
+
"kd": 200,
|
| 57 |
+
"kv": 200,
|
| 58 |
+
"kp": 1000,
|
| 59 |
+
"velocity_limits": [-1,1],
|
| 60 |
+
"kp_limits": [0, 1000],
|
| 61 |
+
"interpolation": null,
|
| 62 |
+
"ramp_ratio": 0.2
|
| 63 |
+
},
|
| 64 |
+
"head": {
|
| 65 |
+
"type" : "JOINT_POSITION",
|
| 66 |
+
"input_max": 1,
|
| 67 |
+
"input_min": -1,
|
| 68 |
+
"output_max": 0.5,
|
| 69 |
+
"output_min": -0.5,
|
| 70 |
+
"kd": 200,
|
| 71 |
+
"kv": 200,
|
| 72 |
+
"kp": 1000,
|
| 73 |
+
"velocity_limits": [-1,1],
|
| 74 |
+
"kp_limits": [0, 1000],
|
| 75 |
+
"interpolation": null,
|
| 76 |
+
"ramp_ratio": 0.2
|
| 77 |
+
},
|
| 78 |
+
"base": {
|
| 79 |
+
"type": "JOINT_VELOCITY",
|
| 80 |
+
"interpolation": "null"
|
| 81 |
+
},
|
| 82 |
+
"legs": {
|
| 83 |
+
"type": "JOINT_POSITION",
|
| 84 |
+
"input_max": 1,
|
| 85 |
+
"input_min": -1,
|
| 86 |
+
"output_max": 0.5,
|
| 87 |
+
"output_min": -0.5,
|
| 88 |
+
"kd": 200,
|
| 89 |
+
"kv": 200,
|
| 90 |
+
"kp": 1000,
|
| 91 |
+
"velocity_limits": [-1,1],
|
| 92 |
+
"kp_limits": [0, 1000],
|
| 93 |
+
"interpolation": null,
|
| 94 |
+
"ramp_ratio": 0.2
|
| 95 |
+
}
|
| 96 |
+
}
|
| 97 |
+
}
|
robosuite/controllers/config/default/composite/hybrid_mobile_base.json
ADDED
|
@@ -0,0 +1,97 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "HYBRID_MOBILE_BASE",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP"
|
| 25 |
+
}
|
| 26 |
+
},
|
| 27 |
+
"left": {
|
| 28 |
+
"type": "OSC_POSE",
|
| 29 |
+
"input_max": 1,
|
| 30 |
+
"input_min": -1,
|
| 31 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 32 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 33 |
+
"kp": 150,
|
| 34 |
+
"damping_ratio": 1,
|
| 35 |
+
"impedance_mode": "fixed",
|
| 36 |
+
"kp_limits": [0, 300],
|
| 37 |
+
"damping_ratio_limits": [0, 10],
|
| 38 |
+
"position_limits": null,
|
| 39 |
+
"orientation_limits": null,
|
| 40 |
+
"uncouple_pos_ori": true,
|
| 41 |
+
"input_type": "delta",
|
| 42 |
+
"input_ref_frame": "base",
|
| 43 |
+
"interpolation": null,
|
| 44 |
+
"ramp_ratio": 0.2,
|
| 45 |
+
"gripper": {
|
| 46 |
+
"type": "GRIP"
|
| 47 |
+
}
|
| 48 |
+
}
|
| 49 |
+
},
|
| 50 |
+
"torso": {
|
| 51 |
+
"type" : "JOINT_POSITION",
|
| 52 |
+
"input_max": 1,
|
| 53 |
+
"input_min": -1,
|
| 54 |
+
"output_max": 0.5,
|
| 55 |
+
"output_min": -0.5,
|
| 56 |
+
"kd": 200,
|
| 57 |
+
"kv": 200,
|
| 58 |
+
"kp": 1000,
|
| 59 |
+
"velocity_limits": [-1,1],
|
| 60 |
+
"kp_limits": [0, 1000],
|
| 61 |
+
"interpolation": null,
|
| 62 |
+
"ramp_ratio": 0.2
|
| 63 |
+
},
|
| 64 |
+
"head": {
|
| 65 |
+
"type" : "JOINT_POSITION",
|
| 66 |
+
"input_max": 1,
|
| 67 |
+
"input_min": -1,
|
| 68 |
+
"output_max": 0.5,
|
| 69 |
+
"output_min": -0.5,
|
| 70 |
+
"kd": 200,
|
| 71 |
+
"kv": 200,
|
| 72 |
+
"kp": 1000,
|
| 73 |
+
"velocity_limits": [-1,1],
|
| 74 |
+
"kp_limits": [0, 1000],
|
| 75 |
+
"interpolation": null,
|
| 76 |
+
"ramp_ratio": 0.2
|
| 77 |
+
},
|
| 78 |
+
"base": {
|
| 79 |
+
"type": "JOINT_VELOCITY",
|
| 80 |
+
"interpolation": "null"
|
| 81 |
+
},
|
| 82 |
+
"legs": {
|
| 83 |
+
"type": "JOINT_POSITION",
|
| 84 |
+
"input_max": 1,
|
| 85 |
+
"input_min": -1,
|
| 86 |
+
"output_max": 0.5,
|
| 87 |
+
"output_min": -0.5,
|
| 88 |
+
"kd": 200,
|
| 89 |
+
"kv": 200,
|
| 90 |
+
"kp": 1000,
|
| 91 |
+
"velocity_limits": [-1,1],
|
| 92 |
+
"kp_limits": [0, 1000],
|
| 93 |
+
"interpolation": null,
|
| 94 |
+
"ramp_ratio": 0.2
|
| 95 |
+
}
|
| 96 |
+
}
|
| 97 |
+
}
|
robosuite/controllers/config/default/composite/whole_body_ik.json
ADDED
|
@@ -0,0 +1,115 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "WHOLE_BODY_IK",
|
| 3 |
+
"composite_controller_specific_configs": {
|
| 4 |
+
"ref_name": ["gripper0_right_grip_site", "gripper0_left_grip_site"],
|
| 5 |
+
"interpolation": null,
|
| 6 |
+
"actuation_part_names": ["torso", "head", "right", "left", "base", "legs"],
|
| 7 |
+
"max_dq": 4,
|
| 8 |
+
"nullspace_joint_weights": {
|
| 9 |
+
"robot0_torso_waist_yaw": 100.0,
|
| 10 |
+
"robot0_torso_waist_pitch": 100.0,
|
| 11 |
+
"robot0_torso_waist_roll": 500.0,
|
| 12 |
+
"robot0_l_shoulder_pitch": 4.0,
|
| 13 |
+
"robot0_r_shoulder_pitch": 4.0,
|
| 14 |
+
"robot0_l_shoulder_roll": 3.0,
|
| 15 |
+
"robot0_r_shoulder_roll": 3.0,
|
| 16 |
+
"robot0_l_shoulder_yaw": 2.0,
|
| 17 |
+
"robot0_r_shoulder_yaw": 2.0
|
| 18 |
+
},
|
| 19 |
+
"ik_pseudo_inverse_damping": 5e-2,
|
| 20 |
+
"ik_integration_dt": 1e-1,
|
| 21 |
+
"ik_max_dq": 4.0,
|
| 22 |
+
"ik_max_dq_torso": 0.2,
|
| 23 |
+
"ik_input_type": "absolute",
|
| 24 |
+
"ik_input_rotation_repr": "axis_angle",
|
| 25 |
+
"verbose": false
|
| 26 |
+
},
|
| 27 |
+
"body_parts": {
|
| 28 |
+
"arms": {
|
| 29 |
+
"right": {
|
| 30 |
+
"type" : "JOINT_POSITION",
|
| 31 |
+
"input_max": 1,
|
| 32 |
+
"input_min": -1,
|
| 33 |
+
"input_type": "absolute",
|
| 34 |
+
"output_max": 0.5,
|
| 35 |
+
"output_min": -0.5,
|
| 36 |
+
"kd": 200,
|
| 37 |
+
"kv": 200,
|
| 38 |
+
"kp": 1000,
|
| 39 |
+
"velocity_limits": [-1,1],
|
| 40 |
+
"kp_limits": [0, 1000],
|
| 41 |
+
"interpolation": null,
|
| 42 |
+
"ramp_ratio": 0.2,
|
| 43 |
+
"gripper": {
|
| 44 |
+
"type": "GRIP"
|
| 45 |
+
}
|
| 46 |
+
},
|
| 47 |
+
"left": {
|
| 48 |
+
"type" : "JOINT_POSITION",
|
| 49 |
+
"input_max": 1,
|
| 50 |
+
"input_min": -1,
|
| 51 |
+
"input_type": "absolute",
|
| 52 |
+
"output_max": 0.5,
|
| 53 |
+
"output_min": -0.5,
|
| 54 |
+
"kd": 200,
|
| 55 |
+
"kv": 200,
|
| 56 |
+
"kp": 1000,
|
| 57 |
+
"velocity_limits": [-1,1],
|
| 58 |
+
"kp_limits": [0, 1000],
|
| 59 |
+
"interpolation": null,
|
| 60 |
+
"ramp_ratio": 0.2,
|
| 61 |
+
"gripper": {
|
| 62 |
+
"type": "GRIP"
|
| 63 |
+
}
|
| 64 |
+
}
|
| 65 |
+
},
|
| 66 |
+
"torso": {
|
| 67 |
+
"type" : "JOINT_POSITION",
|
| 68 |
+
"input_max": 1,
|
| 69 |
+
"input_min": -1,
|
| 70 |
+
"input_type": "absolute",
|
| 71 |
+
"output_max": 0.5,
|
| 72 |
+
"output_min": -0.5,
|
| 73 |
+
"kd": 200,
|
| 74 |
+
"kv": 200,
|
| 75 |
+
"kp": 1000,
|
| 76 |
+
"velocity_limits": [-1,1],
|
| 77 |
+
"kp_limits": [0, 1000],
|
| 78 |
+
"interpolation": null,
|
| 79 |
+
"ramp_ratio": 0.2
|
| 80 |
+
},
|
| 81 |
+
"head": {
|
| 82 |
+
"type" : "JOINT_POSITION",
|
| 83 |
+
"input_max": 1,
|
| 84 |
+
"input_min": -1,
|
| 85 |
+
"input_type": "absolute",
|
| 86 |
+
"output_max": 0.5,
|
| 87 |
+
"output_min": -0.5,
|
| 88 |
+
"kd": 200,
|
| 89 |
+
"kv": 200,
|
| 90 |
+
"kp": 1000,
|
| 91 |
+
"velocity_limits": [-1,1],
|
| 92 |
+
"kp_limits": [0, 1000],
|
| 93 |
+
"interpolation": null,
|
| 94 |
+
"ramp_ratio": 0.2
|
| 95 |
+
},
|
| 96 |
+
"base": {
|
| 97 |
+
"type" : "JOINT_VELOCITY",
|
| 98 |
+
"interpolation": null
|
| 99 |
+
},
|
| 100 |
+
"legs": {
|
| 101 |
+
"type": "JOINT_POSITION",
|
| 102 |
+
"input_max": 1,
|
| 103 |
+
"input_min": -1,
|
| 104 |
+
"output_max": 0.5,
|
| 105 |
+
"output_min": -0.5,
|
| 106 |
+
"kd": 200,
|
| 107 |
+
"kv": 200,
|
| 108 |
+
"kp": 1000,
|
| 109 |
+
"velocity_limits": [-1,1],
|
| 110 |
+
"kp_limits": [0, 1000],
|
| 111 |
+
"interpolation": null,
|
| 112 |
+
"ramp_ratio": 0.2
|
| 113 |
+
}
|
| 114 |
+
}
|
| 115 |
+
}
|
robosuite/controllers/config/default/composite/whole_body_mink_ik.json
ADDED
|
@@ -0,0 +1,101 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "WHOLE_BODY_MINK_IK",
|
| 3 |
+
"composite_controller_specific_configs": {
|
| 4 |
+
"ref_name": ["gripper0_right_grip_site", "gripper0_left_grip_site"],
|
| 5 |
+
"interpolation": null,
|
| 6 |
+
"actuation_part_names": ["torso", "head", "right", "left"],
|
| 7 |
+
"max_dq": 4,
|
| 8 |
+
"ik_pseudo_inverse_damping": 5e-2,
|
| 9 |
+
"ik_integration_dt": 1e-1,
|
| 10 |
+
"ik_input_type": "absolute",
|
| 11 |
+
"ik_input_ref_frame": "world",
|
| 12 |
+
"ik_input_rotation_repr": "axis_angle",
|
| 13 |
+
"verbose": false,
|
| 14 |
+
"ik_posture_weights": {
|
| 15 |
+
"robot0_torso_waist_yaw": 10.0,
|
| 16 |
+
"robot0_torso_waist_pitch": 10.0,
|
| 17 |
+
"robot0_torso_waist_roll": 200.0,
|
| 18 |
+
"robot0_l_shoulder_pitch": 4.0,
|
| 19 |
+
"robot0_r_shoulder_pitch": 4.0,
|
| 20 |
+
"robot0_l_shoulder_roll": 3.0,
|
| 21 |
+
"robot0_r_shoulder_roll": 3.0,
|
| 22 |
+
"robot0_l_shoulder_yaw": 2.0,
|
| 23 |
+
"robot0_r_shoulder_yaw": 2.0
|
| 24 |
+
},
|
| 25 |
+
"ik_hand_pos_cost": 1.0,
|
| 26 |
+
"ik_hand_ori_cost": 0.5,
|
| 27 |
+
"use_joint_angle_action_input": false
|
| 28 |
+
},
|
| 29 |
+
"body_parts": {
|
| 30 |
+
"arms": {
|
| 31 |
+
"right": {
|
| 32 |
+
"type" : "JOINT_POSITION",
|
| 33 |
+
"input_max": 1,
|
| 34 |
+
"input_min": -1,
|
| 35 |
+
"input_type": "absolute",
|
| 36 |
+
"output_max": 0.5,
|
| 37 |
+
"output_min": -0.5,
|
| 38 |
+
"kd": 200,
|
| 39 |
+
"kv": 200,
|
| 40 |
+
"kp": 1000,
|
| 41 |
+
"velocity_limits": [-1,1],
|
| 42 |
+
"kp_limits": [0, 1000],
|
| 43 |
+
"interpolation": null,
|
| 44 |
+
"ramp_ratio": 0.2,
|
| 45 |
+
"gripper": {
|
| 46 |
+
"type": "GRIP",
|
| 47 |
+
"use_action_scaling": false
|
| 48 |
+
}
|
| 49 |
+
},
|
| 50 |
+
"left": {
|
| 51 |
+
"type" : "JOINT_POSITION",
|
| 52 |
+
"input_max": 1,
|
| 53 |
+
"input_min": -1,
|
| 54 |
+
"input_type": "absolute",
|
| 55 |
+
"output_max": 0.5,
|
| 56 |
+
"output_min": -0.5,
|
| 57 |
+
"kd": 200,
|
| 58 |
+
"kv": 200,
|
| 59 |
+
"kp": 1000,
|
| 60 |
+
"velocity_limits": [-1,1],
|
| 61 |
+
"kp_limits": [0, 1000],
|
| 62 |
+
"interpolation": null,
|
| 63 |
+
"ramp_ratio": 0.2,
|
| 64 |
+
"gripper": {
|
| 65 |
+
"type": "GRIP",
|
| 66 |
+
"use_action_scaling": false
|
| 67 |
+
}
|
| 68 |
+
}
|
| 69 |
+
},
|
| 70 |
+
"torso": {
|
| 71 |
+
"type" : "JOINT_POSITION",
|
| 72 |
+
"input_max": 1,
|
| 73 |
+
"input_min": -1,
|
| 74 |
+
"input_type": "absolute",
|
| 75 |
+
"output_max": 0.5,
|
| 76 |
+
"output_min": -0.5,
|
| 77 |
+
"kd": 200,
|
| 78 |
+
"kv": 200,
|
| 79 |
+
"kp": 1000,
|
| 80 |
+
"velocity_limits": [-1,1],
|
| 81 |
+
"kp_limits": [0, 1000],
|
| 82 |
+
"interpolation": null,
|
| 83 |
+
"ramp_ratio": 0.2
|
| 84 |
+
},
|
| 85 |
+
"head": {
|
| 86 |
+
"type" : "JOINT_POSITION",
|
| 87 |
+
"input_max": 1,
|
| 88 |
+
"input_min": -1,
|
| 89 |
+
"input_type": "absolute",
|
| 90 |
+
"output_max": 0.5,
|
| 91 |
+
"output_min": -0.5,
|
| 92 |
+
"kd": 200,
|
| 93 |
+
"kv": 200,
|
| 94 |
+
"kp": 1000,
|
| 95 |
+
"velocity_limits": [-1,1],
|
| 96 |
+
"kp_limits": [0, 1000],
|
| 97 |
+
"interpolation": null,
|
| 98 |
+
"ramp_ratio": 0.2
|
| 99 |
+
}
|
| 100 |
+
}
|
| 101 |
+
}
|
robosuite/controllers/config/default/parts/ik_pose.json
ADDED
|
@@ -0,0 +1,7 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type" : "IK_POSE",
|
| 3 |
+
"ik_pos_limit": 0.02,
|
| 4 |
+
"ik_ori_limit": 0.05,
|
| 5 |
+
"interpolation": null,
|
| 6 |
+
"ramp_ratio": 0.2
|
| 7 |
+
}
|
robosuite/controllers/config/default/parts/joint_position.json
ADDED
|
@@ -0,0 +1,15 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "JOINT_POSITION",
|
| 3 |
+
"input_max": 1,
|
| 4 |
+
"input_min": -1,
|
| 5 |
+
"output_max": 0.05,
|
| 6 |
+
"output_min": -0.05,
|
| 7 |
+
"kp": 50,
|
| 8 |
+
"damping_ratio": 1,
|
| 9 |
+
"impedance_mode": "fixed",
|
| 10 |
+
"kp_limits": [0, 300],
|
| 11 |
+
"damping_ratio_limits": [0, 10],
|
| 12 |
+
"qpos_limits": null,
|
| 13 |
+
"interpolation": null,
|
| 14 |
+
"ramp_ratio": 0.2
|
| 15 |
+
}
|
robosuite/controllers/config/default/parts/joint_torque.json
ADDED
|
@@ -0,0 +1,10 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "JOINT_TORQUE",
|
| 3 |
+
"input_max": 1,
|
| 4 |
+
"input_min": -1,
|
| 5 |
+
"output_max": 0.1,
|
| 6 |
+
"output_min": -0.1,
|
| 7 |
+
"torque_limits": null,
|
| 8 |
+
"interpolation": null,
|
| 9 |
+
"ramp_ratio": 0.2
|
| 10 |
+
}
|
robosuite/controllers/config/default/parts/joint_velocity.json
ADDED
|
@@ -0,0 +1,11 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type" : "JOINT_VELOCITY",
|
| 3 |
+
"input_max": 1,
|
| 4 |
+
"input_min": -1,
|
| 5 |
+
"output_max": 0.5,
|
| 6 |
+
"output_min": -0.5,
|
| 7 |
+
"kp": 3.0,
|
| 8 |
+
"velocity_limits": [-1,1],
|
| 9 |
+
"interpolation": null,
|
| 10 |
+
"ramp_ratio": 0.2
|
| 11 |
+
}
|
robosuite/controllers/config/default/parts/osc_pose.json
ADDED
|
@@ -0,0 +1,19 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "OSC_POSE",
|
| 3 |
+
"input_max": 1,
|
| 4 |
+
"input_min": -1,
|
| 5 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 6 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 7 |
+
"kp": 150,
|
| 8 |
+
"damping_ratio": 1,
|
| 9 |
+
"impedance_mode": "fixed",
|
| 10 |
+
"kp_limits": [0, 300],
|
| 11 |
+
"damping_ratio_limits": [0, 10],
|
| 12 |
+
"position_limits": null,
|
| 13 |
+
"orientation_limits": null,
|
| 14 |
+
"uncouple_pos_ori": true,
|
| 15 |
+
"input_type": "delta",
|
| 16 |
+
"input_ref_frame": "base",
|
| 17 |
+
"interpolation": null,
|
| 18 |
+
"ramp_ratio": 0.2
|
| 19 |
+
}
|
robosuite/controllers/config/default/parts/osc_position.json
ADDED
|
@@ -0,0 +1,17 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "OSC_POSITION",
|
| 3 |
+
"input_max": 1,
|
| 4 |
+
"input_min": -1,
|
| 5 |
+
"output_max": [0.05, 0.05, 0.05],
|
| 6 |
+
"output_min": [-0.05, -0.05, -0.05],
|
| 7 |
+
"kp": 150,
|
| 8 |
+
"damping_ratio": 1,
|
| 9 |
+
"impedance_mode": "fixed",
|
| 10 |
+
"kp_limits": [0, 300],
|
| 11 |
+
"damping_ratio_limits": [0, 10],
|
| 12 |
+
"position_limits": null,
|
| 13 |
+
"input_type": "delta",
|
| 14 |
+
"input_ref_frame": "base",
|
| 15 |
+
"interpolation": null,
|
| 16 |
+
"ramp_ratio": 0.2
|
| 17 |
+
}
|
robosuite/controllers/config/robots/default_baxter.json
ADDED
|
@@ -0,0 +1,51 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "BASIC",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP"
|
| 25 |
+
}
|
| 26 |
+
},
|
| 27 |
+
"left": {
|
| 28 |
+
"type": "OSC_POSE",
|
| 29 |
+
"input_max": 1,
|
| 30 |
+
"input_min": -1,
|
| 31 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 32 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 33 |
+
"kp": 150,
|
| 34 |
+
"damping_ratio": 1,
|
| 35 |
+
"impedance_mode": "fixed",
|
| 36 |
+
"kp_limits": [0, 300],
|
| 37 |
+
"damping_ratio_limits": [0, 10],
|
| 38 |
+
"position_limits": null,
|
| 39 |
+
"orientation_limits": null,
|
| 40 |
+
"uncouple_pos_ori": true,
|
| 41 |
+
"input_type": "delta",
|
| 42 |
+
"input_ref_frame": "base",
|
| 43 |
+
"interpolation": null,
|
| 44 |
+
"ramp_ratio": 0.2,
|
| 45 |
+
"gripper": {
|
| 46 |
+
"type": "GRIP"
|
| 47 |
+
}
|
| 48 |
+
}
|
| 49 |
+
}
|
| 50 |
+
}
|
| 51 |
+
}
|
robosuite/controllers/config/robots/default_gr1.json
ADDED
|
@@ -0,0 +1,118 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "WHOLE_BODY_IK",
|
| 3 |
+
"composite_controller_specific_configs": {
|
| 4 |
+
"ref_name": ["gripper0_right_grip_site", "gripper0_left_grip_site"],
|
| 5 |
+
"interpolation": null,
|
| 6 |
+
"actuation_part_names": ["torso", "head", "right", "left", "base", "legs"],
|
| 7 |
+
"max_dq": 4,
|
| 8 |
+
"nullspace_joint_weights": {
|
| 9 |
+
"robot0_torso_waist_yaw": 100.0,
|
| 10 |
+
"robot0_torso_waist_pitch": 100.0,
|
| 11 |
+
"robot0_torso_waist_roll": 500.0,
|
| 12 |
+
"robot0_l_shoulder_pitch": 4.0,
|
| 13 |
+
"robot0_r_shoulder_pitch": 4.0,
|
| 14 |
+
"robot0_l_shoulder_roll": 3.0,
|
| 15 |
+
"robot0_r_shoulder_roll": 3.0,
|
| 16 |
+
"robot0_l_shoulder_yaw": 2.0,
|
| 17 |
+
"robot0_r_shoulder_yaw": 2.0
|
| 18 |
+
},
|
| 19 |
+
"ik_pseudo_inverse_damping": 5e-2,
|
| 20 |
+
"ik_integration_dt": 1e-1,
|
| 21 |
+
"ik_max_dq": 4.0,
|
| 22 |
+
"ik_max_dq_torso": 0.2,
|
| 23 |
+
"ik_input_type": "absolute",
|
| 24 |
+
"ik_input_ref_frame": "base",
|
| 25 |
+
"ik_input_rotation_repr": "axis_angle",
|
| 26 |
+
"ik_verbose": true
|
| 27 |
+
},
|
| 28 |
+
"body_parts": {
|
| 29 |
+
"arms": {
|
| 30 |
+
"right": {
|
| 31 |
+
"type" : "JOINT_POSITION",
|
| 32 |
+
"input_max": 1,
|
| 33 |
+
"input_min": -1,
|
| 34 |
+
"input_type": "absolute",
|
| 35 |
+
"output_max": 0.5,
|
| 36 |
+
"output_min": -0.5,
|
| 37 |
+
"kd": 200,
|
| 38 |
+
"kv": 200,
|
| 39 |
+
"kp": 1000,
|
| 40 |
+
"velocity_limits": [-1,1],
|
| 41 |
+
"kp_limits": [0, 1000],
|
| 42 |
+
"interpolation": null,
|
| 43 |
+
"ramp_ratio": 0.2,
|
| 44 |
+
"gripper": {
|
| 45 |
+
"type": "GRIP",
|
| 46 |
+
"use_action_scaling": false
|
| 47 |
+
}
|
| 48 |
+
},
|
| 49 |
+
"left": {
|
| 50 |
+
"type" : "JOINT_POSITION",
|
| 51 |
+
"input_max": 1,
|
| 52 |
+
"input_min": -1,
|
| 53 |
+
"input_type": "absolute",
|
| 54 |
+
"output_max": 0.5,
|
| 55 |
+
"output_min": -0.5,
|
| 56 |
+
"kd": 200,
|
| 57 |
+
"kv": 200,
|
| 58 |
+
"kp": 1000,
|
| 59 |
+
"velocity_limits": [-1,1],
|
| 60 |
+
"kp_limits": [0, 1000],
|
| 61 |
+
"interpolation": null,
|
| 62 |
+
"ramp_ratio": 0.2,
|
| 63 |
+
"gripper": {
|
| 64 |
+
"type": "GRIP",
|
| 65 |
+
"use_action_scaling": false
|
| 66 |
+
}
|
| 67 |
+
}
|
| 68 |
+
},
|
| 69 |
+
"torso": {
|
| 70 |
+
"type" : "JOINT_POSITION",
|
| 71 |
+
"input_max": 1,
|
| 72 |
+
"input_min": -1,
|
| 73 |
+
"input_type": "absolute",
|
| 74 |
+
"output_max": 0.5,
|
| 75 |
+
"output_min": -0.5,
|
| 76 |
+
"kd": 200,
|
| 77 |
+
"kv": 200,
|
| 78 |
+
"kp": 1000,
|
| 79 |
+
"velocity_limits": [-1,1],
|
| 80 |
+
"kp_limits": [0, 1000],
|
| 81 |
+
"interpolation": null,
|
| 82 |
+
"ramp_ratio": 0.2
|
| 83 |
+
},
|
| 84 |
+
"head": {
|
| 85 |
+
"type" : "JOINT_POSITION",
|
| 86 |
+
"input_max": 1,
|
| 87 |
+
"input_min": -1,
|
| 88 |
+
"input_type": "absolute",
|
| 89 |
+
"output_max": 0.5,
|
| 90 |
+
"output_min": -0.5,
|
| 91 |
+
"kd": 200,
|
| 92 |
+
"kv": 200,
|
| 93 |
+
"kp": 1000,
|
| 94 |
+
"velocity_limits": [-1,1],
|
| 95 |
+
"kp_limits": [0, 1000],
|
| 96 |
+
"interpolation": null,
|
| 97 |
+
"ramp_ratio": 0.2
|
| 98 |
+
},
|
| 99 |
+
"base": {
|
| 100 |
+
"type": "JOINT_VELOCITY",
|
| 101 |
+
"interpolation": "null"
|
| 102 |
+
},
|
| 103 |
+
"legs": {
|
| 104 |
+
"type": "JOINT_POSITION",
|
| 105 |
+
"input_max": 1,
|
| 106 |
+
"input_min": -1,
|
| 107 |
+
"output_max": 0.5,
|
| 108 |
+
"output_min": -0.5,
|
| 109 |
+
"kd": 200,
|
| 110 |
+
"kv": 200,
|
| 111 |
+
"kp": 1000,
|
| 112 |
+
"velocity_limits": [-1,1],
|
| 113 |
+
"kp_limits": [0, 1000],
|
| 114 |
+
"interpolation": null,
|
| 115 |
+
"ramp_ratio": 0.2
|
| 116 |
+
}
|
| 117 |
+
}
|
| 118 |
+
}
|
robosuite/controllers/config/robots/default_gr1_fixed_lower_body.json
ADDED
|
@@ -0,0 +1,101 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "WHOLE_BODY_MINK_IK",
|
| 3 |
+
"composite_controller_specific_configs": {
|
| 4 |
+
"ref_name": ["gripper0_right_grip_site", "gripper0_left_grip_site"],
|
| 5 |
+
"interpolation": null,
|
| 6 |
+
"actuation_part_names": ["torso", "head", "right", "left"],
|
| 7 |
+
"max_dq": 4,
|
| 8 |
+
"ik_pseudo_inverse_damping": 5e-2,
|
| 9 |
+
"ik_integration_dt": 1e-1,
|
| 10 |
+
"ik_input_type": "absolute",
|
| 11 |
+
"ik_input_ref_frame": "base",
|
| 12 |
+
"ik_input_rotation_repr": "axis_angle",
|
| 13 |
+
"verbose": false,
|
| 14 |
+
"ik_posture_weights": {
|
| 15 |
+
"robot0_torso_waist_yaw": 10.0,
|
| 16 |
+
"robot0_torso_waist_pitch": 10.0,
|
| 17 |
+
"robot0_torso_waist_roll": 200.0,
|
| 18 |
+
"robot0_l_shoulder_pitch": 4.0,
|
| 19 |
+
"robot0_r_shoulder_pitch": 4.0,
|
| 20 |
+
"robot0_l_shoulder_roll": 3.0,
|
| 21 |
+
"robot0_r_shoulder_roll": 3.0,
|
| 22 |
+
"robot0_l_shoulder_yaw": 2.0,
|
| 23 |
+
"robot0_r_shoulder_yaw": 2.0
|
| 24 |
+
},
|
| 25 |
+
"ik_hand_pos_cost": 1.0,
|
| 26 |
+
"ik_hand_ori_cost": 0.5,
|
| 27 |
+
"use_joint_angle_action_input": false
|
| 28 |
+
},
|
| 29 |
+
"body_parts": {
|
| 30 |
+
"arms": {
|
| 31 |
+
"right": {
|
| 32 |
+
"type" : "JOINT_POSITION",
|
| 33 |
+
"input_max": 1,
|
| 34 |
+
"input_min": -1,
|
| 35 |
+
"input_type": "absolute",
|
| 36 |
+
"output_max": 0.5,
|
| 37 |
+
"output_min": -0.5,
|
| 38 |
+
"kd": 200,
|
| 39 |
+
"kv": 200,
|
| 40 |
+
"kp": 1000,
|
| 41 |
+
"velocity_limits": [-1,1],
|
| 42 |
+
"kp_limits": [0, 1000],
|
| 43 |
+
"interpolation": null,
|
| 44 |
+
"ramp_ratio": 0.2,
|
| 45 |
+
"gripper": {
|
| 46 |
+
"type": "GRIP",
|
| 47 |
+
"use_action_scaling": false
|
| 48 |
+
}
|
| 49 |
+
},
|
| 50 |
+
"left": {
|
| 51 |
+
"type" : "JOINT_POSITION",
|
| 52 |
+
"input_max": 1,
|
| 53 |
+
"input_min": -1,
|
| 54 |
+
"input_type": "absolute",
|
| 55 |
+
"output_max": 0.5,
|
| 56 |
+
"output_min": -0.5,
|
| 57 |
+
"kd": 200,
|
| 58 |
+
"kv": 200,
|
| 59 |
+
"kp": 1000,
|
| 60 |
+
"velocity_limits": [-1,1],
|
| 61 |
+
"kp_limits": [0, 1000],
|
| 62 |
+
"interpolation": null,
|
| 63 |
+
"ramp_ratio": 0.2,
|
| 64 |
+
"gripper": {
|
| 65 |
+
"type": "GRIP",
|
| 66 |
+
"use_action_scaling": false
|
| 67 |
+
}
|
| 68 |
+
}
|
| 69 |
+
},
|
| 70 |
+
"torso": {
|
| 71 |
+
"type" : "JOINT_POSITION",
|
| 72 |
+
"input_max": 1,
|
| 73 |
+
"input_min": -1,
|
| 74 |
+
"input_type": "absolute",
|
| 75 |
+
"output_max": 0.5,
|
| 76 |
+
"output_min": -0.5,
|
| 77 |
+
"kd": 200,
|
| 78 |
+
"kv": 200,
|
| 79 |
+
"kp": 1000,
|
| 80 |
+
"velocity_limits": [-1,1],
|
| 81 |
+
"kp_limits": [0, 1000],
|
| 82 |
+
"interpolation": null,
|
| 83 |
+
"ramp_ratio": 0.2
|
| 84 |
+
},
|
| 85 |
+
"head": {
|
| 86 |
+
"type" : "JOINT_POSITION",
|
| 87 |
+
"input_max": 1,
|
| 88 |
+
"input_min": -1,
|
| 89 |
+
"input_type": "absolute",
|
| 90 |
+
"output_max": 0.5,
|
| 91 |
+
"output_min": -0.5,
|
| 92 |
+
"kd": 200,
|
| 93 |
+
"kv": 200,
|
| 94 |
+
"kp": 1000,
|
| 95 |
+
"velocity_limits": [-1,1],
|
| 96 |
+
"kp_limits": [0, 1000],
|
| 97 |
+
"interpolation": null,
|
| 98 |
+
"ramp_ratio": 0.2
|
| 99 |
+
}
|
| 100 |
+
}
|
| 101 |
+
}
|
robosuite/controllers/config/robots/default_gr1_floating_body.json
ADDED
|
@@ -0,0 +1,65 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "HYBRID_MOBILE_BASE",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP",
|
| 25 |
+
"use_action_scaling": false
|
| 26 |
+
}
|
| 27 |
+
},
|
| 28 |
+
"left": {
|
| 29 |
+
"type": "OSC_POSE",
|
| 30 |
+
"input_max": 1,
|
| 31 |
+
"input_min": -1,
|
| 32 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 33 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 34 |
+
"kp": 150,
|
| 35 |
+
"damping_ratio": 1,
|
| 36 |
+
"impedance_mode": "fixed",
|
| 37 |
+
"kp_limits": [0, 300],
|
| 38 |
+
"damping_ratio_limits": [0, 10],
|
| 39 |
+
"position_limits": null,
|
| 40 |
+
"orientation_limits": null,
|
| 41 |
+
"uncouple_pos_ori": true,
|
| 42 |
+
"input_type": "delta",
|
| 43 |
+
"input_ref_frame": "base",
|
| 44 |
+
"interpolation": null,
|
| 45 |
+
"ramp_ratio": 0.2,
|
| 46 |
+
"gripper": {
|
| 47 |
+
"type": "GRIP",
|
| 48 |
+
"use_action_scaling": false
|
| 49 |
+
}
|
| 50 |
+
}
|
| 51 |
+
},
|
| 52 |
+
"torso": {
|
| 53 |
+
"type": "JOINT_POSITION",
|
| 54 |
+
"interpolation": "null"
|
| 55 |
+
},
|
| 56 |
+
"head": {
|
| 57 |
+
"type": "JOINT_POSITION",
|
| 58 |
+
"interpolation": "null"
|
| 59 |
+
},
|
| 60 |
+
"base": {
|
| 61 |
+
"type": "JOINT_VELOCITY",
|
| 62 |
+
"interpolation": "null"
|
| 63 |
+
}
|
| 64 |
+
}
|
| 65 |
+
}
|
robosuite/controllers/config/robots/default_iiwa.json
ADDED
|
@@ -0,0 +1,29 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "BASIC",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP"
|
| 25 |
+
}
|
| 26 |
+
}
|
| 27 |
+
}
|
| 28 |
+
}
|
| 29 |
+
}
|
robosuite/controllers/config/robots/default_kinova3.json
ADDED
|
@@ -0,0 +1,29 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "BASIC",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP"
|
| 25 |
+
}
|
| 26 |
+
}
|
| 27 |
+
}
|
| 28 |
+
}
|
| 29 |
+
}
|
robosuite/controllers/config/robots/default_panda.json
ADDED
|
@@ -0,0 +1,29 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "BASIC",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP"
|
| 25 |
+
}
|
| 26 |
+
}
|
| 27 |
+
}
|
| 28 |
+
}
|
| 29 |
+
}
|
robosuite/controllers/config/robots/default_panda_dex.json
ADDED
|
@@ -0,0 +1,30 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "BASIC",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP",
|
| 25 |
+
"use_action_scaling": false
|
| 26 |
+
}
|
| 27 |
+
}
|
| 28 |
+
}
|
| 29 |
+
}
|
| 30 |
+
}
|
robosuite/controllers/config/robots/default_pandaomron.json
ADDED
|
@@ -0,0 +1,38 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "HYBRID_MOBILE_BASE",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP"
|
| 25 |
+
}
|
| 26 |
+
}
|
| 27 |
+
},
|
| 28 |
+
"torso": {
|
| 29 |
+
"type": "JOINT_POSITION",
|
| 30 |
+
"interpolation": "null",
|
| 31 |
+
"kp": 2000
|
| 32 |
+
},
|
| 33 |
+
"base": {
|
| 34 |
+
"type": "JOINT_VELOCITY",
|
| 35 |
+
"interpolation": "null"
|
| 36 |
+
}
|
| 37 |
+
}
|
| 38 |
+
}
|
robosuite/controllers/config/robots/default_pandaomron_whole_body_ik.json
ADDED
|
@@ -0,0 +1,116 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "WHOLE_BODY_IK",
|
| 3 |
+
"composite_controller_specific_configs": {
|
| 4 |
+
"ref_name": ["gripper0_right_grip_site", "gripper0_left_grip_site"],
|
| 5 |
+
"interpolation": null,
|
| 6 |
+
"actuation_part_names": ["right", "left"],
|
| 7 |
+
"max_dq": 4,
|
| 8 |
+
"nullspace_joint_weights": {
|
| 9 |
+
"robot0_torso_waist_yaw": 100.0,
|
| 10 |
+
"robot0_torso_waist_pitch": 100.0,
|
| 11 |
+
"robot0_torso_waist_roll": 500.0,
|
| 12 |
+
"robot0_l_shoulder_pitch": 4.0,
|
| 13 |
+
"robot0_r_shoulder_pitch": 4.0,
|
| 14 |
+
"robot0_l_shoulder_roll": 3.0,
|
| 15 |
+
"robot0_r_shoulder_roll": 3.0,
|
| 16 |
+
"robot0_l_shoulder_yaw": 2.0,
|
| 17 |
+
"robot0_r_shoulder_yaw": 2.0
|
| 18 |
+
},
|
| 19 |
+
"ik_pseudo_inverse_damping": 5e-2,
|
| 20 |
+
"ik_integration_dt": 1e-1,
|
| 21 |
+
"ik_max_dq": 4.0,
|
| 22 |
+
"ik_max_dq_torso": 0.2,
|
| 23 |
+
"ik_input_type": "absolute",
|
| 24 |
+
"ik_input_ref_frame": "mobilebase0_base",
|
| 25 |
+
"ik_input_rotation_repr": "axis_angle",
|
| 26 |
+
"verbose": false
|
| 27 |
+
},
|
| 28 |
+
"body_parts": {
|
| 29 |
+
"arms": {
|
| 30 |
+
"right": {
|
| 31 |
+
"type" : "JOINT_POSITION",
|
| 32 |
+
"input_max": 1,
|
| 33 |
+
"input_min": -1,
|
| 34 |
+
"input_type": "absolute",
|
| 35 |
+
"output_max": 0.5,
|
| 36 |
+
"output_min": -0.5,
|
| 37 |
+
"kd": 200,
|
| 38 |
+
"kv": 200,
|
| 39 |
+
"kp": 1000,
|
| 40 |
+
"velocity_limits": [-1,1],
|
| 41 |
+
"kp_limits": [0, 1000],
|
| 42 |
+
"interpolation": null,
|
| 43 |
+
"ramp_ratio": 0.2,
|
| 44 |
+
"gripper": {
|
| 45 |
+
"type": "GRIP"
|
| 46 |
+
}
|
| 47 |
+
},
|
| 48 |
+
"left": {
|
| 49 |
+
"type" : "JOINT_POSITION",
|
| 50 |
+
"input_max": 1,
|
| 51 |
+
"input_min": -1,
|
| 52 |
+
"input_type": "absolute",
|
| 53 |
+
"output_max": 0.5,
|
| 54 |
+
"output_min": -0.5,
|
| 55 |
+
"kd": 200,
|
| 56 |
+
"kv": 200,
|
| 57 |
+
"kp": 1000,
|
| 58 |
+
"velocity_limits": [-1,1],
|
| 59 |
+
"kp_limits": [0, 1000],
|
| 60 |
+
"interpolation": null,
|
| 61 |
+
"ramp_ratio": 0.2,
|
| 62 |
+
"gripper": {
|
| 63 |
+
"type": "GRIP"
|
| 64 |
+
}
|
| 65 |
+
}
|
| 66 |
+
},
|
| 67 |
+
"torso": {
|
| 68 |
+
"type" : "JOINT_POSITION",
|
| 69 |
+
"input_max": 1,
|
| 70 |
+
"input_min": -1,
|
| 71 |
+
"input_type": "absolute",
|
| 72 |
+
"output_max": 0.5,
|
| 73 |
+
"output_min": -0.5,
|
| 74 |
+
"kd": 200,
|
| 75 |
+
"kv": 200,
|
| 76 |
+
"kp": 1000,
|
| 77 |
+
"velocity_limits": [-1,1],
|
| 78 |
+
"kp_limits": [0, 1000],
|
| 79 |
+
"interpolation": null,
|
| 80 |
+
"ramp_ratio": 0.2
|
| 81 |
+
},
|
| 82 |
+
"head": {
|
| 83 |
+
"type" : "JOINT_POSITION",
|
| 84 |
+
"input_max": 1,
|
| 85 |
+
"input_min": -1,
|
| 86 |
+
"input_type": "absolute",
|
| 87 |
+
"output_max": 0.5,
|
| 88 |
+
"output_min": -0.5,
|
| 89 |
+
"kd": 200,
|
| 90 |
+
"kv": 200,
|
| 91 |
+
"kp": 1000,
|
| 92 |
+
"velocity_limits": [-1,1],
|
| 93 |
+
"kp_limits": [0, 1000],
|
| 94 |
+
"interpolation": null,
|
| 95 |
+
"ramp_ratio": 0.2
|
| 96 |
+
},
|
| 97 |
+
"base": {
|
| 98 |
+
"type" : "JOINT_VELOCITY",
|
| 99 |
+
"interpolation": null
|
| 100 |
+
},
|
| 101 |
+
"legs": {
|
| 102 |
+
"type": "JOINT_POSITION",
|
| 103 |
+
"input_max": 1,
|
| 104 |
+
"input_min": -1,
|
| 105 |
+
"output_max": 0.5,
|
| 106 |
+
"output_min": -0.5,
|
| 107 |
+
"kd": 200,
|
| 108 |
+
"kv": 200,
|
| 109 |
+
"kp": 1000,
|
| 110 |
+
"velocity_limits": [-1,1],
|
| 111 |
+
"kp_limits": [0, 1000],
|
| 112 |
+
"interpolation": null,
|
| 113 |
+
"ramp_ratio": 0.2
|
| 114 |
+
}
|
| 115 |
+
}
|
| 116 |
+
}
|
robosuite/controllers/config/robots/default_sawyer.json
ADDED
|
@@ -0,0 +1,29 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "BASIC",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP"
|
| 25 |
+
}
|
| 26 |
+
}
|
| 27 |
+
}
|
| 28 |
+
}
|
| 29 |
+
}
|
robosuite/controllers/config/robots/default_spotwitharm.json
ADDED
|
@@ -0,0 +1,43 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "BASIC",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP"
|
| 25 |
+
}
|
| 26 |
+
}
|
| 27 |
+
},
|
| 28 |
+
"legs": {
|
| 29 |
+
"type" : "JOINT_POSITION",
|
| 30 |
+
"input_max": 1,
|
| 31 |
+
"input_min": -1,
|
| 32 |
+
"output_max": 0.5,
|
| 33 |
+
"output_min": -0.5,
|
| 34 |
+
"kd": 200,
|
| 35 |
+
"kv": 200,
|
| 36 |
+
"kp": 1000,
|
| 37 |
+
"velocity_limits": [-1,1],
|
| 38 |
+
"kp_limits": [0, 1000],
|
| 39 |
+
"interpolation": null,
|
| 40 |
+
"ramp_ratio": 0.2
|
| 41 |
+
}
|
| 42 |
+
}
|
| 43 |
+
}
|
robosuite/controllers/config/robots/default_tiago.json
ADDED
|
@@ -0,0 +1,101 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "BASIC",
|
| 3 |
+
"composite_controller_specific_configs": {
|
| 4 |
+
"ref_name": ["gripper0_right_grip_site", "gripper0_left_grip_site"],
|
| 5 |
+
"interpolation": null,
|
| 6 |
+
"max_dq": 4,
|
| 7 |
+
"nullspace_joint_weights": {
|
| 8 |
+
"robot0_torso_lift_joint": 100.0
|
| 9 |
+
},
|
| 10 |
+
"ik_pseudo_inverse_damping": 5e-2,
|
| 11 |
+
"ik_integration_dt": 1e-1,
|
| 12 |
+
"ik_max_dq": 4.0,
|
| 13 |
+
"ik_max_dq_torso": 0.2,
|
| 14 |
+
"ik_input_type": "absolute",
|
| 15 |
+
"ik_input_ref_frame": "base",
|
| 16 |
+
"ik_input_rotation_repr": "axis_angle",
|
| 17 |
+
"verbose": false
|
| 18 |
+
},
|
| 19 |
+
"body_parts": {
|
| 20 |
+
"arms": {
|
| 21 |
+
"right": {
|
| 22 |
+
"type": "OSC_POSE",
|
| 23 |
+
"input_max": 1,
|
| 24 |
+
"input_min": -1,
|
| 25 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 26 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 27 |
+
"kp": 150,
|
| 28 |
+
"damping_ratio": 1,
|
| 29 |
+
"impedance_mode": "fixed",
|
| 30 |
+
"kp_limits": [0, 300],
|
| 31 |
+
"damping_ratio_limits": [0, 10],
|
| 32 |
+
"position_limits": null,
|
| 33 |
+
"orientation_limits": null,
|
| 34 |
+
"uncouple_pos_ori": true,
|
| 35 |
+
"input_type": "delta",
|
| 36 |
+
"input_ref_frame": "base",
|
| 37 |
+
"interpolation": null,
|
| 38 |
+
"ramp_ratio": 0.2,
|
| 39 |
+
"gripper": {
|
| 40 |
+
"type": "GRIP"
|
| 41 |
+
}
|
| 42 |
+
},
|
| 43 |
+
"left": {
|
| 44 |
+
"type": "OSC_POSE",
|
| 45 |
+
"input_max": 1,
|
| 46 |
+
"input_min": -1,
|
| 47 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 48 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 49 |
+
"kp": 150,
|
| 50 |
+
"damping_ratio": 1,
|
| 51 |
+
"impedance_mode": "fixed",
|
| 52 |
+
"kp_limits": [0, 300],
|
| 53 |
+
"damping_ratio_limits": [0, 10],
|
| 54 |
+
"position_limits": null,
|
| 55 |
+
"orientation_limits": null,
|
| 56 |
+
"uncouple_pos_ori": true,
|
| 57 |
+
"input_type": "delta",
|
| 58 |
+
"input_ref_frame": "base",
|
| 59 |
+
"interpolation": null,
|
| 60 |
+
"ramp_ratio": 0.2,
|
| 61 |
+
"gripper": {
|
| 62 |
+
"type": "GRIP"
|
| 63 |
+
}
|
| 64 |
+
}
|
| 65 |
+
},
|
| 66 |
+
"torso": {
|
| 67 |
+
"type" : "JOINT_POSITION",
|
| 68 |
+
"input_max": 1,
|
| 69 |
+
"input_min": -1,
|
| 70 |
+
"input_type": "absolute",
|
| 71 |
+
"output_max": 0.5,
|
| 72 |
+
"output_min": -0.5,
|
| 73 |
+
"kd": 200,
|
| 74 |
+
"kv": 200,
|
| 75 |
+
"kp": 1000,
|
| 76 |
+
"velocity_limits": [-1,1],
|
| 77 |
+
"kp_limits": [0, 1000],
|
| 78 |
+
"interpolation": null,
|
| 79 |
+
"ramp_ratio": 0.2
|
| 80 |
+
},
|
| 81 |
+
"head": {
|
| 82 |
+
"type" : "JOINT_POSITION",
|
| 83 |
+
"input_max": 1,
|
| 84 |
+
"input_min": -1,
|
| 85 |
+
"input_type": "absolute",
|
| 86 |
+
"output_max": 0.5,
|
| 87 |
+
"output_min": -0.5,
|
| 88 |
+
"kd": 200,
|
| 89 |
+
"kv": 200,
|
| 90 |
+
"kp": 1000,
|
| 91 |
+
"velocity_limits": [-1,1],
|
| 92 |
+
"kp_limits": [0, 1000],
|
| 93 |
+
"interpolation": null,
|
| 94 |
+
"ramp_ratio": 0.2
|
| 95 |
+
},
|
| 96 |
+
"base": {
|
| 97 |
+
"type": "JOINT_VELOCITY",
|
| 98 |
+
"interpolation": "null"
|
| 99 |
+
}
|
| 100 |
+
}
|
| 101 |
+
}
|
robosuite/controllers/config/robots/default_tiago_whole_body_ik.json
ADDED
|
@@ -0,0 +1,92 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "WHOLE_BODY_IK",
|
| 3 |
+
"composite_controller_specific_configs": {
|
| 4 |
+
"ref_name": ["gripper0_right_grip_site", "gripper0_left_grip_site"],
|
| 5 |
+
"interpolation": null,
|
| 6 |
+
"actuation_part_names": ["torso", "head", "right", "left"],
|
| 7 |
+
"max_dq": 4,
|
| 8 |
+
"nullspace_joint_weights": {
|
| 9 |
+
"robot0_torso_lift_joint": 100.0
|
| 10 |
+
},
|
| 11 |
+
"ik_pseudo_inverse_damping": 5e-2,
|
| 12 |
+
"ik_integration_dt": 1e-1,
|
| 13 |
+
"ik_max_dq": 4.0,
|
| 14 |
+
"ik_max_dq_torso": 0.2,
|
| 15 |
+
"ik_input_rotation_repr": "axis_angle",
|
| 16 |
+
"verbose": false
|
| 17 |
+
},
|
| 18 |
+
"body_parts": {
|
| 19 |
+
"arms": {
|
| 20 |
+
"right": {
|
| 21 |
+
"type" : "JOINT_POSITION",
|
| 22 |
+
"input_max": 1,
|
| 23 |
+
"input_min": -1,
|
| 24 |
+
"input_type": "absolute",
|
| 25 |
+
"output_max": 0.5,
|
| 26 |
+
"output_min": -0.5,
|
| 27 |
+
"kd": 200,
|
| 28 |
+
"kv": 200,
|
| 29 |
+
"kp": 1000,
|
| 30 |
+
"velocity_limits": [-1,1],
|
| 31 |
+
"kp_limits": [0, 1000],
|
| 32 |
+
"interpolation": null,
|
| 33 |
+
"ramp_ratio": 0.2,
|
| 34 |
+
"gripper": {
|
| 35 |
+
"type": "GRIP"
|
| 36 |
+
}
|
| 37 |
+
},
|
| 38 |
+
"left": {
|
| 39 |
+
"type" : "JOINT_POSITION",
|
| 40 |
+
"input_max": 1,
|
| 41 |
+
"input_min": -1,
|
| 42 |
+
"input_type": "absolute",
|
| 43 |
+
"output_max": 0.5,
|
| 44 |
+
"output_min": -0.5,
|
| 45 |
+
"kd": 200,
|
| 46 |
+
"kv": 200,
|
| 47 |
+
"kp": 1000,
|
| 48 |
+
"velocity_limits": [-1,1],
|
| 49 |
+
"kp_limits": [0, 1000],
|
| 50 |
+
"interpolation": null,
|
| 51 |
+
"ramp_ratio": 0.2,
|
| 52 |
+
"gripper": {
|
| 53 |
+
"type": "GRIP"
|
| 54 |
+
}
|
| 55 |
+
}
|
| 56 |
+
},
|
| 57 |
+
"torso": {
|
| 58 |
+
"type" : "JOINT_POSITION",
|
| 59 |
+
"input_max": 1,
|
| 60 |
+
"input_min": -1,
|
| 61 |
+
"input_type": "absolute",
|
| 62 |
+
"output_max": 0.5,
|
| 63 |
+
"output_min": -0.5,
|
| 64 |
+
"kd": 200,
|
| 65 |
+
"kv": 200,
|
| 66 |
+
"kp": 1000,
|
| 67 |
+
"velocity_limits": [-1,1],
|
| 68 |
+
"kp_limits": [0, 1000],
|
| 69 |
+
"interpolation": null,
|
| 70 |
+
"ramp_ratio": 0.2
|
| 71 |
+
},
|
| 72 |
+
"head": {
|
| 73 |
+
"type" : "JOINT_POSITION",
|
| 74 |
+
"input_max": 1,
|
| 75 |
+
"input_min": -1,
|
| 76 |
+
"input_type": "absolute",
|
| 77 |
+
"output_max": 0.5,
|
| 78 |
+
"output_min": -0.5,
|
| 79 |
+
"kd": 200,
|
| 80 |
+
"kv": 200,
|
| 81 |
+
"kp": 1000,
|
| 82 |
+
"velocity_limits": [-1,1],
|
| 83 |
+
"kp_limits": [0, 1000],
|
| 84 |
+
"interpolation": null,
|
| 85 |
+
"ramp_ratio": 0.2
|
| 86 |
+
},
|
| 87 |
+
"base": {
|
| 88 |
+
"type": "JOINT_VELOCITY",
|
| 89 |
+
"interpolation": "null"
|
| 90 |
+
}
|
| 91 |
+
}
|
| 92 |
+
}
|
robosuite/controllers/config/robots/default_ur5e.json
ADDED
|
@@ -0,0 +1,29 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
{
|
| 2 |
+
"type": "BASIC",
|
| 3 |
+
"body_parts": {
|
| 4 |
+
"arms": {
|
| 5 |
+
"right": {
|
| 6 |
+
"type": "OSC_POSE",
|
| 7 |
+
"input_max": 1,
|
| 8 |
+
"input_min": -1,
|
| 9 |
+
"output_max": [0.05, 0.05, 0.05, 0.5, 0.5, 0.5],
|
| 10 |
+
"output_min": [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5],
|
| 11 |
+
"kp": 150,
|
| 12 |
+
"damping_ratio": 1,
|
| 13 |
+
"impedance_mode": "fixed",
|
| 14 |
+
"kp_limits": [0, 300],
|
| 15 |
+
"damping_ratio_limits": [0, 10],
|
| 16 |
+
"position_limits": null,
|
| 17 |
+
"orientation_limits": null,
|
| 18 |
+
"uncouple_pos_ori": true,
|
| 19 |
+
"input_type": "delta",
|
| 20 |
+
"input_ref_frame": "base",
|
| 21 |
+
"interpolation": null,
|
| 22 |
+
"ramp_ratio": 0.2,
|
| 23 |
+
"gripper": {
|
| 24 |
+
"type": "GRIP"
|
| 25 |
+
}
|
| 26 |
+
}
|
| 27 |
+
}
|
| 28 |
+
}
|
| 29 |
+
}
|
robosuite/controllers/parts/__init__.py
ADDED
|
File without changes
|
robosuite/controllers/parts/arm/__init__.py
ADDED
|
@@ -0,0 +1,2 @@
|
|
|
|
|
|
|
|
|
|
| 1 |
+
from .osc import OperationalSpaceController
|
| 2 |
+
from .ik import InverseKinematicsController
|
robosuite/controllers/parts/arm/ik.py
ADDED
|
@@ -0,0 +1,584 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
"""
|
| 2 |
+
***********************************************************************************
|
| 3 |
+
|
| 4 |
+
|
| 5 |
+
NOTE: IK is only supported for the following robots:
|
| 6 |
+
|
| 7 |
+
:Baxter:
|
| 8 |
+
:Sawyer:
|
| 9 |
+
:Panda:
|
| 10 |
+
|
| 11 |
+
Attempting to run IK with any other robot will raise an error!
|
| 12 |
+
|
| 13 |
+
***********************************************************************************
|
| 14 |
+
"""
|
| 15 |
+
|
| 16 |
+
from dataclasses import field
|
| 17 |
+
from typing import Dict, List, Optional, Union
|
| 18 |
+
|
| 19 |
+
import mujoco
|
| 20 |
+
import numpy as np
|
| 21 |
+
|
| 22 |
+
import robosuite.utils.transform_utils as T
|
| 23 |
+
from robosuite.controllers.parts.generic.joint_pos import JointPositionController
|
| 24 |
+
from robosuite.utils.binding_utils import MjSim
|
| 25 |
+
from robosuite.utils.control_utils import *
|
| 26 |
+
from robosuite.utils.ik_utils import IKSolver, get_nullspace_gains
|
| 27 |
+
|
| 28 |
+
# Dict of supported ik robots
|
| 29 |
+
SUPPORTED_IK_ROBOTS = {"Baxter", "Sawyer", "Panda", "GR1FixedLowerBody"}
|
| 30 |
+
|
| 31 |
+
|
| 32 |
+
class InverseKinematicsController(JointPositionController):
|
| 33 |
+
"""
|
| 34 |
+
Controller for controlling robot arm via inverse kinematics. Allows position and orientation control of the
|
| 35 |
+
robot's end effector.
|
| 36 |
+
|
| 37 |
+
We use differential inverse kinematics with posture control in the null space
|
| 38 |
+
to generate joint positions (see https://github.com/kevinzakka/mjctrl) which are fed to the JointPositionController.
|
| 39 |
+
|
| 40 |
+
NOTE: Control input actions are assumed to be relative to the current position / orientation of the end effector
|
| 41 |
+
and are taken as the array (x_dpos, y_dpos, z_dpos, x_rot, y_rot, z_rot).
|
| 42 |
+
|
| 43 |
+
However, confusingly, x_dpos, y_dpos, z_dpos are relative to the mujoco world frame, while x_rot, y_rot, z_rot are
|
| 44 |
+
relative to the current end effector frame.
|
| 45 |
+
|
| 46 |
+
Args:
|
| 47 |
+
sim (MjSim): Simulator instance this controller will pull robot state updates from
|
| 48 |
+
|
| 49 |
+
ref_name: Name of controlled robot arm's end effector (from robot XML)
|
| 50 |
+
|
| 51 |
+
joint_indexes (dict): Each key contains sim reference indexes to relevant robot joint information, namely:
|
| 52 |
+
|
| 53 |
+
:`'joints'`: list of indexes to relevant robot joints
|
| 54 |
+
:`'qpos'`: list of indexes to relevant robot joint positions
|
| 55 |
+
:`'qvel'`: list of indexes to relevant robot joint velocities
|
| 56 |
+
|
| 57 |
+
robot_name (str): Name of robot being controlled. Can be {"Sawyer", "Panda", or "Baxter"}
|
| 58 |
+
|
| 59 |
+
actuator_range (2-tuple of array of float): 2-Tuple (low, high) representing the robot joint actuator range
|
| 60 |
+
|
| 61 |
+
eef_rot_offset (4-array): Quaternion (x,y,z,w) representing rotational offset between the final
|
| 62 |
+
robot arm link coordinate system and the end effector coordinate system (i.e: the gripper)
|
| 63 |
+
|
| 64 |
+
policy_freq (int): Frequency at which actions from the robot policy are fed into this controller
|
| 65 |
+
|
| 66 |
+
ik_pos_limit (float): Limit (meters) above which the magnitude of a given action's
|
| 67 |
+
positional inputs will be clipped
|
| 68 |
+
|
| 69 |
+
ik_ori_limit (float): Limit (radians) above which the magnitude of a given action's
|
| 70 |
+
orientation inputs will be clipped
|
| 71 |
+
|
| 72 |
+
interpolator (Interpolator): Interpolator object to be used for interpolating from the current state to
|
| 73 |
+
the goal state during each timestep between inputted actions
|
| 74 |
+
|
| 75 |
+
converge_steps (int): How many iterations to run the inverse kinematics solver to converge to a
|
| 76 |
+
solution
|
| 77 |
+
|
| 78 |
+
**kwargs: Does nothing; placeholder to "sink" any additional arguments so that instantiating this controller
|
| 79 |
+
via an argument dict that has additional extraneous arguments won't raise an error
|
| 80 |
+
|
| 81 |
+
Raises:
|
| 82 |
+
AssertionError: [Unsupported robot]
|
| 83 |
+
"""
|
| 84 |
+
|
| 85 |
+
def __init__(
|
| 86 |
+
self,
|
| 87 |
+
sim,
|
| 88 |
+
ref_name: Union[List[str], str],
|
| 89 |
+
joint_indexes,
|
| 90 |
+
robot_name,
|
| 91 |
+
actuator_range,
|
| 92 |
+
eef_rot_offset=None,
|
| 93 |
+
bullet_server_id=0,
|
| 94 |
+
policy_freq=20,
|
| 95 |
+
load_urdf=True,
|
| 96 |
+
ik_pos_limit=None,
|
| 97 |
+
ik_ori_limit=None,
|
| 98 |
+
interpolator_pos=None,
|
| 99 |
+
interpolator_ori=None,
|
| 100 |
+
converge_steps=5,
|
| 101 |
+
kp: int = 100,
|
| 102 |
+
kv: int = 10,
|
| 103 |
+
control_delta: bool = True,
|
| 104 |
+
**kwargs,
|
| 105 |
+
):
|
| 106 |
+
# Run sueprclass inits
|
| 107 |
+
super().__init__(
|
| 108 |
+
sim=sim,
|
| 109 |
+
ref_name=ref_name,
|
| 110 |
+
joint_indexes=joint_indexes,
|
| 111 |
+
actuator_range=actuator_range,
|
| 112 |
+
input_max=1,
|
| 113 |
+
input_min=-1,
|
| 114 |
+
output_max=1,
|
| 115 |
+
output_min=-1,
|
| 116 |
+
kp=kp,
|
| 117 |
+
kv=kv,
|
| 118 |
+
policy_freq=policy_freq,
|
| 119 |
+
velocity_limits=[-1, 1],
|
| 120 |
+
**kwargs,
|
| 121 |
+
)
|
| 122 |
+
|
| 123 |
+
# Verify robot is supported by IK
|
| 124 |
+
assert robot_name in SUPPORTED_IK_ROBOTS, (
|
| 125 |
+
"Error: Tried to instantiate IK controller for unsupported robot! "
|
| 126 |
+
"Inputted robot: {}, Supported robots: {}".format(robot_name, SUPPORTED_IK_ROBOTS)
|
| 127 |
+
)
|
| 128 |
+
|
| 129 |
+
# Initialize ik-specific attributes
|
| 130 |
+
self.robot_name = robot_name # Name of robot (e.g.: "Panda", "Sawyer", etc.)
|
| 131 |
+
|
| 132 |
+
self.rest_poses = None
|
| 133 |
+
|
| 134 |
+
self.num_ref_sites = 1 if isinstance(ref_name, str) else len(ref_name)
|
| 135 |
+
# Set the reference robot target pos / orientation (to prevent drift / weird ik numerical behavior over time)
|
| 136 |
+
if self.num_ref_sites == 1:
|
| 137 |
+
self.reference_target_pos = self.ref_pos
|
| 138 |
+
self.reference_target_orn = T.mat2quat(self.ref_ori_mat)
|
| 139 |
+
else:
|
| 140 |
+
self.reference_target_pos = self.ref_pos
|
| 141 |
+
self.reference_target_orn = np.array([T.mat2quat(self.ref_ori_mat[i]) for i in range(self.num_ref_sites)])
|
| 142 |
+
|
| 143 |
+
# Override underlying control dim
|
| 144 |
+
self.control_dim = 6 * self.num_ref_sites # assuming 6dof control of end effectors; TODO: handle head
|
| 145 |
+
|
| 146 |
+
# Interpolator
|
| 147 |
+
self.interpolator_pos = interpolator_pos
|
| 148 |
+
self.interpolator_ori = interpolator_ori
|
| 149 |
+
|
| 150 |
+
# Interpolator-related attributes
|
| 151 |
+
self.ori_ref = None
|
| 152 |
+
self.relative_ori = None
|
| 153 |
+
|
| 154 |
+
self.use_delta = control_delta
|
| 155 |
+
|
| 156 |
+
# Set ik limits and override internal min / max
|
| 157 |
+
self.ik_pos_limit = ik_pos_limit
|
| 158 |
+
self.ik_ori_limit = ik_ori_limit
|
| 159 |
+
|
| 160 |
+
# Should be in (0, 1], smaller values mean less sensitivity.
|
| 161 |
+
self.user_sensitivity = 0.3
|
| 162 |
+
|
| 163 |
+
self.nullspace_joint_weights = kwargs.get("nullspace_joint_weights", {})
|
| 164 |
+
self.joint_names = [sim.model.joint_id2name(i) for i in joint_indexes["joints"]]
|
| 165 |
+
self.integration_dt = kwargs.get("ik_integration_dt", 0.1)
|
| 166 |
+
self.damping = kwargs.get("ik_pseudo_inverse_damping", 5e-1)
|
| 167 |
+
self.max_dq = kwargs.get("ik_max_dq", 4.0) # currently only used for multi-site ik
|
| 168 |
+
|
| 169 |
+
self.i = 0
|
| 170 |
+
|
| 171 |
+
def get_control(self, dpos=None, rotation=None, update_targets=False):
|
| 172 |
+
"""
|
| 173 |
+
Returns joint positions to control the robot after the target end effector
|
| 174 |
+
position and orientation are updated from arguments @dpos and @rotation.
|
| 175 |
+
If no arguments are provided, joint positions will be computed based
|
| 176 |
+
on the previously recorded target.
|
| 177 |
+
|
| 178 |
+
Args:
|
| 179 |
+
dpos (np.array): a 3 dimensional array corresponding to the desired
|
| 180 |
+
change in x, y, and z end effector position.
|
| 181 |
+
rotation (np.array): a rotation matrix of shape (3, 3) corresponding
|
| 182 |
+
to the desired rotation from the current orientation of the end effector.
|
| 183 |
+
update_targets (bool): whether to update ik target pos / ori attributes or not
|
| 184 |
+
|
| 185 |
+
Returns:
|
| 186 |
+
np.array: a flat array of joint position commands to apply to try and achieve the desired input control.
|
| 187 |
+
"""
|
| 188 |
+
positions = InverseKinematicsController.compute_joint_positions(
|
| 189 |
+
self.sim,
|
| 190 |
+
self.initial_joint,
|
| 191 |
+
self.joint_index,
|
| 192 |
+
self.ref_name,
|
| 193 |
+
self.control_freq,
|
| 194 |
+
[-1, 1], # hardcoded velocity limits; unused
|
| 195 |
+
use_delta=self.use_delta,
|
| 196 |
+
dpos=dpos,
|
| 197 |
+
drot=rotation,
|
| 198 |
+
jac=self.J_full,
|
| 199 |
+
joint_names=self.joint_names,
|
| 200 |
+
nullspace_joint_weights=self.nullspace_joint_weights,
|
| 201 |
+
damping=self.damping,
|
| 202 |
+
integration_dt=self.integration_dt,
|
| 203 |
+
max_dq=self.max_dq,
|
| 204 |
+
)
|
| 205 |
+
|
| 206 |
+
return positions
|
| 207 |
+
|
| 208 |
+
@staticmethod
|
| 209 |
+
def compute_joint_positions(
|
| 210 |
+
sim: MjSim,
|
| 211 |
+
initial_joint: np.ndarray,
|
| 212 |
+
joint_indices: np.ndarray,
|
| 213 |
+
ref_name: Union[List[str], str],
|
| 214 |
+
control_freq: float,
|
| 215 |
+
velocity_limits: Optional[np.ndarray] = None,
|
| 216 |
+
use_delta: bool = True,
|
| 217 |
+
dpos: Optional[np.ndarray] = None,
|
| 218 |
+
drot: Optional[np.ndarray] = None,
|
| 219 |
+
Kn: Optional[np.ndarray] = np.array([10.0, 10.0, 10.0, 10.0, 5.0, 5.0, 5.0]),
|
| 220 |
+
damping_pseudo_inv: float = 0.05,
|
| 221 |
+
Kpos: float = 0.95,
|
| 222 |
+
Kori: float = 0.95,
|
| 223 |
+
jac: Optional[np.ndarray] = None,
|
| 224 |
+
joint_names: Optional[List[str]] = None,
|
| 225 |
+
nullspace_joint_weights: Dict[str, float] = field(default_factory=dict),
|
| 226 |
+
integration_dt: float = 0.1,
|
| 227 |
+
damping: float = 5e-1,
|
| 228 |
+
max_dq: int = 4, # TODO: should be derived from velocity_limits
|
| 229 |
+
) -> np.ndarray:
|
| 230 |
+
"""
|
| 231 |
+
Returns joint positions to control the robot after the target end effector
|
| 232 |
+
position and orientation are updated from arguments @dpos and @drot.
|
| 233 |
+
If no arguments are provided, joint positions will be set as zero.
|
| 234 |
+
|
| 235 |
+
Args:
|
| 236 |
+
sim (MjSim): The simulation object.
|
| 237 |
+
initial_joint (np.array): Initial joint positions.
|
| 238 |
+
joint_indices (np.array): Indices of the joints.
|
| 239 |
+
ref_name: Reference site name.
|
| 240 |
+
control_freq (float): Control frequency.
|
| 241 |
+
velocity_limits (np.array): Limits on joint velocities.
|
| 242 |
+
use_delta: Whether or not to use delta commands. If so, use dpos, drot to compute joint positions.
|
| 243 |
+
If not, assume dpos, drot are absolute commands (in mujoco world frame).
|
| 244 |
+
dpos (Optional[np.array]): Desired change in end-effector position
|
| 245 |
+
if use_delta=True, otherwise desired end-effector position.
|
| 246 |
+
drot (Optional[np.array]): Desired change in orientation for the reference site (e.g end effector)
|
| 247 |
+
if use_delta=True, otherwise desired end-effector orientation.
|
| 248 |
+
update_targets (bool): Whether to update ik target pos / ori attributes or not.
|
| 249 |
+
Kpos (float): Position gain. Between 0 and 1.
|
| 250 |
+
0 means no movement, 1 means move end effector to desired position in one integration step.
|
| 251 |
+
Kori (float): Orientation gain. Between 0 and 1.
|
| 252 |
+
jac (Optional[np.array]): Precomputed jacobian matrix.
|
| 253 |
+
|
| 254 |
+
Returns:
|
| 255 |
+
np.array: A flat array of joint position commands to apply to try and achieve the desired input control.
|
| 256 |
+
"""
|
| 257 |
+
if (dpos is not None) and (drot is not None):
|
| 258 |
+
max_angvel = velocity_limits[1] if velocity_limits is not None else 0.7
|
| 259 |
+
|
| 260 |
+
q0 = initial_joint
|
| 261 |
+
dof_ids = joint_indices
|
| 262 |
+
|
| 263 |
+
num_ref_sites = 1 if isinstance(ref_name, str) else len(ref_name)
|
| 264 |
+
if num_ref_sites == 1:
|
| 265 |
+
assert use_delta, "Currently, only delta commands are supported. Please set use_delta=True."
|
| 266 |
+
# TODO: support absolute commands by using solve() from diffik_nullspace.py
|
| 267 |
+
twist = np.zeros(6)
|
| 268 |
+
error_quat = np.zeros(4)
|
| 269 |
+
diag = damping_pseudo_inv**2 * np.eye(len(twist))
|
| 270 |
+
eye = np.eye(len(joint_indices))
|
| 271 |
+
|
| 272 |
+
jac = np.zeros((6, sim.model.nv), dtype=np.float64)
|
| 273 |
+
twist = np.zeros(6)
|
| 274 |
+
error_quat = np.zeros(4)
|
| 275 |
+
|
| 276 |
+
twist[:3] = Kpos * dpos / integration_dt
|
| 277 |
+
mujoco.mju_mat2Quat(error_quat, drot.reshape(-1))
|
| 278 |
+
mujoco.mju_quat2Vel(twist[3:], error_quat, 1.0)
|
| 279 |
+
twist[3:] *= Kori / integration_dt
|
| 280 |
+
|
| 281 |
+
mujoco.mj_jacSite(
|
| 282 |
+
sim.model._model,
|
| 283 |
+
sim.data._data,
|
| 284 |
+
jac[:3],
|
| 285 |
+
jac[3:],
|
| 286 |
+
sim.data.site(ref_name).id,
|
| 287 |
+
)
|
| 288 |
+
|
| 289 |
+
jac = jac[:, dof_ids]
|
| 290 |
+
|
| 291 |
+
dq = jac.T @ np.linalg.solve(jac @ jac.T + diag, twist)
|
| 292 |
+
dq += (eye - np.linalg.pinv(jac) @ jac) @ (Kn * (q0 - sim.data.qpos[dof_ids]))
|
| 293 |
+
|
| 294 |
+
dq_abs_max = np.abs(dq).max()
|
| 295 |
+
if dq_abs_max > max_angvel:
|
| 296 |
+
dq *= max_angvel / dq_abs_max
|
| 297 |
+
|
| 298 |
+
q_des = sim.data.qpos[dof_ids] + dq * integration_dt
|
| 299 |
+
dq = q_des # hack for now
|
| 300 |
+
return dq
|
| 301 |
+
else:
|
| 302 |
+
model = sim.model._model
|
| 303 |
+
data = sim.data._data
|
| 304 |
+
joint_names = [
|
| 305 |
+
model.joint(i).name
|
| 306 |
+
for i in range(model.njnt)
|
| 307 |
+
if model.joint(i).type != 0 and ("gripper0" not in model.joint(i).name)
|
| 308 |
+
] # Exclude fixed joints
|
| 309 |
+
nullspace_gains = get_nullspace_gains(joint_names, nullspace_joint_weights)
|
| 310 |
+
robot_config = {
|
| 311 |
+
"end_effector_sites": ref_name,
|
| 312 |
+
"joint_names": joint_names,
|
| 313 |
+
"mocap_bodies": [],
|
| 314 |
+
"nullspace_gains": nullspace_gains,
|
| 315 |
+
}
|
| 316 |
+
ik_solver = IKSolver(
|
| 317 |
+
model,
|
| 318 |
+
data,
|
| 319 |
+
robot_config,
|
| 320 |
+
damping=damping,
|
| 321 |
+
integration_dt=integration_dt,
|
| 322 |
+
max_dq=max_dq,
|
| 323 |
+
input_type="mocap",
|
| 324 |
+
input_rotation_repr="quat_wxyz",
|
| 325 |
+
)
|
| 326 |
+
if use_delta:
|
| 327 |
+
target_ori_mat = np.array([ik_solver.data.site(site_id).xmat for site_id in ik_solver.site_ids])
|
| 328 |
+
target_ori = np.array([np.ones(4) for _ in range(len(ik_solver.site_ids))])
|
| 329 |
+
[mujoco.mju_mat2Quat(target_ori[i], target_ori_mat[i]) for i in range(len(ik_solver.site_ids))]
|
| 330 |
+
target_pos = np.array([ik_solver.data.site(site_id).xpos for site_id in ik_solver.site_ids])
|
| 331 |
+
if dpos.ndim == 1:
|
| 332 |
+
target_pos[0] += dpos
|
| 333 |
+
target_ori[0] = T.quat_multiply(target_ori[0], T.mat2quat(drot))
|
| 334 |
+
else:
|
| 335 |
+
target_pos += dpos
|
| 336 |
+
target_ori = np.array(
|
| 337 |
+
[
|
| 338 |
+
T.quat_multiply(target_ori[i], T.mat2quat(drot[i]))
|
| 339 |
+
for i in range(len(ik_solver.site_ids))
|
| 340 |
+
]
|
| 341 |
+
)
|
| 342 |
+
else:
|
| 343 |
+
target_pos = dpos
|
| 344 |
+
target_ori = np.array([np.ones(4) for _ in range(len(ik_solver.site_ids))])
|
| 345 |
+
# convert drot (3x3) to quaternion
|
| 346 |
+
[mujoco.mju_mat2Quat(target_ori[i], drot[i].flatten()) for i in range(len(ik_solver.site_ids))]
|
| 347 |
+
|
| 348 |
+
ori_dim = target_ori.shape[1]
|
| 349 |
+
pos_dim = target_pos.shape[1]
|
| 350 |
+
target_action = np.empty(target_pos.shape[0] * (target_pos.shape[1] + target_ori.shape[1]))
|
| 351 |
+
for i in range(target_pos.shape[0]):
|
| 352 |
+
target_action[i * (pos_dim + ori_dim) : (i + 1) * (pos_dim + ori_dim)] = np.concatenate(
|
| 353 |
+
(target_pos[i], target_ori[i])
|
| 354 |
+
)
|
| 355 |
+
|
| 356 |
+
return ik_solver.solve(
|
| 357 |
+
target_pos=target_pos,
|
| 358 |
+
target_ori=target_ori,
|
| 359 |
+
Kpos=Kpos,
|
| 360 |
+
Kori=Kori,
|
| 361 |
+
)
|
| 362 |
+
|
| 363 |
+
return sim.data.qpos[joint_indices]
|
| 364 |
+
|
| 365 |
+
def set_goal(self, delta, set_ik=None):
|
| 366 |
+
"""
|
| 367 |
+
Sets the internal goal state of this controller based on @delta
|
| 368 |
+
|
| 369 |
+
Note that this controller wraps a PositionController, and so determines the desired positions
|
| 370 |
+
to achieve the inputted pose, and sets its internal setpoint in terms of joint positions
|
| 371 |
+
|
| 372 |
+
TODO: Add feature so that using @set_ik automatically sets the target values to these absolute values
|
| 373 |
+
|
| 374 |
+
Args:
|
| 375 |
+
delta (Iterable): Desired relative position / orientation goal state
|
| 376 |
+
set_ik (Iterable): If set, overrides @delta and sets the desired global position / orientation goal state
|
| 377 |
+
"""
|
| 378 |
+
# Update state
|
| 379 |
+
self.update(force=True) # force because new_update = True only set in super().run_controller()
|
| 380 |
+
|
| 381 |
+
if self.num_ref_sites > 1:
|
| 382 |
+
delta = np.array(delta).reshape(self.num_ref_sites, 6)
|
| 383 |
+
|
| 384 |
+
# hardcoding to assumes 6D delta input for now
|
| 385 |
+
(dpos, dquat) = self._clip_ik_input(delta[..., :3], delta[..., 3:6])
|
| 386 |
+
|
| 387 |
+
# Set interpolated goals if necessary
|
| 388 |
+
if self.interpolator_pos is not None:
|
| 389 |
+
# Absolute position goal
|
| 390 |
+
self.interpolator_pos.set_goal(dpos * self.user_sensitivity + self.reference_target_pos)
|
| 391 |
+
|
| 392 |
+
if self.interpolator_ori is not None:
|
| 393 |
+
# Relative orientation goal
|
| 394 |
+
self.interpolator_ori.set_goal(dquat) # goal is the relative change in orientation
|
| 395 |
+
self.ori_ref = np.array(self.ref_ori_mat) # reference is the current orientation at start
|
| 396 |
+
self.relative_ori = np.zeros(3) # relative orientation always starts at 0
|
| 397 |
+
|
| 398 |
+
# Run ik prepropressing to convert pos, quat ori to desired positions
|
| 399 |
+
requested_control = self._make_input(delta, self.reference_target_orn)
|
| 400 |
+
|
| 401 |
+
# Compute desired (absolute) joint positions to achieve eef pos / ori
|
| 402 |
+
positions = self.get_control(**requested_control, update_targets=True)
|
| 403 |
+
|
| 404 |
+
# Set the goal positions for the underlying position controller
|
| 405 |
+
super().set_goal(positions)
|
| 406 |
+
|
| 407 |
+
def run_controller(self):
|
| 408 |
+
"""
|
| 409 |
+
Calculates the torques required to reach the desired setpoint
|
| 410 |
+
|
| 411 |
+
Returns:
|
| 412 |
+
np.array: Command torques
|
| 413 |
+
"""
|
| 414 |
+
# Update state
|
| 415 |
+
self.update() # force because new_update = True only set in super().run_controller()
|
| 416 |
+
|
| 417 |
+
# Update interpolated action if necessary
|
| 418 |
+
desired_pos = None
|
| 419 |
+
rotation = None
|
| 420 |
+
update_position_goal = False
|
| 421 |
+
|
| 422 |
+
# Update interpolated goals if active
|
| 423 |
+
if self.interpolator_pos is not None:
|
| 424 |
+
# Linear case
|
| 425 |
+
if self.interpolator_pos.order == 1:
|
| 426 |
+
desired_pos = self.interpolator_pos.get_interpolated_goal()
|
| 427 |
+
else:
|
| 428 |
+
# Nonlinear case not currently supported
|
| 429 |
+
pass
|
| 430 |
+
update_position_goal = True
|
| 431 |
+
else:
|
| 432 |
+
desired_pos = self.reference_target_pos
|
| 433 |
+
|
| 434 |
+
if self.interpolator_ori is not None:
|
| 435 |
+
# Linear case
|
| 436 |
+
if self.interpolator_ori.order == 1:
|
| 437 |
+
# relative orientation based on difference between current ori and ref
|
| 438 |
+
self.relative_ori = orientation_error(self.ref_ori_mat, self.ori_ref)
|
| 439 |
+
ori_error = self.interpolator_ori.get_interpolated_goal()
|
| 440 |
+
rotation = T.quat2mat(ori_error)
|
| 441 |
+
else:
|
| 442 |
+
# Nonlinear case not currently supported
|
| 443 |
+
pass
|
| 444 |
+
update_position_goal = True
|
| 445 |
+
else:
|
| 446 |
+
if self.num_ref_sites == 1:
|
| 447 |
+
rotation = T.mat2quat(self.ref_ori_mat)
|
| 448 |
+
else:
|
| 449 |
+
rotation = np.array([T.mat2quat(self.ref_ori_mat[i]) for i in range(self.num_ref_sites)])
|
| 450 |
+
|
| 451 |
+
# Only update the position goals if we're interpolating
|
| 452 |
+
if update_position_goal:
|
| 453 |
+
velocities = self.get_control(dpos=(desired_pos - self.ref_pos), rotation=rotation)
|
| 454 |
+
super().set_goal(velocities)
|
| 455 |
+
|
| 456 |
+
return super().run_controller()
|
| 457 |
+
|
| 458 |
+
def update_initial_joints(self, initial_joints):
|
| 459 |
+
# First, update from the superclass method
|
| 460 |
+
super().update_initial_joints(initial_joints)
|
| 461 |
+
|
| 462 |
+
# Then, update the rest pose from the initial joints
|
| 463 |
+
self.rest_poses = list(self.initial_joint)
|
| 464 |
+
|
| 465 |
+
def reset_goal(self):
|
| 466 |
+
"""
|
| 467 |
+
Resets the goal to the current pose of the robot
|
| 468 |
+
"""
|
| 469 |
+
if self.num_ref_sites == 1:
|
| 470 |
+
self.reference_target_pos = self.ref_pos
|
| 471 |
+
self.reference_target_orn = T.mat2quat(self.ref_ori_mat)
|
| 472 |
+
else:
|
| 473 |
+
self.reference_target_pos = self.ref_pos
|
| 474 |
+
self.reference_target_orn = np.array([T.mat2quat(self.ref_ori_mat[i]) for i in range(self.num_ref_sites)])
|
| 475 |
+
|
| 476 |
+
def _clip_ik_input(self, dpos, rotation):
|
| 477 |
+
"""
|
| 478 |
+
Helper function that clips desired ik input deltas into a valid range.
|
| 479 |
+
|
| 480 |
+
Args:
|
| 481 |
+
dpos (np.array): a 3 dimensional array corresponding to the desired
|
| 482 |
+
change in x, y, and z end effector position.
|
| 483 |
+
rotation (np.array): relative rotation in scaled axis angle form (ax, ay, az)
|
| 484 |
+
corresponding to the (relative) desired orientation of the end effector.
|
| 485 |
+
|
| 486 |
+
Returns:
|
| 487 |
+
2-tuple:
|
| 488 |
+
|
| 489 |
+
- (np.array) clipped dpos
|
| 490 |
+
- (np.array) clipped rotation
|
| 491 |
+
"""
|
| 492 |
+
# scale input range to desired magnitude
|
| 493 |
+
if dpos.any() and self.ik_pos_limit is not None:
|
| 494 |
+
dpos, _ = T.clip_translation(dpos, self.ik_pos_limit)
|
| 495 |
+
|
| 496 |
+
if self.num_ref_sites == 1:
|
| 497 |
+
# Map input to quaternion
|
| 498 |
+
rotation = T.axisangle2quat(rotation)
|
| 499 |
+
else:
|
| 500 |
+
rotation = [T.axisangle2quat(rotation[i]) for i in range(self.num_ref_sites)]
|
| 501 |
+
|
| 502 |
+
if self.ik_ori_limit is not None:
|
| 503 |
+
# Clip orientation to desired magnitude
|
| 504 |
+
rotation, _ = T.clip_rotation(rotation, self.ik_ori_limit)
|
| 505 |
+
|
| 506 |
+
return dpos, rotation
|
| 507 |
+
|
| 508 |
+
def _make_input(self, action, old_quat):
|
| 509 |
+
"""
|
| 510 |
+
Helper function that returns a dictionary with keys dpos, rotation from a raw input
|
| 511 |
+
array. The first three elements are taken to be displacement in position, and a
|
| 512 |
+
quaternion indicating the change in rotation with respect to @old_quat. Additionally clips @action as well
|
| 513 |
+
|
| 514 |
+
Args:
|
| 515 |
+
action (np.array) should have form: [dx, dy, dz, ax, ay, az] (orientation in
|
| 516 |
+
scaled axis-angle form)
|
| 517 |
+
old_quat (np.array) the old target quaternion that will be updated with the relative change in @action
|
| 518 |
+
"""
|
| 519 |
+
if self.num_ref_sites > 1:
|
| 520 |
+
action = np.array(action).reshape(self.num_ref_sites, 6)
|
| 521 |
+
|
| 522 |
+
# Clip action appropriately
|
| 523 |
+
dpos, rotation = self._clip_ik_input(
|
| 524 |
+
action[..., :3], action[..., 3:6]
|
| 525 |
+
) # hardcoded to assume 6dof control for now
|
| 526 |
+
|
| 527 |
+
if self.use_delta:
|
| 528 |
+
if self.num_ref_sites == 1:
|
| 529 |
+
# Update reference targets
|
| 530 |
+
self.reference_target_pos += dpos * self.user_sensitivity
|
| 531 |
+
self.reference_target_orn = T.quat_multiply(old_quat, rotation)
|
| 532 |
+
else:
|
| 533 |
+
# Update reference targets
|
| 534 |
+
self.reference_target_pos += dpos * self.user_sensitivity
|
| 535 |
+
self.reference_target_orn = np.array(
|
| 536 |
+
[T.quat_multiply(old_quat[i], rotation[i]) for i in range(self.num_ref_sites)]
|
| 537 |
+
)
|
| 538 |
+
else:
|
| 539 |
+
# Update reference targets
|
| 540 |
+
self.reference_target_pos = dpos
|
| 541 |
+
self.reference_target_orn = rotation
|
| 542 |
+
|
| 543 |
+
if self.num_ref_sites == 1:
|
| 544 |
+
rotation = T.quat2mat(rotation)
|
| 545 |
+
else:
|
| 546 |
+
dpos = dpos
|
| 547 |
+
rotation = np.array([T.quat2mat(rotation[i]) for i in range(self.num_ref_sites)])
|
| 548 |
+
|
| 549 |
+
return {"dpos": dpos, "rotation": rotation}
|
| 550 |
+
|
| 551 |
+
@staticmethod
|
| 552 |
+
def _get_current_error(current, set_point):
|
| 553 |
+
"""
|
| 554 |
+
Returns an array of differences between the desired joint positions and current
|
| 555 |
+
joint positions. Useful for PID control.
|
| 556 |
+
|
| 557 |
+
Args:
|
| 558 |
+
current (np.array): the current joint positions
|
| 559 |
+
set_point (np.array): the joint positions that are desired as a numpy array
|
| 560 |
+
|
| 561 |
+
Returns:
|
| 562 |
+
np.array: the current error in the joint positions
|
| 563 |
+
"""
|
| 564 |
+
error = current - set_point
|
| 565 |
+
return error
|
| 566 |
+
|
| 567 |
+
@property
|
| 568 |
+
def control_limits(self):
|
| 569 |
+
"""
|
| 570 |
+
The limits over this controller's action space, as specified by self.ik_pos_limit and self.ik_ori_limit
|
| 571 |
+
and overriding the superclass method
|
| 572 |
+
|
| 573 |
+
Returns:
|
| 574 |
+
2-tuple:
|
| 575 |
+
|
| 576 |
+
- (np.array) minimum control values
|
| 577 |
+
- (np.array) maximum control values
|
| 578 |
+
"""
|
| 579 |
+
max_limit = np.concatenate([self.ik_pos_limit * np.ones(3), self.ik_ori_limit * np.ones(3)])
|
| 580 |
+
return -max_limit, max_limit
|
| 581 |
+
|
| 582 |
+
@property
|
| 583 |
+
def name(self):
|
| 584 |
+
return "IK_POSE"
|
robosuite/controllers/parts/arm/osc.py
ADDED
|
@@ -0,0 +1,584 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import math
|
| 2 |
+
|
| 3 |
+
import numpy as np
|
| 4 |
+
from scipy.spatial.transform import Rotation
|
| 5 |
+
|
| 6 |
+
import robosuite.utils.transform_utils as T
|
| 7 |
+
from robosuite.controllers.parts.controller import Controller
|
| 8 |
+
from robosuite.utils.control_utils import *
|
| 9 |
+
|
| 10 |
+
# Supported impedance modes
|
| 11 |
+
IMPEDANCE_MODES = {"fixed", "variable", "variable_kp"}
|
| 12 |
+
|
| 13 |
+
# TODO: Maybe better naming scheme to differentiate between input / output min / max and pos/ori limits, etc.
|
| 14 |
+
|
| 15 |
+
|
| 16 |
+
class OperationalSpaceController(Controller):
|
| 17 |
+
"""
|
| 18 |
+
Controller for controlling robot arm via operational space control. Allows position and / or orientation control
|
| 19 |
+
of the robot's end effector. For detailed information as to the mathematical foundation for this controller, please
|
| 20 |
+
reference http://khatib.stanford.edu/publications/pdfs/Khatib_1987_RA.pdf
|
| 21 |
+
|
| 22 |
+
NOTE: Control input actions can either be taken to be relative to the current position / orientation of the
|
| 23 |
+
end effector or absolute values. In either case, a given action to this controller is assumed to be of the form:
|
| 24 |
+
(x, y, z, ax, ay, az) if controlling pos and ori or simply (x, y, z) if only controlling pos
|
| 25 |
+
|
| 26 |
+
Args:
|
| 27 |
+
sim (MjSim): Simulator instance this controller will pull robot state updates from
|
| 28 |
+
|
| 29 |
+
joint_indexes (dict): Each key contains sim reference indexes to relevant robot joint information, namely:
|
| 30 |
+
|
| 31 |
+
:`'joints'`: list of indexes to relevant robot joints
|
| 32 |
+
:`'qpos'`: list of indexes to relevant robot joint positions
|
| 33 |
+
:`'qvel'`: list of indexes to relevant robot joint velocities
|
| 34 |
+
|
| 35 |
+
actuator_range (2-tuple of array of float): 2-Tuple (low, high) representing the robot joint actuator range
|
| 36 |
+
|
| 37 |
+
input_max (float or Iterable of float): Maximum above which an inputted action will be clipped. Can be either be
|
| 38 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 39 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 40 |
+
|
| 41 |
+
input_min (float or Iterable of float): Minimum below which an inputted action will be clipped. Can be either be
|
| 42 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 43 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 44 |
+
|
| 45 |
+
output_max (float or Iterable of float): Maximum which defines upper end of scaling range when scaling an input
|
| 46 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 47 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 48 |
+
|
| 49 |
+
output_min (float or Iterable of float): Minimum which defines upper end of scaling range when scaling an input
|
| 50 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 51 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 52 |
+
|
| 53 |
+
kp (float or Iterable of float): positional gain for determining desired torques based upon the pos / ori error.
|
| 54 |
+
Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)
|
| 55 |
+
|
| 56 |
+
damping_ratio (float or Iterable of float): used in conjunction with kp to determine the velocity gain for
|
| 57 |
+
determining desired torques based upon the joint pos errors. Can be either be a scalar (same value for all
|
| 58 |
+
action dims), or a list (specific values for each dim)
|
| 59 |
+
|
| 60 |
+
impedance_mode (str): Impedance mode with which to run this controller. Options are {"fixed", "variable",
|
| 61 |
+
"variable_kp"}. If "fixed", the controller will have fixed kp and damping_ratio values as specified by the
|
| 62 |
+
@kp and @damping_ratio arguments. If "variable", both kp and damping_ratio will now be part of the
|
| 63 |
+
controller action space, resulting in a total action space of (6 or 3) + 6 * 2. If "variable_kp", only kp
|
| 64 |
+
will become variable, with damping_ratio fixed at 1 (critically damped). The resulting action space will
|
| 65 |
+
then be (6 or 3) + 6.
|
| 66 |
+
|
| 67 |
+
kp_limits (2-list of float or 2-list of Iterable of floats): Only applicable if @impedance_mode is set to either
|
| 68 |
+
"variable" or "variable_kp". This sets the corresponding min / max ranges of the controller action space
|
| 69 |
+
for the varying kp values. Can be either be a 2-list (same min / max for all kp action dims), or a 2-list
|
| 70 |
+
of list (specific min / max for each kp dim)
|
| 71 |
+
|
| 72 |
+
damping_ratio_limits (2-list of float or 2-list of Iterable of floats): Only applicable if @impedance_mode is
|
| 73 |
+
set to "variable". This sets the corresponding min / max ranges of the controller action space for the
|
| 74 |
+
varying damping_ratio values. Can be either be a 2-list (same min / max for all damping_ratio action dims),
|
| 75 |
+
or a 2-list of list (specific min / max for each damping_ratio dim)
|
| 76 |
+
|
| 77 |
+
policy_freq (int): Frequency at which actions from the robot policy are fed into this controller
|
| 78 |
+
|
| 79 |
+
position_limits (2-list of float or 2-list of Iterable of floats): Limits (m) below and above which the
|
| 80 |
+
magnitude of a calculated goal eef position will be clipped. Can be either be a 2-list (same min/max value
|
| 81 |
+
for all cartesian dims), or a 2-list of list (specific min/max values for each dim)
|
| 82 |
+
|
| 83 |
+
orientation_limits (2-list of float or 2-list of Iterable of floats): Limits (rad) below and above which the
|
| 84 |
+
magnitude of a calculated goal eef orientation will be clipped. Can be either be a 2-list
|
| 85 |
+
(same min/max value for all joint dims), or a 2-list of list (specific min/mx values for each dim)
|
| 86 |
+
|
| 87 |
+
interpolator_pos (Interpolator): Interpolator object to be used for interpolating from the current position to
|
| 88 |
+
the goal position during each timestep between inputted actions
|
| 89 |
+
|
| 90 |
+
interpolator_ori (Interpolator): Interpolator object to be used for interpolating from the current orientation
|
| 91 |
+
to the goal orientation during each timestep between inputted actions
|
| 92 |
+
|
| 93 |
+
control_ori (bool): Whether inputted actions will control both pos and ori or exclusively pos
|
| 94 |
+
|
| 95 |
+
input_type (str): Whether to control the robot using delta ("delta") or absolute commands ("absolute").
|
| 96 |
+
This is wrt the contorller reference frame (see input_ref_frame field)
|
| 97 |
+
|
| 98 |
+
input_ref_frame (str): Reference frame for controller. Current supported options are:
|
| 99 |
+
"base": actions are wrt to the robot body (i.e., the base)
|
| 100 |
+
"world": actions are wrt the world coordinate frame
|
| 101 |
+
|
| 102 |
+
uncouple_pos_ori (bool): Whether to decouple torques meant to control pos and torques meant to control ori
|
| 103 |
+
|
| 104 |
+
lite_physics (bool): Whether to optimize for mujoco forward and step calls to reduce total simulation overhead.
|
| 105 |
+
Set to False to preserve backward compatibility with datasets collected in robosuite <= 1.4.1.
|
| 106 |
+
|
| 107 |
+
**kwargs: Does nothing; placeholder to "sink" any additional arguments so that instantiating this controller
|
| 108 |
+
via an argument dict that has additional extraneous arguments won't raise an error
|
| 109 |
+
|
| 110 |
+
Raises:
|
| 111 |
+
AssertionError: [Invalid impedance mode]
|
| 112 |
+
"""
|
| 113 |
+
|
| 114 |
+
def __init__(
|
| 115 |
+
self,
|
| 116 |
+
sim,
|
| 117 |
+
ref_name,
|
| 118 |
+
joint_indexes,
|
| 119 |
+
actuator_range,
|
| 120 |
+
input_max=1,
|
| 121 |
+
input_min=-1,
|
| 122 |
+
output_max=(0.05, 0.05, 0.05, 0.5, 0.5, 0.5),
|
| 123 |
+
output_min=(-0.05, -0.05, -0.05, -0.5, -0.5, -0.5),
|
| 124 |
+
kp=150,
|
| 125 |
+
damping_ratio=1,
|
| 126 |
+
impedance_mode="fixed",
|
| 127 |
+
kp_limits=(0, 300),
|
| 128 |
+
damping_ratio_limits=(0, 100),
|
| 129 |
+
policy_freq=20,
|
| 130 |
+
position_limits=None,
|
| 131 |
+
orientation_limits=None,
|
| 132 |
+
interpolator_pos=None,
|
| 133 |
+
interpolator_ori=None,
|
| 134 |
+
control_ori=True,
|
| 135 |
+
input_type="delta",
|
| 136 |
+
input_ref_frame="base",
|
| 137 |
+
uncouple_pos_ori=True,
|
| 138 |
+
lite_physics=True,
|
| 139 |
+
**kwargs, # does nothing; used so no error raised when dict is passed with extra terms used previously
|
| 140 |
+
):
|
| 141 |
+
|
| 142 |
+
super().__init__(
|
| 143 |
+
sim,
|
| 144 |
+
ref_name=ref_name,
|
| 145 |
+
joint_indexes=joint_indexes,
|
| 146 |
+
actuator_range=actuator_range,
|
| 147 |
+
lite_physics=lite_physics,
|
| 148 |
+
part_name=kwargs.get("part_name", None),
|
| 149 |
+
naming_prefix=kwargs.get("naming_prefix", None),
|
| 150 |
+
)
|
| 151 |
+
# Determine whether this is pos ori or just pos
|
| 152 |
+
self.use_ori = control_ori
|
| 153 |
+
# Determine whether we want to use delta or absolute values as inputs
|
| 154 |
+
self.input_type = input_type
|
| 155 |
+
assert self.input_type in ["delta", "absolute"], f"Input type must be delta or absolute, got: {self.input_type}"
|
| 156 |
+
|
| 157 |
+
# determine reference frame wrt actions are set
|
| 158 |
+
self.input_ref_frame = input_ref_frame
|
| 159 |
+
assert self.input_ref_frame in [
|
| 160 |
+
"world",
|
| 161 |
+
"base",
|
| 162 |
+
], f"Input reference frame must be world or base, got: {self.input_ref_frame}"
|
| 163 |
+
|
| 164 |
+
# Control dimension
|
| 165 |
+
self.control_dim = 6 if self.use_ori else 3
|
| 166 |
+
self.name_suffix = "POSE" if self.use_ori else "POSITION"
|
| 167 |
+
|
| 168 |
+
# input and output max and min (allow for either explicit lists or single numbers)
|
| 169 |
+
self.input_max = self.nums2array(input_max, self.control_dim)
|
| 170 |
+
self.input_min = self.nums2array(input_min, self.control_dim)
|
| 171 |
+
self.output_max = self.nums2array(output_max, self.control_dim)
|
| 172 |
+
self.output_min = self.nums2array(output_min, self.control_dim)
|
| 173 |
+
|
| 174 |
+
# kp kd
|
| 175 |
+
self.kp = self.nums2array(kp, 6)
|
| 176 |
+
self.kd = 2 * np.sqrt(self.kp) * damping_ratio
|
| 177 |
+
|
| 178 |
+
# kp and kd limits
|
| 179 |
+
self.kp_min = self.nums2array(kp_limits[0], 6)
|
| 180 |
+
self.kp_max = self.nums2array(kp_limits[1], 6)
|
| 181 |
+
self.damping_ratio_min = self.nums2array(damping_ratio_limits[0], 6)
|
| 182 |
+
self.damping_ratio_max = self.nums2array(damping_ratio_limits[1], 6)
|
| 183 |
+
|
| 184 |
+
# Verify the proposed impedance mode is supported
|
| 185 |
+
assert impedance_mode in IMPEDANCE_MODES, (
|
| 186 |
+
"Error: Tried to instantiate OSC controller for unsupported "
|
| 187 |
+
"impedance mode! Inputted impedance mode: {}, Supported modes: {}".format(impedance_mode, IMPEDANCE_MODES)
|
| 188 |
+
)
|
| 189 |
+
|
| 190 |
+
# Impedance mode
|
| 191 |
+
self.impedance_mode = impedance_mode
|
| 192 |
+
|
| 193 |
+
# Add to control dim based on impedance_mode
|
| 194 |
+
if self.impedance_mode == "variable":
|
| 195 |
+
self.control_dim += 12
|
| 196 |
+
elif self.impedance_mode == "variable_kp":
|
| 197 |
+
self.control_dim += 6
|
| 198 |
+
|
| 199 |
+
# limits
|
| 200 |
+
self.position_limits = np.array(position_limits) if position_limits is not None else position_limits
|
| 201 |
+
self.orientation_limits = np.array(orientation_limits) if orientation_limits is not None else orientation_limits
|
| 202 |
+
|
| 203 |
+
# control frequency
|
| 204 |
+
self.control_freq = policy_freq
|
| 205 |
+
|
| 206 |
+
# interpolator
|
| 207 |
+
self.interpolator_pos = interpolator_pos
|
| 208 |
+
self.interpolator_ori = interpolator_ori
|
| 209 |
+
|
| 210 |
+
# whether or not pos and ori want to be uncoupled
|
| 211 |
+
self.uncoupling = uncouple_pos_ori
|
| 212 |
+
|
| 213 |
+
# initialize goals
|
| 214 |
+
self.goal_pos = None
|
| 215 |
+
self.goal_ori = None
|
| 216 |
+
|
| 217 |
+
# initialize orientation references
|
| 218 |
+
self.relative_ori = np.zeros(3)
|
| 219 |
+
self.ori_ref = None
|
| 220 |
+
|
| 221 |
+
# initialize origin pos and ori
|
| 222 |
+
self.origin_pos = None
|
| 223 |
+
self.origin_ori = None
|
| 224 |
+
|
| 225 |
+
def set_goal(self, action):
|
| 226 |
+
"""
|
| 227 |
+
Sets goal based on input @action. If self.impedance_mode is not "fixed", then the input will be parsed into the
|
| 228 |
+
delta values to update the goal position / pose and the kp and/or damping_ratio values to be immediately updated
|
| 229 |
+
internally before executing the proceeding control loop.
|
| 230 |
+
|
| 231 |
+
Note that @action expected to be in the following format, based on impedance mode!
|
| 232 |
+
|
| 233 |
+
:Mode `'fixed'`: [joint pos command]
|
| 234 |
+
:Mode `'variable'`: [damping_ratio values, kp values, joint pos command]
|
| 235 |
+
:Mode `'variable_kp'`: [kp values, joint pos command]
|
| 236 |
+
|
| 237 |
+
Args:
|
| 238 |
+
action (Iterable): Desired relative joint position goal state
|
| 239 |
+
"""
|
| 240 |
+
# Update state
|
| 241 |
+
self.update()
|
| 242 |
+
|
| 243 |
+
# Parse action based on the impedance mode, and update kp / kd as necessary
|
| 244 |
+
if self.impedance_mode == "variable":
|
| 245 |
+
damping_ratio, kp, goal_update = action[:6], action[6:12], action[12:]
|
| 246 |
+
self.kp = np.clip(kp, self.kp_min, self.kp_max)
|
| 247 |
+
self.kd = 2 * np.sqrt(self.kp) * np.clip(damping_ratio, self.damping_ratio_min, self.damping_ratio_max)
|
| 248 |
+
elif self.impedance_mode == "variable_kp":
|
| 249 |
+
kp, goal_update = action[:6], action[6:]
|
| 250 |
+
self.kp = np.clip(kp, self.kp_min, self.kp_max)
|
| 251 |
+
self.kd = 2 * np.sqrt(self.kp) # critically damped
|
| 252 |
+
else: # This is case "fixed"
|
| 253 |
+
goal_update = action
|
| 254 |
+
|
| 255 |
+
# If we're using deltas, interpret actions as such
|
| 256 |
+
if self.input_type == "delta":
|
| 257 |
+
delta = goal_update
|
| 258 |
+
scaled_delta = self.scale_action(delta)
|
| 259 |
+
self.goal_pos = self.compute_goal_pos(scaled_delta[0:3])
|
| 260 |
+
if self.use_ori is True:
|
| 261 |
+
self.goal_ori = self.compute_goal_ori(scaled_delta[3:6])
|
| 262 |
+
else:
|
| 263 |
+
self.goal_ori = self.compute_goal_ori(np.zeros(3))
|
| 264 |
+
# Else, interpret actions as absolute values
|
| 265 |
+
elif self.input_type == "absolute":
|
| 266 |
+
abs_action = goal_update
|
| 267 |
+
self.goal_pos = abs_action[0:3]
|
| 268 |
+
if self.use_ori is True:
|
| 269 |
+
self.goal_ori = Rotation.from_rotvec(abs_action[3:6]).as_matrix()
|
| 270 |
+
else:
|
| 271 |
+
self.goal_ori = self.compute_goal_ori(np.zeros(3))
|
| 272 |
+
else:
|
| 273 |
+
raise ValueError(f"Unsupport input_type {self.input_type}")
|
| 274 |
+
|
| 275 |
+
if self.interpolator_pos is not None:
|
| 276 |
+
self.interpolator_pos.set_goal(self.goal_pos)
|
| 277 |
+
|
| 278 |
+
if self.interpolator_ori is not None:
|
| 279 |
+
self.ori_ref = np.array(self.ref_ori_mat) # reference is the current orientation at start
|
| 280 |
+
self.interpolator_ori.set_goal(
|
| 281 |
+
orientation_error(self.goal_ori, self.ori_ref)
|
| 282 |
+
) # goal is the total orientation error
|
| 283 |
+
self.relative_ori = np.zeros(3) # relative orientation always starts at 0
|
| 284 |
+
|
| 285 |
+
def world_to_origin_frame(self, vec):
|
| 286 |
+
"""
|
| 287 |
+
transform vector from world to reference coordinate frame
|
| 288 |
+
"""
|
| 289 |
+
|
| 290 |
+
# world rotation matrix is just identity
|
| 291 |
+
world_frame = np.eye(4)
|
| 292 |
+
world_frame[:3, 3] = vec
|
| 293 |
+
|
| 294 |
+
origin_frame = T.make_pose(self.origin_pos, self.origin_ori)
|
| 295 |
+
origin_frame_inv = T.pose_inv(origin_frame)
|
| 296 |
+
vec_origin_pose = T.pose_in_A_to_pose_in_B(world_frame, origin_frame_inv)
|
| 297 |
+
vec_origin_pos, _ = T.mat2pose(vec_origin_pose)
|
| 298 |
+
return vec_origin_pos
|
| 299 |
+
|
| 300 |
+
def goal_origin_to_eef_pose(self):
|
| 301 |
+
origin_pose = T.make_pose(self.origin_pos, self.origin_ori)
|
| 302 |
+
ee_pose = T.make_pose(self.ref_pos, self.ref_ori_mat)
|
| 303 |
+
origin_pose_inv = T.pose_inv(origin_pose)
|
| 304 |
+
return T.pose_in_A_to_pose_in_B(ee_pose, origin_pose_inv)
|
| 305 |
+
|
| 306 |
+
def compute_goal_pos(self, delta, goal_update_mode=None):
|
| 307 |
+
"""
|
| 308 |
+
Compute new goal position, given a delta to update. Can either update the new goal based on
|
| 309 |
+
current achieved position or current deisred goal. Updating based on current deisred goal can be useful
|
| 310 |
+
if we want the robot to adhere with a sequence of target poses as closely as possible,
|
| 311 |
+
without lagging or overshooting.
|
| 312 |
+
|
| 313 |
+
Args:
|
| 314 |
+
delta (np.array): Desired relative change in position [x, y, z]
|
| 315 |
+
goal_update_mode (str): either "achieved" (achieved position) or "desired" (desired goal)
|
| 316 |
+
|
| 317 |
+
Returns:
|
| 318 |
+
np.array: updated goal position in the controller frame
|
| 319 |
+
"""
|
| 320 |
+
if goal_update_mode is None:
|
| 321 |
+
goal_update_mode = self._goal_update_mode
|
| 322 |
+
assert goal_update_mode in ["achieved", "desired"]
|
| 323 |
+
|
| 324 |
+
if self.goal_pos is None:
|
| 325 |
+
# if goal is not already set, set it to current position (in controller ref frame)
|
| 326 |
+
if self.input_ref_frame == "base":
|
| 327 |
+
self.goal_pos = self.world_to_origin_frame(self.ref_pos)
|
| 328 |
+
elif self.input_ref_frame == "world":
|
| 329 |
+
self.goal_pos = self.ref_pos
|
| 330 |
+
else:
|
| 331 |
+
raise ValueError
|
| 332 |
+
|
| 333 |
+
if goal_update_mode == "desired":
|
| 334 |
+
# update new goal wrt current desired goal
|
| 335 |
+
goal_pos = self.goal_pos + delta
|
| 336 |
+
elif goal_update_mode == "achieved":
|
| 337 |
+
# update new goal wrt current achieved position
|
| 338 |
+
if self.input_ref_frame == "base":
|
| 339 |
+
goal_pos = self.world_to_origin_frame(self.ref_pos) + delta
|
| 340 |
+
elif self.input_ref_frame == "world":
|
| 341 |
+
goal_pos = self.ref_pos + delta
|
| 342 |
+
else:
|
| 343 |
+
raise ValueError
|
| 344 |
+
|
| 345 |
+
if self.position_limits is not None:
|
| 346 |
+
# to be implemented later
|
| 347 |
+
raise NotImplementedError
|
| 348 |
+
|
| 349 |
+
return goal_pos
|
| 350 |
+
|
| 351 |
+
def compute_goal_ori(self, delta, goal_update_mode=None):
|
| 352 |
+
"""
|
| 353 |
+
Compute new goal orientation, given a delta to update. Can either update the new goal based on
|
| 354 |
+
current achieved position or current deisred goal. Updating based on current deisred goal can be useful
|
| 355 |
+
if we want the robot to adhere with a sequence of target poses as closely as possible,
|
| 356 |
+
without lagging or overshooting.
|
| 357 |
+
|
| 358 |
+
Args:
|
| 359 |
+
delta (np.array): Desired relative change in orientation, in axis-angle form [ax, ay, az]
|
| 360 |
+
goal_update_mode (str): either "achieved" (achieved position) or "desired" (desired goal)
|
| 361 |
+
|
| 362 |
+
Returns:
|
| 363 |
+
np.array: updated goal orientation in the controller frame
|
| 364 |
+
"""
|
| 365 |
+
if goal_update_mode is None:
|
| 366 |
+
goal_update_mode = self._goal_update_mode
|
| 367 |
+
assert goal_update_mode in ["achieved", "desired"]
|
| 368 |
+
|
| 369 |
+
if self.goal_ori is None:
|
| 370 |
+
# if goal is not already set, set it to current orientation (in controller ref frame)
|
| 371 |
+
if self.input_ref_frame == "base":
|
| 372 |
+
self.goal_ori = self.goal_origin_to_eef_pose()[:3, :3]
|
| 373 |
+
elif self.input_ref_frame == "world":
|
| 374 |
+
self.goal_ori = self.ref_ori_mat
|
| 375 |
+
else:
|
| 376 |
+
raise ValueError
|
| 377 |
+
|
| 378 |
+
# convert axis-angle value to rotation matrix
|
| 379 |
+
quat_error = T.axisangle2quat(delta)
|
| 380 |
+
rotation_mat_error = T.quat2mat(quat_error)
|
| 381 |
+
|
| 382 |
+
if self._goal_update_mode == "desired":
|
| 383 |
+
# update new goal wrt current desired goal
|
| 384 |
+
goal_ori = np.dot(rotation_mat_error, self.goal_ori)
|
| 385 |
+
elif self._goal_update_mode == "achieved":
|
| 386 |
+
# update new goal wrt current achieved orientation
|
| 387 |
+
if self.input_ref_frame == "base":
|
| 388 |
+
curr_goal_ori = self.goal_origin_to_eef_pose()[:3, :3]
|
| 389 |
+
elif self.input_ref_frame == "world":
|
| 390 |
+
curr_goal_ori = self.ref_ori_mat
|
| 391 |
+
else:
|
| 392 |
+
raise ValueError
|
| 393 |
+
goal_ori = np.dot(rotation_mat_error, curr_goal_ori)
|
| 394 |
+
else:
|
| 395 |
+
raise ValueError
|
| 396 |
+
|
| 397 |
+
# check for orientation limits
|
| 398 |
+
if np.array(self.orientation_limits).any():
|
| 399 |
+
# to be implemented later
|
| 400 |
+
raise NotImplementedError
|
| 401 |
+
return goal_ori
|
| 402 |
+
|
| 403 |
+
def run_controller(self):
|
| 404 |
+
"""
|
| 405 |
+
Calculates the torques required to reach the desired setpoint.
|
| 406 |
+
|
| 407 |
+
Executes Operational Space Control (OSC) -- either position only or position and orientation.
|
| 408 |
+
|
| 409 |
+
A detailed overview of derivation of OSC equations can be seen at:
|
| 410 |
+
http://khatib.stanford.edu/publications/pdfs/Khatib_1987_RA.pdf
|
| 411 |
+
|
| 412 |
+
Returns:
|
| 413 |
+
np.array: Command torques
|
| 414 |
+
"""
|
| 415 |
+
# Update state
|
| 416 |
+
self.update()
|
| 417 |
+
|
| 418 |
+
desired_world_pos = None
|
| 419 |
+
# Only linear interpolator is currently supported
|
| 420 |
+
if self.interpolator_pos is not None:
|
| 421 |
+
# Linear case
|
| 422 |
+
if self.interpolator_pos.order == 1:
|
| 423 |
+
desired_world_pos = self.interpolator_pos.get_interpolated_goal()
|
| 424 |
+
else:
|
| 425 |
+
# Nonlinear case not currently supported
|
| 426 |
+
pass
|
| 427 |
+
else:
|
| 428 |
+
if self.input_ref_frame == "base":
|
| 429 |
+
# compute goal based on current base position and orientation
|
| 430 |
+
desired_world_pos = self.origin_pos + np.dot(self.origin_ori, self.goal_pos)
|
| 431 |
+
elif self.input_ref_frame == "world":
|
| 432 |
+
desired_world_pos = self.goal_pos
|
| 433 |
+
else:
|
| 434 |
+
raise ValueError
|
| 435 |
+
|
| 436 |
+
if self.interpolator_ori is not None:
|
| 437 |
+
# relative orientation based on difference between current ori and ref
|
| 438 |
+
self.relative_ori = orientation_error(self.ref_ori_mat, self.ori_ref)
|
| 439 |
+
|
| 440 |
+
ori_error = self.interpolator_ori.get_interpolated_goal()
|
| 441 |
+
else:
|
| 442 |
+
if self.input_ref_frame == "base":
|
| 443 |
+
# compute goal based on current base orientation
|
| 444 |
+
desired_world_ori = np.dot(self.origin_ori, self.goal_ori)
|
| 445 |
+
elif self.input_ref_frame == "world":
|
| 446 |
+
desired_world_ori = self.goal_ori
|
| 447 |
+
else:
|
| 448 |
+
raise ValueError
|
| 449 |
+
ori_error = orientation_error(desired_world_ori, self.ref_ori_mat)
|
| 450 |
+
|
| 451 |
+
# Compute desired force and torque based on errors
|
| 452 |
+
position_error = desired_world_pos - self.ref_pos
|
| 453 |
+
base_pos_vel = np.array(self.sim.data.get_site_xvelp(f"{self.naming_prefix}{self.part_name}_center"))
|
| 454 |
+
vel_pos_error = -(self.ref_pos_vel - base_pos_vel)
|
| 455 |
+
|
| 456 |
+
# F_r = kp * pos_err + kd * vel_err
|
| 457 |
+
desired_force = np.multiply(np.array(position_error), np.array(self.kp[0:3])) + np.multiply(
|
| 458 |
+
vel_pos_error, self.kd[0:3]
|
| 459 |
+
)
|
| 460 |
+
|
| 461 |
+
base_ori_vel = np.array(self.sim.data.get_site_xvelr(f"{self.naming_prefix}{self.part_name}_center"))
|
| 462 |
+
vel_ori_error = -(self.ref_ori_vel - base_ori_vel)
|
| 463 |
+
|
| 464 |
+
# Tau_r = kp * ori_err + kd * vel_err
|
| 465 |
+
desired_torque = np.multiply(np.array(ori_error), np.array(self.kp[3:6])) + np.multiply(
|
| 466 |
+
vel_ori_error, self.kd[3:6]
|
| 467 |
+
)
|
| 468 |
+
|
| 469 |
+
# Compute nullspace matrix (I - Jbar * J) and lambda matrices ((J * M^-1 * J^T)^-1)
|
| 470 |
+
lambda_full, lambda_pos, lambda_ori, nullspace_matrix = opspace_matrices(
|
| 471 |
+
self.mass_matrix, self.J_full, self.J_pos, self.J_ori
|
| 472 |
+
)
|
| 473 |
+
|
| 474 |
+
# Decouples desired positional control from orientation control
|
| 475 |
+
if self.uncoupling:
|
| 476 |
+
decoupled_force = np.dot(lambda_pos, desired_force)
|
| 477 |
+
decoupled_torque = np.dot(lambda_ori, desired_torque)
|
| 478 |
+
decoupled_wrench = np.concatenate([decoupled_force, decoupled_torque])
|
| 479 |
+
else:
|
| 480 |
+
desired_wrench = np.concatenate([desired_force, desired_torque])
|
| 481 |
+
decoupled_wrench = np.dot(lambda_full, desired_wrench)
|
| 482 |
+
|
| 483 |
+
# Gamma (without null torques) = J^T * F + gravity compensations
|
| 484 |
+
self.torques = np.dot(self.J_full.T, decoupled_wrench) + self.torque_compensation
|
| 485 |
+
# Calculate and add nullspace torques (nullspace_matrix^T * Gamma_null) to final torques
|
| 486 |
+
# Note: Gamma_null = desired nullspace pose torques, assumed to be positional joint control relative
|
| 487 |
+
# to the initial joint positions
|
| 488 |
+
self.torques += nullspace_torques(
|
| 489 |
+
self.mass_matrix, nullspace_matrix, self.initial_joint, self.joint_pos, self.joint_vel
|
| 490 |
+
)
|
| 491 |
+
|
| 492 |
+
# Always run superclass call for any cleanups at the end
|
| 493 |
+
super().run_controller()
|
| 494 |
+
|
| 495 |
+
return self.torques
|
| 496 |
+
|
| 497 |
+
def update_origin(self, origin_pos, origin_ori):
|
| 498 |
+
"""
|
| 499 |
+
Optional function to implement in subclass controllers that will take in @origin_pos and @origin_ori and update
|
| 500 |
+
internal configuration to account for changes in the respective states. Useful for controllers in which the origin
|
| 501 |
+
is a frame of reference that is dynamically changing, e.g., adapting the arm to move along with a moving base.
|
| 502 |
+
|
| 503 |
+
Args:
|
| 504 |
+
origin_pos (3-tuple): x,y,z position of controller reference in mujoco world coordinates
|
| 505 |
+
origin_ori (np.array): 3x3 rotation matrix orientation of controller reference in mujoco world coordinates
|
| 506 |
+
"""
|
| 507 |
+
self.origin_pos = origin_pos
|
| 508 |
+
self.origin_ori = origin_ori
|
| 509 |
+
|
| 510 |
+
def update_initial_joints(self, initial_joints):
|
| 511 |
+
# First, update from the superclass method
|
| 512 |
+
super().update_initial_joints(initial_joints)
|
| 513 |
+
|
| 514 |
+
# We also need to reset the goal in case the old goals were set to the initial confguration
|
| 515 |
+
self.reset_goal()
|
| 516 |
+
|
| 517 |
+
def set_goal_update_mode(self, goal_update_mode):
|
| 518 |
+
self._goal_update_mode = goal_update_mode
|
| 519 |
+
|
| 520 |
+
def reset_goal(self, goal_update_mode="achieved"):
|
| 521 |
+
"""
|
| 522 |
+
Resets the goal to the current state of the robot.
|
| 523 |
+
|
| 524 |
+
Args:
|
| 525 |
+
goal_update_mode (str): set mode for updating controller goals,
|
| 526 |
+
either "achieved" (achieved position) or "desired" (desired goal).
|
| 527 |
+
"""
|
| 528 |
+
self.goal_ori = np.array(self.ref_ori_mat)
|
| 529 |
+
self.goal_pos = np.array(self.ref_pos)
|
| 530 |
+
|
| 531 |
+
assert goal_update_mode in ["achieved", "desired"]
|
| 532 |
+
self._goal_update_mode = goal_update_mode
|
| 533 |
+
|
| 534 |
+
# Also reset interpolators if required
|
| 535 |
+
|
| 536 |
+
if self.interpolator_pos is not None:
|
| 537 |
+
self.interpolator_pos.set_goal(self.goal_pos)
|
| 538 |
+
|
| 539 |
+
if self.interpolator_ori is not None:
|
| 540 |
+
self.ori_ref = np.array(self.ref_ori_mat) # reference is the current orientation at start
|
| 541 |
+
self.interpolator_ori.set_goal(
|
| 542 |
+
orientation_error(self.goal_ori, self.ori_ref)
|
| 543 |
+
) # goal is the total orientation error
|
| 544 |
+
self.relative_ori = np.zeros(3) # relative orientation always starts at 0
|
| 545 |
+
|
| 546 |
+
@property
|
| 547 |
+
def control_limits(self):
|
| 548 |
+
"""
|
| 549 |
+
Returns the limits over this controller's action space, overrides the superclass property
|
| 550 |
+
Returns the following (generalized for both high and low limits), based on the impedance mode:
|
| 551 |
+
|
| 552 |
+
:Mode `'fixed'`: [joint pos command]
|
| 553 |
+
:Mode `'variable'`: [damping_ratio values, kp values, joint pos command]
|
| 554 |
+
:Mode `'variable_kp'`: [kp values, joint pos command]
|
| 555 |
+
|
| 556 |
+
Returns:
|
| 557 |
+
2-tuple:
|
| 558 |
+
|
| 559 |
+
- (np.array) minimum action values
|
| 560 |
+
- (np.array) maximum action values
|
| 561 |
+
"""
|
| 562 |
+
if self.impedance_mode == "variable":
|
| 563 |
+
low = np.concatenate([self.damping_ratio_min, self.kp_min, self.input_min])
|
| 564 |
+
high = np.concatenate([self.damping_ratio_max, self.kp_max, self.input_max])
|
| 565 |
+
elif self.impedance_mode == "variable_kp":
|
| 566 |
+
low = np.concatenate([self.kp_min, self.input_min])
|
| 567 |
+
high = np.concatenate([self.kp_max, self.input_max])
|
| 568 |
+
else: # This is case "fixed"
|
| 569 |
+
low, high = self.input_min, self.input_max
|
| 570 |
+
return low, high
|
| 571 |
+
|
| 572 |
+
def delta_to_abs_action(self, delta_ac, goal_update_mode):
|
| 573 |
+
"""
|
| 574 |
+
helper function that converts delta action into absolute action
|
| 575 |
+
"""
|
| 576 |
+
abs_pos = self.compute_goal_pos(delta_ac[0:3], goal_update_mode=goal_update_mode)
|
| 577 |
+
abs_ori = self.compute_goal_ori(delta_ac[3:6], goal_update_mode=goal_update_mode)
|
| 578 |
+
abs_rot = T.quat2axisangle(T.mat2quat(abs_ori))
|
| 579 |
+
abs_action = np.concatenate([abs_pos, abs_rot])
|
| 580 |
+
return abs_action
|
| 581 |
+
|
| 582 |
+
@property
|
| 583 |
+
def name(self):
|
| 584 |
+
return "OSC_" + self.name_suffix
|
robosuite/controllers/parts/controller.py
ADDED
|
@@ -0,0 +1,347 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import abc
|
| 2 |
+
from collections.abc import Iterable
|
| 3 |
+
|
| 4 |
+
import mujoco
|
| 5 |
+
import numpy as np
|
| 6 |
+
|
| 7 |
+
import robosuite.macros as macros
|
| 8 |
+
|
| 9 |
+
|
| 10 |
+
class Controller(object, metaclass=abc.ABCMeta):
|
| 11 |
+
"""
|
| 12 |
+
General controller interface.
|
| 13 |
+
|
| 14 |
+
Requires reference to mujoco sim object, ref_name of specific robot, relevant joint_indexes to that robot, and
|
| 15 |
+
whether an initial_joint is used for nullspace torques or not
|
| 16 |
+
|
| 17 |
+
Args:
|
| 18 |
+
sim (MjSim): Simulator instance this controller will pull robot state updates from
|
| 19 |
+
|
| 20 |
+
ref_name (str): Name of controlled robot arm's end effector (from robot XML)
|
| 21 |
+
|
| 22 |
+
joint_indexes (dict): Each key contains sim reference indexes to relevant robot joint information, namely:
|
| 23 |
+
|
| 24 |
+
:`'joints'`: list of indexes to relevant robot joints
|
| 25 |
+
:`'qpos'`: list of indexes to relevant robot joint positions
|
| 26 |
+
:`'qvel'`: list of indexes to relevant robot joint velocities
|
| 27 |
+
|
| 28 |
+
actuator_range (2-tuple of array of float): 2-Tuple (low, high) representing the robot joint actuator range
|
| 29 |
+
|
| 30 |
+
lite_physics (bool): Whether to optimize for mujoco forward and step calls to reduce total simulation overhead.
|
| 31 |
+
Ignores all self.update() calls, unless set to force=True
|
| 32 |
+
Set to False to preserve backward compatibility with datasets collected in robosuite <= 1.4.1.
|
| 33 |
+
"""
|
| 34 |
+
|
| 35 |
+
def __init__(
|
| 36 |
+
self,
|
| 37 |
+
sim,
|
| 38 |
+
joint_indexes,
|
| 39 |
+
actuator_range,
|
| 40 |
+
ref_name=None,
|
| 41 |
+
part_name=None,
|
| 42 |
+
naming_prefix=None,
|
| 43 |
+
lite_physics=True,
|
| 44 |
+
):
|
| 45 |
+
|
| 46 |
+
# Actuator range
|
| 47 |
+
self.actuator_min = actuator_range[0]
|
| 48 |
+
self.actuator_max = actuator_range[1]
|
| 49 |
+
|
| 50 |
+
# Attributes for scaling / clipping inputs to outputs
|
| 51 |
+
self.action_scale = None
|
| 52 |
+
self.action_input_transform = None
|
| 53 |
+
self.action_output_transform = None
|
| 54 |
+
|
| 55 |
+
# Private property attributes
|
| 56 |
+
self.control_dim = None
|
| 57 |
+
self.output_min = None
|
| 58 |
+
self.output_max = None
|
| 59 |
+
self.input_min = None
|
| 60 |
+
self.input_max = None
|
| 61 |
+
|
| 62 |
+
# mujoco simulator state
|
| 63 |
+
self.sim = sim
|
| 64 |
+
self.model_timestep = macros.SIMULATION_TIMESTEP
|
| 65 |
+
self.lite_physics = lite_physics
|
| 66 |
+
self.ref_name = ref_name
|
| 67 |
+
# A list of site the controller want to follow
|
| 68 |
+
# self.ref_site_names = ref_site_names
|
| 69 |
+
|
| 70 |
+
self.part_name = part_name
|
| 71 |
+
self.naming_prefix = naming_prefix
|
| 72 |
+
self.joint_index = joint_indexes["joints"]
|
| 73 |
+
self.qpos_index = joint_indexes["qpos"]
|
| 74 |
+
self.qvel_index = joint_indexes["qvel"]
|
| 75 |
+
self.joint_names = [self.sim.model.joint_id2name(joint_id) for joint_id in self.joint_index]
|
| 76 |
+
|
| 77 |
+
# robot states
|
| 78 |
+
self.ref_pos = None
|
| 79 |
+
self.ref_ori_mat = None
|
| 80 |
+
self.ref_pos_vel = None
|
| 81 |
+
self.ref_ori_vel = None
|
| 82 |
+
|
| 83 |
+
self.joint_pos = None
|
| 84 |
+
self.joint_vel = None
|
| 85 |
+
|
| 86 |
+
# Joint dimension
|
| 87 |
+
self.joint_dim = len(joint_indexes["joints"])
|
| 88 |
+
|
| 89 |
+
if ref_name is None:
|
| 90 |
+
self.ref_names = None
|
| 91 |
+
self.num_ref_sites = 0
|
| 92 |
+
elif isinstance(ref_name, str):
|
| 93 |
+
self.ref_names = [ref_name]
|
| 94 |
+
self.num_ref_sites = 1
|
| 95 |
+
else:
|
| 96 |
+
self.ref_names = ref_name
|
| 97 |
+
self.num_ref_sites = len(ref_name)
|
| 98 |
+
|
| 99 |
+
# Initialize robot states
|
| 100 |
+
if self.num_ref_sites == 1:
|
| 101 |
+
# non-batched for backward compatibility
|
| 102 |
+
self.ref_pos = np.zeros(3)
|
| 103 |
+
self.ref_ori_mat = np.zeros((3, 3))
|
| 104 |
+
self.ref_pos_vel = np.zeros(3)
|
| 105 |
+
self.ref_ori_vel = np.zeros(3)
|
| 106 |
+
# Initialize Jacobians
|
| 107 |
+
self.J_pos = np.zeros((3, len(self.joint_index)))
|
| 108 |
+
self.J_ori = np.zeros((3, len(self.joint_index)))
|
| 109 |
+
self.J_full = np.zeros((6, len(self.joint_index)))
|
| 110 |
+
else:
|
| 111 |
+
self.ref_pos = np.zeros((self.num_ref_sites, 3))
|
| 112 |
+
self.ref_ori_mat = np.zeros((self.num_ref_sites, 3, 3))
|
| 113 |
+
self.ref_pos_vel = np.zeros((self.num_ref_sites, 3))
|
| 114 |
+
self.ref_ori_vel = np.zeros((self.num_ref_sites, 3))
|
| 115 |
+
# Initialize Jacobians
|
| 116 |
+
self.J_pos = np.zeros((self.num_ref_sites, 3, len(self.joint_index)))
|
| 117 |
+
self.J_ori = np.zeros((self.num_ref_sites, 3, len(self.joint_index)))
|
| 118 |
+
self.J_full = np.zeros((self.num_ref_sites, 6, len(self.joint_index)))
|
| 119 |
+
|
| 120 |
+
self.mass_matrix = None
|
| 121 |
+
|
| 122 |
+
# Torques being outputted by the controller
|
| 123 |
+
self.torques = None
|
| 124 |
+
|
| 125 |
+
# Update flag to prevent redundant update calls
|
| 126 |
+
self.new_update = True
|
| 127 |
+
|
| 128 |
+
# Move forward one timestep to propagate updates before taking first update
|
| 129 |
+
self.sim.forward()
|
| 130 |
+
|
| 131 |
+
# Initialize controller by updating internal state and setting the initial joint, pos, and ori
|
| 132 |
+
self.update()
|
| 133 |
+
self.initial_joint = self.joint_pos
|
| 134 |
+
self.initial_ref_pos = self.ref_pos
|
| 135 |
+
self.initial_ref_ori_mat = self.ref_ori_mat
|
| 136 |
+
|
| 137 |
+
self.origin_pos = None
|
| 138 |
+
self.origin_ori = None
|
| 139 |
+
|
| 140 |
+
@abc.abstractmethod
|
| 141 |
+
def run_controller(self):
|
| 142 |
+
"""
|
| 143 |
+
Abstract method that should be implemented in all subclass controllers, and should convert a given action
|
| 144 |
+
into torques (pre gravity compensation) to be executed on the robot.
|
| 145 |
+
Additionally, resets the self.new_update flag so that the next self.update call will occur
|
| 146 |
+
"""
|
| 147 |
+
self.new_update = True
|
| 148 |
+
|
| 149 |
+
def scale_action(self, action):
|
| 150 |
+
"""
|
| 151 |
+
Clips @action to be within self.input_min and self.input_max, and then re-scale the values to be within
|
| 152 |
+
the range self.output_min and self.output_max
|
| 153 |
+
|
| 154 |
+
Args:
|
| 155 |
+
action (Iterable): Actions to scale
|
| 156 |
+
|
| 157 |
+
Returns:
|
| 158 |
+
np.array: Re-scaled action
|
| 159 |
+
"""
|
| 160 |
+
|
| 161 |
+
if self.action_scale is None:
|
| 162 |
+
self.action_scale = abs(self.output_max - self.output_min) / abs(self.input_max - self.input_min)
|
| 163 |
+
self.action_output_transform = (self.output_max + self.output_min) / 2.0
|
| 164 |
+
self.action_input_transform = (self.input_max + self.input_min) / 2.0
|
| 165 |
+
action = np.clip(action, self.input_min, self.input_max)
|
| 166 |
+
transformed_action = (action - self.action_input_transform) * self.action_scale + self.action_output_transform
|
| 167 |
+
|
| 168 |
+
return transformed_action
|
| 169 |
+
|
| 170 |
+
def update_reference_data(self):
|
| 171 |
+
if self.num_ref_sites == 1:
|
| 172 |
+
self._update_single_reference(self.ref_name, 0)
|
| 173 |
+
else:
|
| 174 |
+
for i, name in enumerate(self.ref_name):
|
| 175 |
+
self._update_single_reference(name, i)
|
| 176 |
+
|
| 177 |
+
def _update_single_reference(self, name: str, index: int):
|
| 178 |
+
# TODO: remove if statement once we unify the shapes of variables when num_ref_sites == 1 and num_ref_sites > 1
|
| 179 |
+
ref_id = self.sim.model.site_name2id(name)
|
| 180 |
+
|
| 181 |
+
if self.num_ref_sites == 1:
|
| 182 |
+
self.ref_pos[:] = np.array(self.sim.data.site_xpos[ref_id])
|
| 183 |
+
self.ref_ori_mat[:, :] = np.array(self.sim.data.site_xmat[ref_id].reshape([3, 3]))
|
| 184 |
+
self.ref_pos_vel[:] = np.array(self.sim.data.get_site_xvelp(name))
|
| 185 |
+
self.ref_ori_vel[:] = np.array(self.sim.data.get_site_xvelr(name))
|
| 186 |
+
self.J_pos[:, :] = np.array(self.sim.data.get_site_jacp(name).reshape((3, -1))[:, self.qvel_index])
|
| 187 |
+
self.J_ori[:, :] = np.array(self.sim.data.get_site_jacr(name).reshape((3, -1))[:, self.qvel_index])
|
| 188 |
+
self.J_full[:, :] = np.vstack([self.J_pos, self.J_ori])
|
| 189 |
+
else:
|
| 190 |
+
self.ref_pos[index, :] = np.array(self.sim.data.site_xpos[ref_id])
|
| 191 |
+
self.ref_ori_mat[index, :, :] = np.array(self.sim.data.site_xmat[ref_id].reshape([3, 3]))
|
| 192 |
+
self.ref_pos_vel[index, :] = np.array(self.sim.data.get_site_xvelp(name))
|
| 193 |
+
self.ref_ori_vel[index, :] = np.array(self.sim.data.get_site_xvelr(name))
|
| 194 |
+
|
| 195 |
+
self.J_pos[index, :, :] = np.array(self.sim.data.get_site_jacp(name).reshape((3, -1))[:, self.qvel_index])
|
| 196 |
+
self.J_ori[index, :, :] = np.array(self.sim.data.get_site_jacr(name).reshape((3, -1))[:, self.qvel_index])
|
| 197 |
+
self.J_full[index, :, :] = np.vstack([self.J_pos[index], self.J_ori[index]])
|
| 198 |
+
|
| 199 |
+
def update(self, force=False):
|
| 200 |
+
"""
|
| 201 |
+
Updates the state of the robot arm, including end effector pose / orientation / velocity, joint pos/vel,
|
| 202 |
+
jacobian, and mass matrix. By default, since this is a non-negligible computation, multiple redundant calls
|
| 203 |
+
will be ignored via the self.new_update attribute flag. However, if the @force flag is set, the update will
|
| 204 |
+
occur regardless of that state of self.new_update. This base class method of @run_controller resets the
|
| 205 |
+
self.new_update flag
|
| 206 |
+
|
| 207 |
+
Args:
|
| 208 |
+
force (bool): Whether to force an update to occur or not
|
| 209 |
+
"""
|
| 210 |
+
|
| 211 |
+
# Only run update if self.new_update or force flag is set
|
| 212 |
+
if self.new_update or force:
|
| 213 |
+
# no need to call sim.forward if using lite_physics
|
| 214 |
+
if self.lite_physics and not force:
|
| 215 |
+
pass
|
| 216 |
+
else:
|
| 217 |
+
# BUG: Potential bug here. If there are more than two controlllers, the simulation will be forwarded multiple times.
|
| 218 |
+
self.sim.forward()
|
| 219 |
+
|
| 220 |
+
if self.ref_name is not None:
|
| 221 |
+
self.update_reference_data()
|
| 222 |
+
|
| 223 |
+
self.joint_pos = np.array(self.sim.data.qpos[self.qpos_index])
|
| 224 |
+
self.joint_vel = np.array(self.sim.data.qvel[self.qvel_index])
|
| 225 |
+
|
| 226 |
+
mass_matrix = np.ndarray(shape=(self.sim.model.nv, self.sim.model.nv), dtype=np.float64, order="C")
|
| 227 |
+
mujoco.mj_fullM(self.sim.model._model, mass_matrix, self.sim.data.qM)
|
| 228 |
+
mass_matrix = np.reshape(mass_matrix, (len(self.sim.data.qvel), len(self.sim.data.qvel)))
|
| 229 |
+
self.mass_matrix = mass_matrix[self.qvel_index, :][:, self.qvel_index]
|
| 230 |
+
|
| 231 |
+
# Clear self.new_update
|
| 232 |
+
self.new_update = False
|
| 233 |
+
|
| 234 |
+
def update_origin(self, origin_pos, origin_ori):
|
| 235 |
+
"""
|
| 236 |
+
Optional function to implement in subclass controllers that will take in @origin_pos and @origin_ori and update
|
| 237 |
+
internal configuration to account for changes in the respective states. Useful for controllers in which the origin
|
| 238 |
+
is a frame of reference that is dynamically changing, e.g., adapting the arm to move along with a moving base.
|
| 239 |
+
|
| 240 |
+
Args:
|
| 241 |
+
origin_pos (3-tuple): x,y,z position of controller reference in mujoco world coordinates
|
| 242 |
+
origin_ori (np.array): 3x3 rotation matrix orientation of controller reference in mujoco world coordinates
|
| 243 |
+
"""
|
| 244 |
+
self.origin_pos = origin_pos
|
| 245 |
+
self.origin_ori = origin_ori
|
| 246 |
+
|
| 247 |
+
def update_initial_joints(self, initial_joints):
|
| 248 |
+
"""
|
| 249 |
+
Updates the internal attribute self.initial_joints. This is useful for updating changes in controller-specific
|
| 250 |
+
behavior, such as with OSC where self.initial_joints is used for determine nullspace actions
|
| 251 |
+
|
| 252 |
+
This function can also be extended by subclassed controllers for additional controller-specific updates
|
| 253 |
+
|
| 254 |
+
Args:
|
| 255 |
+
initial_joints (Iterable): Array of joint position values to update the initial joints
|
| 256 |
+
"""
|
| 257 |
+
self.initial_joint = np.array(initial_joints)
|
| 258 |
+
self.update(force=True)
|
| 259 |
+
|
| 260 |
+
if self.ref_name is not None:
|
| 261 |
+
self.initial_ref_pos = self.ref_pos
|
| 262 |
+
self.initial_ref_ori_mat = self.ref_ori_mat
|
| 263 |
+
|
| 264 |
+
def clip_torques(self, torques):
|
| 265 |
+
"""
|
| 266 |
+
Clips the torques to be within the actuator limits
|
| 267 |
+
|
| 268 |
+
Args:
|
| 269 |
+
torques (Iterable): Torques to clip
|
| 270 |
+
|
| 271 |
+
Returns:
|
| 272 |
+
np.array: Clipped torques
|
| 273 |
+
"""
|
| 274 |
+
return np.clip(torques, self.actuator_min, self.actuator_max)
|
| 275 |
+
|
| 276 |
+
def reset_goal(self):
|
| 277 |
+
"""
|
| 278 |
+
Resets the goal -- usually by setting to the goal to all zeros, but in some cases may be different (e.g.: OSC)
|
| 279 |
+
"""
|
| 280 |
+
raise NotImplementedError
|
| 281 |
+
|
| 282 |
+
@staticmethod
|
| 283 |
+
def nums2array(nums, dim):
|
| 284 |
+
"""
|
| 285 |
+
Convert input @nums into numpy array of length @dim. If @nums is a single number, broadcasts it to the
|
| 286 |
+
corresponding dimension size @dim before converting into a numpy array
|
| 287 |
+
|
| 288 |
+
Args:
|
| 289 |
+
nums (numeric or Iterable): Either single value or array of numbers
|
| 290 |
+
dim (int): Size of array to broadcast input to env.sim.data.actuator_force
|
| 291 |
+
|
| 292 |
+
Returns:
|
| 293 |
+
np.array: Array filled with values specified in @nums
|
| 294 |
+
"""
|
| 295 |
+
# First run sanity check to make sure no strings are being inputted
|
| 296 |
+
if isinstance(nums, str):
|
| 297 |
+
raise TypeError("Error: Only numeric inputs are supported for this function, nums2array!")
|
| 298 |
+
|
| 299 |
+
# Check if input is an Iterable, if so, we simply convert the input to np.array and return
|
| 300 |
+
# Else, input is a single value, so we map to a numpy array of correct size and return
|
| 301 |
+
return np.array(nums) if isinstance(nums, Iterable) else np.ones(dim) * nums
|
| 302 |
+
|
| 303 |
+
@property
|
| 304 |
+
def torque_compensation(self):
|
| 305 |
+
"""
|
| 306 |
+
Gravity compensation for this robot arm
|
| 307 |
+
|
| 308 |
+
Returns:
|
| 309 |
+
np.array: torques
|
| 310 |
+
"""
|
| 311 |
+
return self.sim.data.qfrc_bias[self.qvel_index]
|
| 312 |
+
|
| 313 |
+
@property
|
| 314 |
+
def actuator_limits(self):
|
| 315 |
+
"""
|
| 316 |
+
Torque limits for this controller
|
| 317 |
+
|
| 318 |
+
Returns:
|
| 319 |
+
2-tuple:
|
| 320 |
+
|
| 321 |
+
- (np.array) minimum actuator torques
|
| 322 |
+
- (np.array) maximum actuator torques
|
| 323 |
+
"""
|
| 324 |
+
return self.actuator_min, self.actuator_max
|
| 325 |
+
|
| 326 |
+
@property
|
| 327 |
+
def control_limits(self):
|
| 328 |
+
"""
|
| 329 |
+
Limits over this controller's action space, which defaults to input min/max
|
| 330 |
+
|
| 331 |
+
Returns:
|
| 332 |
+
2-tuple:
|
| 333 |
+
|
| 334 |
+
- (np.array) minimum action values
|
| 335 |
+
- (np.array) maximum action values
|
| 336 |
+
"""
|
| 337 |
+
return self.input_min, self.input_max
|
| 338 |
+
|
| 339 |
+
@property
|
| 340 |
+
def name(self):
|
| 341 |
+
"""
|
| 342 |
+
Name of this controller
|
| 343 |
+
|
| 344 |
+
Returns:
|
| 345 |
+
str: controller name
|
| 346 |
+
"""
|
| 347 |
+
raise NotImplementedError
|
robosuite/controllers/parts/controller_factory.py
ADDED
|
@@ -0,0 +1,232 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
"""
|
| 2 |
+
Set of functions that streamline controller initialization process
|
| 3 |
+
"""
|
| 4 |
+
import json
|
| 5 |
+
import os
|
| 6 |
+
from copy import deepcopy
|
| 7 |
+
|
| 8 |
+
import numpy as np
|
| 9 |
+
|
| 10 |
+
from robosuite.controllers.parts import arm as arm_controllers
|
| 11 |
+
from robosuite.controllers.parts import generic
|
| 12 |
+
from robosuite.controllers.parts import gripper as gripper_controllers
|
| 13 |
+
from robosuite.controllers.parts import mobile_base as mobile_base_controllers
|
| 14 |
+
from robosuite.utils.traj_utils import LinearInterpolator
|
| 15 |
+
|
| 16 |
+
# from . import legs as legs_controllers
|
| 17 |
+
|
| 18 |
+
|
| 19 |
+
def load_part_controller_config(custom_fpath=None, default_controller=None):
|
| 20 |
+
"""
|
| 21 |
+
Utility function that loads the desired controller and returns the loaded configuration as a dict
|
| 22 |
+
|
| 23 |
+
If @default_controller is specified, any value inputted to @custom_fpath is overridden and the default controller
|
| 24 |
+
configuration is automatically loaded. See specific arg description below for available default controllers.
|
| 25 |
+
|
| 26 |
+
Args:
|
| 27 |
+
custom_fpath (str): Absolute filepath to the custom controller configuration .json file to be loaded
|
| 28 |
+
default_controller (str): If specified, overrides @custom_fpath and loads a default configuration file for the
|
| 29 |
+
specified controller.
|
| 30 |
+
Choices are: {"JOINT_POSITION", "JOINT_TORQUE", "JOINT_VELOCITY", "OSC_POSITION", "OSC_POSE", "IK_POSE"}
|
| 31 |
+
|
| 32 |
+
Returns:
|
| 33 |
+
dict: Controller configuration
|
| 34 |
+
|
| 35 |
+
Raises:
|
| 36 |
+
AssertionError: [Unknown default controller name]
|
| 37 |
+
AssertionError: [No controller specified]
|
| 38 |
+
"""
|
| 39 |
+
# TODO (YL): this is nolonger usable, need to update
|
| 40 |
+
# First check if default controller is not None; if it
|
| 41 |
+
# is not, load the appropriate controller
|
| 42 |
+
if default_controller is not None:
|
| 43 |
+
|
| 44 |
+
# Assert that requested default controller is in the available default controllers
|
| 45 |
+
from robosuite.controllers import ALL_PART_CONTROLLERS
|
| 46 |
+
|
| 47 |
+
assert (
|
| 48 |
+
default_controller in ALL_PART_CONTROLLERS
|
| 49 |
+
), "Error: Unknown default controller specified. Requested {}, " "available controllers: {}".format(
|
| 50 |
+
default_controller, list(ALL_PART_CONTROLLERS)
|
| 51 |
+
)
|
| 52 |
+
|
| 53 |
+
# Store the default controller config fpath associated with the requested controller
|
| 54 |
+
custom_fpath = os.path.join(
|
| 55 |
+
os.path.dirname(__file__), "..", "config/default/parts/{}.json".format(default_controller.lower())
|
| 56 |
+
)
|
| 57 |
+
|
| 58 |
+
# Assert that the fpath to load the controller is not empty
|
| 59 |
+
assert custom_fpath is not None, "Error: Either custom_fpath or default_controller must be specified!"
|
| 60 |
+
|
| 61 |
+
# Attempt to load the controller
|
| 62 |
+
try:
|
| 63 |
+
with open(custom_fpath) as f:
|
| 64 |
+
controller_config = json.load(f)
|
| 65 |
+
except FileNotFoundError:
|
| 66 |
+
print("Error opening controller filepath at: {}. " "Please check filepath and try again.".format(custom_fpath))
|
| 67 |
+
raise FileNotFoundError
|
| 68 |
+
|
| 69 |
+
# Return the loaded controller
|
| 70 |
+
return controller_config
|
| 71 |
+
|
| 72 |
+
|
| 73 |
+
def arm_controller_factory(name, params):
|
| 74 |
+
"""
|
| 75 |
+
Generator for controllers
|
| 76 |
+
|
| 77 |
+
Creates a Controller instance with the provided @name and relevant @params.
|
| 78 |
+
|
| 79 |
+
Args:
|
| 80 |
+
name (str): the name of the controller. Must be one of: {JOINT_POSITION, JOINT_TORQUE, JOINT_VELOCITY,
|
| 81 |
+
OSC_POSITION, OSC_POSE, IK_POSE}
|
| 82 |
+
params (dict): dict containing the relevant params to pass to the controller
|
| 83 |
+
sim (MjSim): Mujoco sim reference to pass to the controller
|
| 84 |
+
|
| 85 |
+
Returns:
|
| 86 |
+
Controller: Controller instance
|
| 87 |
+
|
| 88 |
+
Raises:
|
| 89 |
+
ValueError: [unknown controller]
|
| 90 |
+
"""
|
| 91 |
+
|
| 92 |
+
interpolator = None
|
| 93 |
+
if params["interpolation"] == "linear":
|
| 94 |
+
interpolator = LinearInterpolator(
|
| 95 |
+
ndim=params["ndim"],
|
| 96 |
+
controller_freq=(1 / params["sim"].model.opt.timestep),
|
| 97 |
+
policy_freq=params["policy_freq"],
|
| 98 |
+
ramp_ratio=params["ramp_ratio"],
|
| 99 |
+
)
|
| 100 |
+
|
| 101 |
+
if name == "OSC_POSE":
|
| 102 |
+
ori_interpolator = None
|
| 103 |
+
if interpolator is not None:
|
| 104 |
+
interpolator.set_states(dim=3) # EE control uses dim 3 for pos and ori each
|
| 105 |
+
ori_interpolator = deepcopy(interpolator)
|
| 106 |
+
ori_interpolator.set_states(ori="euler")
|
| 107 |
+
params["control_ori"] = True
|
| 108 |
+
return arm_controllers.OperationalSpaceController(
|
| 109 |
+
interpolator_pos=interpolator, interpolator_ori=ori_interpolator, **params
|
| 110 |
+
)
|
| 111 |
+
|
| 112 |
+
if name == "OSC_POSITION":
|
| 113 |
+
if interpolator is not None:
|
| 114 |
+
interpolator.set_states(dim=3) # EE control uses dim 3 for pos
|
| 115 |
+
params["control_ori"] = False
|
| 116 |
+
return arm_controllers.OperationalSpaceController(interpolator_pos=interpolator, **params)
|
| 117 |
+
|
| 118 |
+
if name == "IK_POSE":
|
| 119 |
+
ori_interpolator = None
|
| 120 |
+
if interpolator is not None:
|
| 121 |
+
interpolator.set_states(dim=3) # EE IK control uses dim 3 for pos and dim 4 for ori
|
| 122 |
+
ori_interpolator = deepcopy(interpolator)
|
| 123 |
+
ori_interpolator.set_states(dim=4, ori="quat")
|
| 124 |
+
|
| 125 |
+
from robosuite.controllers.parts.arm.ik import InverseKinematicsController
|
| 126 |
+
|
| 127 |
+
return InverseKinematicsController(
|
| 128 |
+
interpolator_pos=interpolator,
|
| 129 |
+
interpolator_ori=ori_interpolator,
|
| 130 |
+
**params,
|
| 131 |
+
)
|
| 132 |
+
|
| 133 |
+
if name == "JOINT_VELOCITY":
|
| 134 |
+
return generic.JointVelocityController(interpolator=interpolator, **params)
|
| 135 |
+
|
| 136 |
+
if name == "JOINT_POSITION":
|
| 137 |
+
return generic.JointPositionController(interpolator=interpolator, **params)
|
| 138 |
+
|
| 139 |
+
if name == "JOINT_TORQUE":
|
| 140 |
+
return generic.JointTorqueController(interpolator=interpolator, **params)
|
| 141 |
+
|
| 142 |
+
raise ValueError("Unknown controller name: {}".format(name))
|
| 143 |
+
|
| 144 |
+
|
| 145 |
+
def controller_factory(part_name, controller_type, controller_params):
|
| 146 |
+
if part_name in ["right", "left"]:
|
| 147 |
+
return arm_controller_factory(controller_type, controller_params)
|
| 148 |
+
elif part_name in ["right_gripper", "left_gripper"]:
|
| 149 |
+
return gripper_controller_factory(controller_type, controller_params)
|
| 150 |
+
elif part_name == "base":
|
| 151 |
+
return mobile_base_controller_factory(controller_type, controller_params)
|
| 152 |
+
elif part_name == "torso":
|
| 153 |
+
return torso_controller_factory(controller_type, controller_params)
|
| 154 |
+
elif part_name == "head":
|
| 155 |
+
return head_controller_factory(controller_type, controller_params)
|
| 156 |
+
elif part_name == "legs":
|
| 157 |
+
return legs_controller_factory(controller_type, controller_params)
|
| 158 |
+
else:
|
| 159 |
+
raise ValueError("Unknown controller part name: {}".format(part_name))
|
| 160 |
+
|
| 161 |
+
|
| 162 |
+
def gripper_controller_factory(name, params):
|
| 163 |
+
interpolator = None
|
| 164 |
+
if name == "GRIP":
|
| 165 |
+
return gripper_controllers.SimpleGripController(interpolator=interpolator, **params)
|
| 166 |
+
elif name == "JOINT_POSITION":
|
| 167 |
+
return generic.JointPositionController(interpolator=interpolator, **params)
|
| 168 |
+
raise ValueError("Unknown controller name: {}".format(name))
|
| 169 |
+
|
| 170 |
+
|
| 171 |
+
def mobile_base_controller_factory(name, params):
|
| 172 |
+
interpolator = None
|
| 173 |
+
if name == "JOINT_VELOCITY":
|
| 174 |
+
return mobile_base_controllers.MobileBaseJointVelocityController(interpolator=interpolator, **params)
|
| 175 |
+
elif name == "JOINT_VELOCITY_LEGACY":
|
| 176 |
+
return mobile_base_controllers.LegacyMobileBaseJointVelocityController(interpolator=interpolator, **params)
|
| 177 |
+
elif name == "JOINT_POSITION":
|
| 178 |
+
raise NotImplementedError
|
| 179 |
+
raise ValueError("Unknown controller name: {}".format(name))
|
| 180 |
+
|
| 181 |
+
|
| 182 |
+
def torso_controller_factory(name, params):
|
| 183 |
+
interpolator = None
|
| 184 |
+
if params["interpolation"] == "linear":
|
| 185 |
+
interpolator = LinearInterpolator(
|
| 186 |
+
ndim=params["ndim"],
|
| 187 |
+
controller_freq=(1 / params["sim"].model.opt.timestep),
|
| 188 |
+
policy_freq=params["policy_freq"],
|
| 189 |
+
ramp_ratio=params["ramp_ratio"],
|
| 190 |
+
)
|
| 191 |
+
|
| 192 |
+
if name == "JOINT_VELOCITY":
|
| 193 |
+
return generic.JointVelocityController(interpolator=interpolator, **params)
|
| 194 |
+
elif name == "JOINT_POSITION":
|
| 195 |
+
return generic.JointPositionController(interpolator=interpolator, **params)
|
| 196 |
+
raise ValueError("Unknown controller name: {}".format(name))
|
| 197 |
+
|
| 198 |
+
|
| 199 |
+
def head_controller_factory(name, params):
|
| 200 |
+
interpolator = None
|
| 201 |
+
if params["interpolation"] == "linear":
|
| 202 |
+
interpolator = LinearInterpolator(
|
| 203 |
+
ndim=params["ndim"],
|
| 204 |
+
controller_freq=(1 / params["sim"].model.opt.timestep),
|
| 205 |
+
policy_freq=params["policy_freq"],
|
| 206 |
+
ramp_ratio=params["ramp_ratio"],
|
| 207 |
+
)
|
| 208 |
+
|
| 209 |
+
if name == "JOINT_VELOCITY":
|
| 210 |
+
return generic.JointVelocityController(interpolator=interpolator, **params)
|
| 211 |
+
elif name == "JOINT_POSITION":
|
| 212 |
+
return generic.JointPositionController(interpolator=interpolator, **params)
|
| 213 |
+
raise ValueError("Unknown controller name: {}".format(name))
|
| 214 |
+
|
| 215 |
+
|
| 216 |
+
def legs_controller_factory(name, params):
|
| 217 |
+
interpolator = None
|
| 218 |
+
if params["interpolation"] == "linear":
|
| 219 |
+
interpolator = LinearInterpolator(
|
| 220 |
+
ndim=params["ndim"],
|
| 221 |
+
controller_freq=(1 / params["sim"].model.opt.timestep),
|
| 222 |
+
policy_freq=params["policy_freq"],
|
| 223 |
+
ramp_ratio=params["ramp_ratio"],
|
| 224 |
+
)
|
| 225 |
+
|
| 226 |
+
if name == "JOINT_POSITION":
|
| 227 |
+
return generic.JointPositionController(interpolator=interpolator, **params)
|
| 228 |
+
|
| 229 |
+
if name == "JOINT_TORQUE":
|
| 230 |
+
return generic.JointTorqueController(interpolator=interpolator, **params)
|
| 231 |
+
|
| 232 |
+
raise ValueError("Unknown controller name: {}".format(name))
|
robosuite/controllers/parts/generic/__init__.py
ADDED
|
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
from .joint_pos import JointPositionController
|
| 2 |
+
from .joint_vel import JointVelocityController
|
| 3 |
+
from .joint_tor import JointTorqueController
|
robosuite/controllers/parts/generic/joint_pos.py
ADDED
|
@@ -0,0 +1,312 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
from typing import Dict, List, Literal
|
| 2 |
+
|
| 3 |
+
import numpy as np
|
| 4 |
+
|
| 5 |
+
from robosuite.controllers.parts.controller import Controller
|
| 6 |
+
from robosuite.utils.control_utils import *
|
| 7 |
+
|
| 8 |
+
# Supported impedance modes
|
| 9 |
+
IMPEDANCE_MODES = {"fixed", "variable", "variable_kp"}
|
| 10 |
+
|
| 11 |
+
|
| 12 |
+
class JointPositionController(Controller):
|
| 13 |
+
"""
|
| 14 |
+
Controller for controlling robot arm via impedance control. Allows position control of the robot's joints.
|
| 15 |
+
|
| 16 |
+
NOTE: Control input actions assumed to be taken relative to the current joint positions. A given action to this
|
| 17 |
+
controller is assumed to be of the form: (dpos_j0, dpos_j1, ... , dpos_jn-1) for an n-joint robot
|
| 18 |
+
|
| 19 |
+
Args:
|
| 20 |
+
sim (MjSim): Simulator instance this controller will pull robot state updates from
|
| 21 |
+
|
| 22 |
+
eef_name (str): Name of controlled robot arm's end effector (from robot XML)
|
| 23 |
+
|
| 24 |
+
joint_indexes (dict): Each key contains sim reference indexes to relevant robot joint information, namely:
|
| 25 |
+
|
| 26 |
+
:`'joints'`: list of indexes to relevant robot joints
|
| 27 |
+
:`'qpos'`: list of indexes to relevant robot joint positions
|
| 28 |
+
:`'qvel'`: list of indexes to relevant robot joint velocities
|
| 29 |
+
|
| 30 |
+
actuator_range (2-tuple of array of float): 2-Tuple (low, high) representing the robot joint actuator range
|
| 31 |
+
|
| 32 |
+
input_max (float or Iterable of float): Maximum above which an inputted action will be clipped. Can be either be
|
| 33 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 34 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 35 |
+
|
| 36 |
+
input_min (float or Iterable of float): Minimum below which an inputted action will be clipped. Can be either be
|
| 37 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 38 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 39 |
+
|
| 40 |
+
output_max (float or Iterable of float): Maximum which defines upper end of scaling range when scaling an input
|
| 41 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 42 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 43 |
+
|
| 44 |
+
output_min (float or Iterable of float): Minimum which defines upper end of scaling range when scaling an input
|
| 45 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 46 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 47 |
+
|
| 48 |
+
kp (float or Iterable of float): positional gain for determining desired torques based upon the joint pos error.
|
| 49 |
+
Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)
|
| 50 |
+
|
| 51 |
+
damping_ratio (float or Iterable of float): used in conjunction with kp to determine the velocity gain for
|
| 52 |
+
determining desired torques based upon the joint pos errors. Can be either be a scalar (same value for all
|
| 53 |
+
action dims), or a list (specific values for each dim)
|
| 54 |
+
|
| 55 |
+
impedance_mode (str): Impedance mode with which to run this controller. Options are {"fixed", "variable",
|
| 56 |
+
"variable_kp"}. If "fixed", the controller will have fixed kp and damping_ratio values as specified by the
|
| 57 |
+
@kp and @damping_ratio arguments. If "variable", both kp and damping_ratio will now be part of the
|
| 58 |
+
controller action space, resulting in a total action space of num_joints * 3. If "variable_kp", only kp
|
| 59 |
+
will become variable, with damping_ratio fixed at 1 (critically damped). The resulting action space will
|
| 60 |
+
then be num_joints * 2.
|
| 61 |
+
|
| 62 |
+
kp_limits (2-list of float or 2-list of Iterable of floats): Only applicable if @impedance_mode is set to either
|
| 63 |
+
"variable" or "variable_kp". This sets the corresponding min / max ranges of the controller action space
|
| 64 |
+
for the varying kp values. Can be either be a 2-list (same min / max for all kp action dims), or a 2-list
|
| 65 |
+
of list (specific min / max for each kp dim)
|
| 66 |
+
|
| 67 |
+
damping_ratio_limits (2-list of float or 2-list of Iterable of floats): Only applicable if @impedance_mode is
|
| 68 |
+
set to "variable". This sets the corresponding min / max ranges of the controller action space for the
|
| 69 |
+
varying damping_ratio values. Can be either be a 2-list (same min / max for all damping_ratio action dims),
|
| 70 |
+
or a 2-list of list (specific min / max for each damping_ratio dim)
|
| 71 |
+
|
| 72 |
+
policy_freq (int): Frequency at which actions from the robot policy are fed into this controller
|
| 73 |
+
|
| 74 |
+
qpos_limits (2-list of float or 2-list of Iterable of floats): Limits (rad) below and above which the magnitude
|
| 75 |
+
of a calculated goal joint position will be clipped. Can be either be a 2-list (same min/max value for all
|
| 76 |
+
joint dims), or a 2-list of list (specific min/max values for each dim)
|
| 77 |
+
|
| 78 |
+
interpolator (Interpolator): Interpolator object to be used for interpolating from the current joint position to
|
| 79 |
+
the goal joint position during each timestep between inputted actions
|
| 80 |
+
|
| 81 |
+
**kwargs: Does nothing; placeholder to "sink" any additional arguments so that instantiating this controller
|
| 82 |
+
via an argument dict that has additional extraneous arguments won't raise an error
|
| 83 |
+
|
| 84 |
+
Raises:
|
| 85 |
+
AssertionError: [Invalid impedance mode]
|
| 86 |
+
"""
|
| 87 |
+
|
| 88 |
+
def __init__(
|
| 89 |
+
self,
|
| 90 |
+
sim,
|
| 91 |
+
joint_indexes,
|
| 92 |
+
actuator_range,
|
| 93 |
+
ref_name=None,
|
| 94 |
+
input_max=1,
|
| 95 |
+
input_min=-1,
|
| 96 |
+
output_max=0.05,
|
| 97 |
+
output_min=-0.05,
|
| 98 |
+
kp=50,
|
| 99 |
+
damping_ratio=1,
|
| 100 |
+
impedance_mode="fixed",
|
| 101 |
+
kp_limits=(0, 300),
|
| 102 |
+
damping_ratio_limits=(0, 100),
|
| 103 |
+
policy_freq=20,
|
| 104 |
+
lite_physics=True,
|
| 105 |
+
qpos_limits=None,
|
| 106 |
+
interpolator=None,
|
| 107 |
+
input_type: Literal["delta", "absolute"] = "delta",
|
| 108 |
+
**kwargs, # does nothing; used so no error raised when dict is passed with extra terms used previously
|
| 109 |
+
):
|
| 110 |
+
|
| 111 |
+
super().__init__(
|
| 112 |
+
sim,
|
| 113 |
+
ref_name=ref_name,
|
| 114 |
+
joint_indexes=joint_indexes,
|
| 115 |
+
actuator_range=actuator_range,
|
| 116 |
+
part_name=kwargs.get("part_name", None),
|
| 117 |
+
naming_prefix=kwargs.get("naming_prefix", None),
|
| 118 |
+
lite_physics=lite_physics,
|
| 119 |
+
)
|
| 120 |
+
|
| 121 |
+
self.joint_indexes = joint_indexes
|
| 122 |
+
|
| 123 |
+
# Control dimension
|
| 124 |
+
self.control_dim = len(joint_indexes["joints"])
|
| 125 |
+
|
| 126 |
+
# input and output max and min (allow for either explicit lists or single numbers)
|
| 127 |
+
self.input_max = self.nums2array(input_max, self.control_dim)
|
| 128 |
+
self.input_min = self.nums2array(input_min, self.control_dim)
|
| 129 |
+
self.output_max = self.nums2array(output_max, self.control_dim)
|
| 130 |
+
self.output_min = self.nums2array(output_min, self.control_dim)
|
| 131 |
+
|
| 132 |
+
# limits
|
| 133 |
+
self.position_limits = np.array(qpos_limits) if qpos_limits is not None else qpos_limits
|
| 134 |
+
|
| 135 |
+
# kp kd
|
| 136 |
+
self.kp = self.nums2array(kp, self.control_dim)
|
| 137 |
+
self.kd = (
|
| 138 |
+
2 * np.sqrt(self.kp) * damping_ratio
|
| 139 |
+
if kwargs.get("kd", None) is None
|
| 140 |
+
else self.nums2array(kwargs.get("kd", None), self.control_dim)
|
| 141 |
+
)
|
| 142 |
+
|
| 143 |
+
# kp and kd limits
|
| 144 |
+
self.kp_min = self.nums2array(kp_limits[0], self.control_dim)
|
| 145 |
+
self.kp_max = self.nums2array(kp_limits[1], self.control_dim)
|
| 146 |
+
self.damping_ratio_min = self.nums2array(damping_ratio_limits[0], self.control_dim)
|
| 147 |
+
self.damping_ratio_max = self.nums2array(damping_ratio_limits[1], self.control_dim)
|
| 148 |
+
|
| 149 |
+
# Verify the proposed impedance mode is supported
|
| 150 |
+
assert impedance_mode in IMPEDANCE_MODES, (
|
| 151 |
+
"Error: Tried to instantiate OSC controller for unsupported "
|
| 152 |
+
"impedance mode! Inputted impedance mode: {}, Supported modes: {}".format(impedance_mode, IMPEDANCE_MODES)
|
| 153 |
+
)
|
| 154 |
+
|
| 155 |
+
# Impedance mode
|
| 156 |
+
self.impedance_mode = impedance_mode
|
| 157 |
+
|
| 158 |
+
# Add to control dim based on impedance_mode
|
| 159 |
+
if self.impedance_mode == "variable":
|
| 160 |
+
self.control_dim *= 3
|
| 161 |
+
elif self.impedance_mode == "variable_kp":
|
| 162 |
+
self.control_dim *= 2
|
| 163 |
+
|
| 164 |
+
# control frequency
|
| 165 |
+
self.control_freq = policy_freq
|
| 166 |
+
|
| 167 |
+
# interpolator
|
| 168 |
+
self.interpolator = interpolator
|
| 169 |
+
|
| 170 |
+
self.input_type = input_type
|
| 171 |
+
assert self.input_type in ["delta", "absolute"], f"Input type must be delta or absolute, got: {self.input_type}"
|
| 172 |
+
if self.input_type == "absolute":
|
| 173 |
+
assert self.impedance_mode == "fixed", "Absolute input type is only supported for fixed impedance mode."
|
| 174 |
+
|
| 175 |
+
# initialize
|
| 176 |
+
self.goal_qpos = None
|
| 177 |
+
|
| 178 |
+
self.use_torque_compensation = kwargs.get("use_torque_compensation", True)
|
| 179 |
+
|
| 180 |
+
def set_goal(self, action, set_qpos=None):
|
| 181 |
+
"""
|
| 182 |
+
Sets goal based on input @action. If self.impedance_mode is not "fixed", then the input will be parsed into the
|
| 183 |
+
delta values to update the goal position / pose and the kp and/or damping_ratio values to be immediately updated
|
| 184 |
+
internally before executing the proceeding control loop.
|
| 185 |
+
|
| 186 |
+
Note that @action expected to be in the following format, based on impedance mode!
|
| 187 |
+
|
| 188 |
+
:Mode `'fixed'`: [joint pos command]
|
| 189 |
+
:Mode `'variable'`: [damping_ratio values, kp values, joint pos command]
|
| 190 |
+
:Mode `'variable_kp'`: [kp values, joint pos command]
|
| 191 |
+
|
| 192 |
+
Args:
|
| 193 |
+
action (Iterable): Desired relative joint position goal state
|
| 194 |
+
set_qpos (Iterable): If set, overrides @action and sets the desired absolute joint position goal state
|
| 195 |
+
|
| 196 |
+
Raises:
|
| 197 |
+
AssertionError: [Invalid action dimension size]
|
| 198 |
+
"""
|
| 199 |
+
# Update state
|
| 200 |
+
self.update()
|
| 201 |
+
|
| 202 |
+
if self.input_type == "delta":
|
| 203 |
+
# Parse action based on the impedance mode, and update kp / kd as necessary
|
| 204 |
+
jnt_dim = len(self.qpos_index)
|
| 205 |
+
if self.impedance_mode == "variable":
|
| 206 |
+
damping_ratio, kp, delta = action[:jnt_dim], action[jnt_dim : 2 * jnt_dim], action[2 * jnt_dim :]
|
| 207 |
+
self.kp = np.clip(kp, self.kp_min, self.kp_max)
|
| 208 |
+
self.kd = 2 * np.sqrt(self.kp) * np.clip(damping_ratio, self.damping_ratio_min, self.damping_ratio_max)
|
| 209 |
+
elif self.impedance_mode == "variable_kp":
|
| 210 |
+
kp, delta = action[:jnt_dim], action[jnt_dim:]
|
| 211 |
+
self.kp = np.clip(kp, self.kp_min, self.kp_max)
|
| 212 |
+
self.kd = 2 * np.sqrt(self.kp) # critically damped
|
| 213 |
+
else: # This is case "fixed"
|
| 214 |
+
delta = action
|
| 215 |
+
|
| 216 |
+
# Check to make sure delta is size self.joint_dim
|
| 217 |
+
assert len(delta) == jnt_dim, "Delta qpos must be equal to the robot's joint dimension space!"
|
| 218 |
+
|
| 219 |
+
if delta is not None:
|
| 220 |
+
scaled_delta = self.scale_action(delta)
|
| 221 |
+
else:
|
| 222 |
+
scaled_delta = None
|
| 223 |
+
|
| 224 |
+
self.goal_qpos = set_goal_position(
|
| 225 |
+
scaled_delta, self.joint_pos, position_limit=self.position_limits, set_pos=set_qpos
|
| 226 |
+
)
|
| 227 |
+
elif self.input_type == "absolute":
|
| 228 |
+
self.goal_qpos = action
|
| 229 |
+
|
| 230 |
+
if self.interpolator is not None:
|
| 231 |
+
self.interpolator.set_goal(self.goal_qpos)
|
| 232 |
+
|
| 233 |
+
def run_controller(self):
|
| 234 |
+
"""
|
| 235 |
+
Calculates the torques required to reach the desired setpoint
|
| 236 |
+
|
| 237 |
+
Returns:
|
| 238 |
+
np.array: Command torques
|
| 239 |
+
"""
|
| 240 |
+
# Make sure goal has been set
|
| 241 |
+
if self.goal_qpos is None:
|
| 242 |
+
self.set_goal(np.zeros(self.control_dim))
|
| 243 |
+
|
| 244 |
+
# Update state
|
| 245 |
+
self.update()
|
| 246 |
+
|
| 247 |
+
desired_qpos = None
|
| 248 |
+
|
| 249 |
+
# Only linear interpolator is currently supported
|
| 250 |
+
if self.interpolator is not None:
|
| 251 |
+
# Linear case
|
| 252 |
+
if self.interpolator.order == 1:
|
| 253 |
+
desired_qpos = self.interpolator.get_interpolated_goal()
|
| 254 |
+
else:
|
| 255 |
+
# Nonlinear case not currently supported
|
| 256 |
+
pass
|
| 257 |
+
else:
|
| 258 |
+
desired_qpos = np.array(self.goal_qpos)
|
| 259 |
+
|
| 260 |
+
position_error = desired_qpos - self.joint_pos
|
| 261 |
+
vel_pos_error = -self.joint_vel
|
| 262 |
+
desired_torque = np.multiply(np.array(position_error), np.array(self.kp)) + np.multiply(vel_pos_error, self.kd)
|
| 263 |
+
|
| 264 |
+
# Return desired torques plus gravity compensations
|
| 265 |
+
if self.use_torque_compensation:
|
| 266 |
+
self.torques = np.dot(self.mass_matrix, desired_torque) + self.torque_compensation
|
| 267 |
+
else:
|
| 268 |
+
self.torques = desired_torque
|
| 269 |
+
|
| 270 |
+
# Always run superclass call for any cleanups at the end
|
| 271 |
+
super().run_controller()
|
| 272 |
+
return self.torques
|
| 273 |
+
|
| 274 |
+
def reset_goal(self):
|
| 275 |
+
"""
|
| 276 |
+
Resets joint position goal to be current position
|
| 277 |
+
"""
|
| 278 |
+
self.goal_qpos = self.joint_pos
|
| 279 |
+
|
| 280 |
+
# Reset interpolator if required
|
| 281 |
+
if self.interpolator is not None:
|
| 282 |
+
self.interpolator.set_goal(self.goal_qpos)
|
| 283 |
+
|
| 284 |
+
@property
|
| 285 |
+
def control_limits(self):
|
| 286 |
+
"""
|
| 287 |
+
Returns the limits over this controller's action space, overrides the superclass property
|
| 288 |
+
Returns the following (generalized for both high and low limits), based on the impedance mode:
|
| 289 |
+
|
| 290 |
+
:Mode `'fixed'`: [joint pos command]
|
| 291 |
+
:Mode `'variable'`: [damping_ratio values, kp values, joint pos command]
|
| 292 |
+
:Mode `'variable_kp'`: [kp values, joint pos command]
|
| 293 |
+
|
| 294 |
+
Returns:
|
| 295 |
+
2-tuple:
|
| 296 |
+
|
| 297 |
+
- (np.array) minimum action values
|
| 298 |
+
- (np.array) maximum action values
|
| 299 |
+
"""
|
| 300 |
+
if self.impedance_mode == "variable":
|
| 301 |
+
low = np.concatenate([self.damping_ratio_min, self.kp_min, self.input_min])
|
| 302 |
+
high = np.concatenate([self.damping_ratio_max, self.kp_max, self.input_max])
|
| 303 |
+
elif self.impedance_mode == "variable_kp":
|
| 304 |
+
low = np.concatenate([self.kp_min, self.input_min])
|
| 305 |
+
high = np.concatenate([self.kp_max, self.input_max])
|
| 306 |
+
else: # This is case "fixed"
|
| 307 |
+
low, high = self.input_min, self.input_max
|
| 308 |
+
return low, high
|
| 309 |
+
|
| 310 |
+
@property
|
| 311 |
+
def name(self):
|
| 312 |
+
return "JOINT_POSITION"
|
robosuite/controllers/parts/generic/joint_tor.py
ADDED
|
@@ -0,0 +1,181 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import numpy as np
|
| 2 |
+
|
| 3 |
+
from robosuite.controllers.parts.controller import Controller
|
| 4 |
+
|
| 5 |
+
|
| 6 |
+
class JointTorqueController(Controller):
|
| 7 |
+
"""
|
| 8 |
+
Controller for controlling the robot arm's joint torques. As the actuators at the mujoco sim level are already
|
| 9 |
+
torque actuators, this "controller" usually simply "passes through" desired torques, though it also includes the
|
| 10 |
+
typical input / output scaling and clipping, as well as interpolator features seen in other controllers classes
|
| 11 |
+
as well
|
| 12 |
+
|
| 13 |
+
NOTE: Control input actions assumed to be taken as absolute joint torques. A given action to this
|
| 14 |
+
controller is assumed to be of the form: (torq_j0, torq_j1, ... , torq_jn-1) for an n-joint robot
|
| 15 |
+
|
| 16 |
+
Args:
|
| 17 |
+
sim (MjSim): Simulator instance this controller will pull robot state updates from
|
| 18 |
+
|
| 19 |
+
eef_name (str): Name of controlled robot arm's end effector (from robot XML)
|
| 20 |
+
|
| 21 |
+
joint_indexes (dict): Each key contains sim reference indexes to relevant robot joint information, namely:
|
| 22 |
+
|
| 23 |
+
:`'joints'`: list of indexes to relevant robot joints
|
| 24 |
+
:`'qpos'`: list of indexes to relevant robot joint positions
|
| 25 |
+
:`'qvel'`: list of indexes to relevant robot joint velocities
|
| 26 |
+
|
| 27 |
+
actuator_range (2-tuple of array of float): 2-Tuple (low, high) representing the robot joint actuator range
|
| 28 |
+
|
| 29 |
+
input_max (float or list of float): Maximum above which an inputted action will be clipped. Can be either be
|
| 30 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 31 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 32 |
+
|
| 33 |
+
input_min (float or list of float): Minimum below which an inputted action will be clipped. Can be either be
|
| 34 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 35 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 36 |
+
|
| 37 |
+
output_max (float or list of float): Maximum which defines upper end of scaling range when scaling an input
|
| 38 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 39 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 40 |
+
|
| 41 |
+
output_min (float or list of float): Minimum which defines upper end of scaling range when scaling an input
|
| 42 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 43 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 44 |
+
|
| 45 |
+
policy_freq (int): Frequency at which actions from the robot policy are fed into this controller
|
| 46 |
+
|
| 47 |
+
torque_limits (2-list of float or 2-list of list of floats): Limits (N-m) below and above which the magnitude
|
| 48 |
+
of a calculated goal joint torque will be clipped. Can be either be a 2-list (same min/max value for all
|
| 49 |
+
joint dims), or a 2-list of list (specific min/max values for each dim)
|
| 50 |
+
If not specified, will automatically set the limits to the actuator limits for this robot arm
|
| 51 |
+
|
| 52 |
+
interpolator (Interpolator): Interpolator object to be used for interpolating from the current joint torques to
|
| 53 |
+
the goal joint torques during each timestep between inputted actions
|
| 54 |
+
|
| 55 |
+
**kwargs: Does nothing; placeholder to "sink" any additional arguments so that instantiating this controller
|
| 56 |
+
via an argument dict that has additional extraneous arguments won't raise an error
|
| 57 |
+
"""
|
| 58 |
+
|
| 59 |
+
def __init__(
|
| 60 |
+
self,
|
| 61 |
+
sim,
|
| 62 |
+
joint_indexes,
|
| 63 |
+
actuator_range,
|
| 64 |
+
ref_name=None,
|
| 65 |
+
input_max=1,
|
| 66 |
+
input_min=-1,
|
| 67 |
+
output_max=0.05,
|
| 68 |
+
output_min=-0.05,
|
| 69 |
+
policy_freq=20,
|
| 70 |
+
lite_physics=True,
|
| 71 |
+
torque_limits=None,
|
| 72 |
+
interpolator=None,
|
| 73 |
+
**kwargs, # does nothing; used so no error raised when dict is passed with extra terms used previously
|
| 74 |
+
):
|
| 75 |
+
|
| 76 |
+
super().__init__(
|
| 77 |
+
sim,
|
| 78 |
+
ref_name=ref_name,
|
| 79 |
+
joint_indexes=joint_indexes,
|
| 80 |
+
actuator_range=actuator_range,
|
| 81 |
+
part_name=kwargs.get("part_name", None),
|
| 82 |
+
naming_prefix=kwargs.get("naming_prefix", None),
|
| 83 |
+
lite_physics=lite_physics,
|
| 84 |
+
)
|
| 85 |
+
|
| 86 |
+
# Control dimension
|
| 87 |
+
self.control_dim = len(joint_indexes["joints"])
|
| 88 |
+
|
| 89 |
+
# input and output max and min (allow for either explicit lists or single numbers)
|
| 90 |
+
self.input_max = self.nums2array(input_max, self.control_dim)
|
| 91 |
+
self.input_min = self.nums2array(input_min, self.control_dim)
|
| 92 |
+
self.output_max = self.nums2array(output_max, self.control_dim)
|
| 93 |
+
self.output_min = self.nums2array(output_min, self.control_dim)
|
| 94 |
+
|
| 95 |
+
# limits (if not specified, set them to actuator limits by default)
|
| 96 |
+
self.torque_limits = np.array(torque_limits) if torque_limits is not None else self.actuator_limits
|
| 97 |
+
|
| 98 |
+
# control frequency
|
| 99 |
+
self.control_freq = policy_freq
|
| 100 |
+
|
| 101 |
+
# interpolator
|
| 102 |
+
self.interpolator = interpolator
|
| 103 |
+
|
| 104 |
+
# initialize torques
|
| 105 |
+
self.goal_torque = None # Goal torque desired, pre-compensation
|
| 106 |
+
self.current_torque = np.zeros(self.control_dim) # Current torques being outputted, pre-compensation
|
| 107 |
+
self.torques = None # Torques returned every time run_controller is called
|
| 108 |
+
|
| 109 |
+
self.use_torque_compensation = kwargs.get("use_torque_compensation", True)
|
| 110 |
+
|
| 111 |
+
def set_goal(self, torques):
|
| 112 |
+
"""
|
| 113 |
+
Sets goal based on input @torques.
|
| 114 |
+
|
| 115 |
+
Args:
|
| 116 |
+
torques (Iterable): Desired joint torques
|
| 117 |
+
|
| 118 |
+
Raises:
|
| 119 |
+
AssertionError: [Invalid action dimension size]
|
| 120 |
+
"""
|
| 121 |
+
# Update state
|
| 122 |
+
self.update()
|
| 123 |
+
|
| 124 |
+
# Check to make sure torques is size self.joint_dim
|
| 125 |
+
assert len(torques) == self.control_dim, "Delta torque must be equal to the robot's joint dimension space!"
|
| 126 |
+
|
| 127 |
+
self.goal_torque = np.clip(self.scale_action(torques), self.torque_limits[0], self.torque_limits[1])
|
| 128 |
+
|
| 129 |
+
if self.interpolator is not None:
|
| 130 |
+
self.interpolator.set_goal(self.goal_torque)
|
| 131 |
+
|
| 132 |
+
def run_controller(self):
|
| 133 |
+
"""
|
| 134 |
+
Calculates the torques required to reach the desired setpoint
|
| 135 |
+
|
| 136 |
+
Returns:
|
| 137 |
+
np.array: Command torques
|
| 138 |
+
"""
|
| 139 |
+
# Make sure goal has been set
|
| 140 |
+
if self.goal_torque is None:
|
| 141 |
+
self.set_goal(np.zeros(self.control_dim))
|
| 142 |
+
|
| 143 |
+
# Update state
|
| 144 |
+
self.update()
|
| 145 |
+
|
| 146 |
+
# Only linear interpolator is currently supported
|
| 147 |
+
if self.interpolator is not None:
|
| 148 |
+
# Linear case
|
| 149 |
+
if self.interpolator.order == 1:
|
| 150 |
+
self.current_torque = self.interpolator.get_interpolated_goal()
|
| 151 |
+
else:
|
| 152 |
+
# Nonlinear case not currently supported
|
| 153 |
+
pass
|
| 154 |
+
else:
|
| 155 |
+
self.current_torque = np.array(self.goal_torque)
|
| 156 |
+
|
| 157 |
+
# Add gravity compensation
|
| 158 |
+
if self.use_torque_compensation:
|
| 159 |
+
self.torques = self.current_torque + self.torque_compensation
|
| 160 |
+
else:
|
| 161 |
+
self.torques = self.current_torque
|
| 162 |
+
|
| 163 |
+
# Always run superclass call for any cleanups at the end
|
| 164 |
+
super().run_controller()
|
| 165 |
+
|
| 166 |
+
# Return final torques
|
| 167 |
+
return self.torques
|
| 168 |
+
|
| 169 |
+
def reset_goal(self):
|
| 170 |
+
"""
|
| 171 |
+
Resets joint torque goal to be all zeros (pre-compensation)
|
| 172 |
+
"""
|
| 173 |
+
self.goal_torque = np.zeros(self.control_dim)
|
| 174 |
+
|
| 175 |
+
# Reset interpolator if required
|
| 176 |
+
if self.interpolator is not None:
|
| 177 |
+
self.interpolator.set_goal(self.goal_torque)
|
| 178 |
+
|
| 179 |
+
@property
|
| 180 |
+
def name(self):
|
| 181 |
+
return "JOINT_TORQUE"
|
robosuite/controllers/parts/generic/joint_vel.py
ADDED
|
@@ -0,0 +1,223 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import numpy as np
|
| 2 |
+
|
| 3 |
+
from robosuite.controllers.parts.controller import Controller
|
| 4 |
+
from robosuite.utils.buffers import RingBuffer
|
| 5 |
+
|
| 6 |
+
|
| 7 |
+
class JointVelocityController(Controller):
|
| 8 |
+
"""
|
| 9 |
+
Controller for controlling the robot arm's joint velocities. This is simply a P controller with desired torques
|
| 10 |
+
(pre gravity compensation) taken to be proportional to the velocity error of the robot joints.
|
| 11 |
+
|
| 12 |
+
NOTE: Control input actions assumed to be taken as absolute joint velocities. A given action to this
|
| 13 |
+
controller is assumed to be of the form: (vel_j0, vel_j1, ... , vel_jn-1) for an n-joint robot
|
| 14 |
+
|
| 15 |
+
Args:
|
| 16 |
+
sim (MjSim): Simulator instance this controller will pull robot state updates from
|
| 17 |
+
|
| 18 |
+
eef_name (str): Name of controlled robot arm's end effector (from robot XML)
|
| 19 |
+
|
| 20 |
+
joint_indexes (dict): Each key contains sim reference indexes to relevant robot joint information, namely:
|
| 21 |
+
|
| 22 |
+
:`'joints'`: list of indexes to relevant robot joints
|
| 23 |
+
:`'qpos'`: list of indexes to relevant robot joint positions
|
| 24 |
+
:`'qvel'`: list of indexes to relevant robot joint velocities
|
| 25 |
+
|
| 26 |
+
actuator_range (2-tuple of array of float): 2-Tuple (low, high) representing the robot joint actuator range
|
| 27 |
+
|
| 28 |
+
input_max (float or list of float): Maximum above which an inputted action will be clipped. Can be either be
|
| 29 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 30 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 31 |
+
|
| 32 |
+
input_min (float or list of float): Minimum below which an inputted action will be clipped. Can be either be
|
| 33 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 34 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 35 |
+
|
| 36 |
+
output_max (float or list of float): Maximum which defines upper end of scaling range when scaling an input
|
| 37 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 38 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 39 |
+
|
| 40 |
+
output_min (float or list of float): Minimum which defines upper end of scaling range when scaling an input
|
| 41 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 42 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 43 |
+
|
| 44 |
+
kp (float or list of float): velocity gain for determining desired torques based upon the joint vel errors.
|
| 45 |
+
Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)
|
| 46 |
+
|
| 47 |
+
policy_freq (int): Frequency at which actions from the robot policy are fed into this controller
|
| 48 |
+
|
| 49 |
+
velocity_limits (2-list of float or 2-list of list of floats): Limits (m/s) below and above which the magnitude
|
| 50 |
+
of a calculated goal joint velocity will be clipped. Can be either be a 2-list (same min/max value for all
|
| 51 |
+
joint dims), or a 2-list of list (specific min/max values for each dim)
|
| 52 |
+
|
| 53 |
+
interpolator (Interpolator): Interpolator object to be used for interpolating from the current joint velocities
|
| 54 |
+
to the goal joint velocities during each timestep between inputted actions
|
| 55 |
+
|
| 56 |
+
**kwargs: Does nothing; placeholder to "sink" any additional arguments so that instantiating this controller
|
| 57 |
+
via an argument dict that has additional extraneous arguments won't raise an error
|
| 58 |
+
"""
|
| 59 |
+
|
| 60 |
+
def __init__(
|
| 61 |
+
self,
|
| 62 |
+
sim,
|
| 63 |
+
joint_indexes,
|
| 64 |
+
actuator_range,
|
| 65 |
+
ref_name=None,
|
| 66 |
+
input_max=1,
|
| 67 |
+
input_min=-1,
|
| 68 |
+
output_max=1,
|
| 69 |
+
output_min=-1,
|
| 70 |
+
kp=0.25,
|
| 71 |
+
policy_freq=20,
|
| 72 |
+
lite_physics=True,
|
| 73 |
+
velocity_limits=None,
|
| 74 |
+
interpolator=None,
|
| 75 |
+
**kwargs, # does nothing; used so no error raised when dict is passed with extra terms used previously
|
| 76 |
+
):
|
| 77 |
+
|
| 78 |
+
super().__init__(
|
| 79 |
+
sim,
|
| 80 |
+
ref_name=ref_name,
|
| 81 |
+
joint_indexes=joint_indexes,
|
| 82 |
+
actuator_range=actuator_range,
|
| 83 |
+
part_name=kwargs.get("part_name", None),
|
| 84 |
+
naming_prefix=kwargs.get("naming_prefix", None),
|
| 85 |
+
lite_physics=lite_physics,
|
| 86 |
+
)
|
| 87 |
+
# Control dimension
|
| 88 |
+
self.control_dim = len(joint_indexes["joints"])
|
| 89 |
+
|
| 90 |
+
# input and output max and min (allow for either explicit lists or single numbers)
|
| 91 |
+
self.input_max = self.nums2array(input_max, self.joint_dim)
|
| 92 |
+
self.input_min = self.nums2array(input_min, self.joint_dim)
|
| 93 |
+
self.output_max = self.nums2array(output_max, self.joint_dim)
|
| 94 |
+
self.output_min = self.nums2array(output_min, self.joint_dim)
|
| 95 |
+
|
| 96 |
+
# gains and corresopnding vars
|
| 97 |
+
self.kp = self.nums2array(kp, self.joint_dim)
|
| 98 |
+
# if kp is a single value, map wrist gains accordingly (scale down x10 for final two joints)
|
| 99 |
+
|
| 100 |
+
if type(kp) is float or type(kp) is int:
|
| 101 |
+
# Scale kpp according to how wide the actuator range is for this robot
|
| 102 |
+
low, high = self.actuator_limits
|
| 103 |
+
self.kp = kp * (high - low)
|
| 104 |
+
|
| 105 |
+
self.ki = self.kp * 0.005
|
| 106 |
+
self.kd = self.kp * 0.001
|
| 107 |
+
self.last_err = np.zeros(self.joint_dim)
|
| 108 |
+
self.derr_buf = RingBuffer(dim=self.joint_dim, length=5)
|
| 109 |
+
self.summed_err = np.zeros(self.joint_dim)
|
| 110 |
+
self.saturated = False
|
| 111 |
+
self.last_joint_vel = np.zeros(self.joint_dim)
|
| 112 |
+
|
| 113 |
+
# limits
|
| 114 |
+
self.velocity_limits = np.array(velocity_limits) if velocity_limits is not None else None
|
| 115 |
+
|
| 116 |
+
# control frequency
|
| 117 |
+
self.control_freq = policy_freq
|
| 118 |
+
|
| 119 |
+
# interpolator
|
| 120 |
+
self.interpolator = interpolator
|
| 121 |
+
|
| 122 |
+
# initialize torques and goal velocity
|
| 123 |
+
self.goal_vel = None # Goal velocity desired, pre-compensation
|
| 124 |
+
self.current_vel = np.zeros(self.joint_dim) # Current velocity setpoint, pre-compensation
|
| 125 |
+
self.torques = None # Torques returned every time run_controller is called
|
| 126 |
+
|
| 127 |
+
self.torque_compensation = kwargs.get("use_torque_compensation", True)
|
| 128 |
+
|
| 129 |
+
def set_goal(self, velocities):
|
| 130 |
+
"""
|
| 131 |
+
Sets goal based on input @velocities.
|
| 132 |
+
|
| 133 |
+
Args:
|
| 134 |
+
velocities (Iterable): Desired joint velocities
|
| 135 |
+
|
| 136 |
+
Raises:
|
| 137 |
+
AssertionError: [Invalid action dimension size]
|
| 138 |
+
"""
|
| 139 |
+
# Update state
|
| 140 |
+
self.update()
|
| 141 |
+
|
| 142 |
+
# Otherwise, check to make sure velocities is size self.joint_dim
|
| 143 |
+
assert (
|
| 144 |
+
len(velocities) == self.joint_dim
|
| 145 |
+
), "Goal action must be equal to the robot's joint dimension space! Expected {}, got {}".format(
|
| 146 |
+
self.joint_dim, len(velocities)
|
| 147 |
+
)
|
| 148 |
+
|
| 149 |
+
self.goal_vel = self.scale_action(velocities)
|
| 150 |
+
if self.velocity_limits is not None:
|
| 151 |
+
self.goal_vel = np.clip(self.goal_vel, self.velocity_limits[0], self.velocity_limits[1])
|
| 152 |
+
|
| 153 |
+
if self.interpolator is not None:
|
| 154 |
+
self.interpolator.set_goal(self.goal_vel)
|
| 155 |
+
|
| 156 |
+
def run_controller(self):
|
| 157 |
+
"""
|
| 158 |
+
Calculates the torques required to reach the desired setpoint
|
| 159 |
+
|
| 160 |
+
Returns:
|
| 161 |
+
np.array: Command torques
|
| 162 |
+
"""
|
| 163 |
+
# Make sure goal has been set
|
| 164 |
+
if self.goal_vel is None:
|
| 165 |
+
self.set_goal(np.zeros(self.joint_dim))
|
| 166 |
+
|
| 167 |
+
# Update state
|
| 168 |
+
self.update()
|
| 169 |
+
|
| 170 |
+
# Only linear interpolator is currently supported
|
| 171 |
+
if self.interpolator is not None:
|
| 172 |
+
if self.interpolator.order == 1:
|
| 173 |
+
# Linear case
|
| 174 |
+
self.current_vel = self.interpolator.get_interpolated_goal()
|
| 175 |
+
else:
|
| 176 |
+
# Nonlinear case not currently supported
|
| 177 |
+
pass
|
| 178 |
+
else:
|
| 179 |
+
self.current_vel = np.array(self.goal_vel)
|
| 180 |
+
|
| 181 |
+
# Compute necessary error terms for PID velocity controller
|
| 182 |
+
err = self.current_vel - self.joint_vel
|
| 183 |
+
derr = err - self.last_err
|
| 184 |
+
self.last_err = err
|
| 185 |
+
self.derr_buf.push(derr)
|
| 186 |
+
|
| 187 |
+
# Only add to I component if we're not saturated (anti-windup)
|
| 188 |
+
if not self.saturated:
|
| 189 |
+
self.summed_err += err
|
| 190 |
+
|
| 191 |
+
# Compute command torques via PID velocity controller plus gravity compensation torques
|
| 192 |
+
if self.torque_compensation:
|
| 193 |
+
torques = (
|
| 194 |
+
self.kp * err + self.ki * self.summed_err + self.kd * self.derr_buf.average + self.torque_compensation
|
| 195 |
+
)
|
| 196 |
+
else:
|
| 197 |
+
torques = self.kp * err + self.ki * self.summed_err + self.kd * self.derr_buf.average
|
| 198 |
+
|
| 199 |
+
# Clip torques
|
| 200 |
+
self.torques = self.clip_torques(torques)
|
| 201 |
+
|
| 202 |
+
# Check if we're saturated
|
| 203 |
+
self.saturated = False if np.sum(np.abs(self.torques - torques)) == 0 else True
|
| 204 |
+
|
| 205 |
+
# Always run superclass call for any cleanups at the end
|
| 206 |
+
super().run_controller()
|
| 207 |
+
|
| 208 |
+
# Return final torques
|
| 209 |
+
return self.torques
|
| 210 |
+
|
| 211 |
+
def reset_goal(self):
|
| 212 |
+
"""
|
| 213 |
+
Resets joint velocity goal to be all zeros
|
| 214 |
+
"""
|
| 215 |
+
self.goal_vel = np.zeros(self.joint_dim)
|
| 216 |
+
|
| 217 |
+
# Reset interpolator if required
|
| 218 |
+
if self.interpolator is not None:
|
| 219 |
+
self.interpolator.set_goal(self.goal_vel)
|
| 220 |
+
|
| 221 |
+
@property
|
| 222 |
+
def name(self):
|
| 223 |
+
return "JOINT_VELOCITY"
|
robosuite/controllers/parts/gripper/__init__.py
ADDED
|
@@ -0,0 +1 @@
|
|
|
|
|
|
|
| 1 |
+
from .simple_grip import SimpleGripController
|
robosuite/controllers/parts/gripper/gripper_controller.py
ADDED
|
@@ -0,0 +1,234 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import abc
|
| 2 |
+
from collections.abc import Iterable
|
| 3 |
+
|
| 4 |
+
import mujoco
|
| 5 |
+
import numpy as np
|
| 6 |
+
|
| 7 |
+
import robosuite.macros as macros
|
| 8 |
+
|
| 9 |
+
|
| 10 |
+
class GripperController(object, metaclass=abc.ABCMeta):
|
| 11 |
+
"""
|
| 12 |
+
General controller interface.
|
| 13 |
+
|
| 14 |
+
Requires reference to mujoco sim object, relevant joint_indexes to that robot, and
|
| 15 |
+
whether an initial_joint is used for nullspace torques or not
|
| 16 |
+
|
| 17 |
+
Args:
|
| 18 |
+
sim (MjSim): Simulator instance this controller will pull robot state updates from
|
| 19 |
+
|
| 20 |
+
eef_name (str): Name of controlled robot arm's end effector (from robot XML)
|
| 21 |
+
|
| 22 |
+
joint_indexes (dict): Each key contains sim reference indexes to relevant robot joint information, namely:
|
| 23 |
+
|
| 24 |
+
:`'joints'`: list of indexes to relevant robot joints
|
| 25 |
+
:`'qpos'`: list of indexes to relevant robot joint positions
|
| 26 |
+
:`'qvel'`: list of indexes to relevant robot joint velocities
|
| 27 |
+
|
| 28 |
+
actuator_range (2-tuple of array of float): 2-Tuple (low, high) representing the robot joint actuator range
|
| 29 |
+
"""
|
| 30 |
+
|
| 31 |
+
def __init__(
|
| 32 |
+
self,
|
| 33 |
+
sim,
|
| 34 |
+
joint_indexes,
|
| 35 |
+
actuator_range,
|
| 36 |
+
part_name=None,
|
| 37 |
+
naming_prefix=None,
|
| 38 |
+
):
|
| 39 |
+
|
| 40 |
+
# Actuator range
|
| 41 |
+
self.actuator_min = actuator_range[0]
|
| 42 |
+
self.actuator_max = actuator_range[1]
|
| 43 |
+
|
| 44 |
+
# Attributes for scaling / clipping inputs to outputs
|
| 45 |
+
self.action_scale = None
|
| 46 |
+
self.action_input_transform = None
|
| 47 |
+
self.action_output_transform = None
|
| 48 |
+
|
| 49 |
+
# Private property attributes
|
| 50 |
+
self.control_dim = None
|
| 51 |
+
self.output_min = None
|
| 52 |
+
self.output_max = None
|
| 53 |
+
self.input_min = None
|
| 54 |
+
self.input_max = None
|
| 55 |
+
|
| 56 |
+
# mujoco simulator state
|
| 57 |
+
self.sim = sim
|
| 58 |
+
self.model_timestep = macros.SIMULATION_TIMESTEP
|
| 59 |
+
self.part_name = part_name
|
| 60 |
+
self.naming_prefix = naming_prefix
|
| 61 |
+
|
| 62 |
+
self.joint_index = joint_indexes["joints"]
|
| 63 |
+
self.actuator_index = joint_indexes["actuators"]
|
| 64 |
+
self.qpos_index = joint_indexes["qpos"]
|
| 65 |
+
self.qvel_index = joint_indexes["qvel"]
|
| 66 |
+
|
| 67 |
+
# robot states
|
| 68 |
+
self.joint_pos = None
|
| 69 |
+
self.joint_vel = None
|
| 70 |
+
|
| 71 |
+
# Joint dimension
|
| 72 |
+
self.joint_dim = len(joint_indexes["joints"])
|
| 73 |
+
|
| 74 |
+
# Torques being outputted by the controller
|
| 75 |
+
self.torques = None
|
| 76 |
+
|
| 77 |
+
# Update flag to prevent redundant update calls
|
| 78 |
+
self.new_update = True
|
| 79 |
+
|
| 80 |
+
# Move forward one timestep to propagate updates before taking first update
|
| 81 |
+
self.sim.forward()
|
| 82 |
+
|
| 83 |
+
# Initialize controller by updating internal state and setting the initial joint, pos, and ori
|
| 84 |
+
self.update()
|
| 85 |
+
self.initial_joint = self.joint_pos
|
| 86 |
+
self.previous_qpos = None
|
| 87 |
+
|
| 88 |
+
@abc.abstractmethod
|
| 89 |
+
def run_controller(self):
|
| 90 |
+
"""
|
| 91 |
+
Abstract method that should be implemented in all subclass controllers, and should convert a given action
|
| 92 |
+
into torques (pre gravity compensation) to be executed on the robot.
|
| 93 |
+
Additionally, resets the self.new_update flag so that the next self.update call will occur
|
| 94 |
+
"""
|
| 95 |
+
self.new_update = True
|
| 96 |
+
|
| 97 |
+
def scale_action(self, action):
|
| 98 |
+
"""
|
| 99 |
+
Clips @action to be within self.input_min and self.input_max, and then re-scale the values to be within
|
| 100 |
+
the range self.output_min and self.output_max
|
| 101 |
+
|
| 102 |
+
Args:
|
| 103 |
+
action (Iterable): Actions to scale
|
| 104 |
+
|
| 105 |
+
Returns:
|
| 106 |
+
np.array: Re-scaled action
|
| 107 |
+
"""
|
| 108 |
+
|
| 109 |
+
if self.action_scale is None:
|
| 110 |
+
self.action_scale = abs(self.output_max - self.output_min) / abs(self.input_max - self.input_min)
|
| 111 |
+
self.action_output_transform = (self.output_max + self.output_min) / 2.0
|
| 112 |
+
self.action_input_transform = (self.input_max + self.input_min) / 2.0
|
| 113 |
+
action = np.clip(action, self.input_min, self.input_max)
|
| 114 |
+
transformed_action = (action - self.action_input_transform) * self.action_scale + self.action_output_transform
|
| 115 |
+
|
| 116 |
+
return transformed_action
|
| 117 |
+
|
| 118 |
+
def update(self, force=False):
|
| 119 |
+
"""
|
| 120 |
+
Updates the state of the robot arm, including end effector pose / orientation / velocity, joint pos/vel,
|
| 121 |
+
jacobian, and mass matrix. By default, since this is a non-negligible computation, multiple redundant calls
|
| 122 |
+
will be ignored via the self.new_update attribute flag. However, if the @force flag is set, the update will
|
| 123 |
+
occur regardless of that state of self.new_update. This base class method of @run_controller resets the
|
| 124 |
+
self.new_update flag
|
| 125 |
+
|
| 126 |
+
Args:
|
| 127 |
+
force (bool): Whether to force an update to occur or not
|
| 128 |
+
"""
|
| 129 |
+
|
| 130 |
+
# Only run update if self.new_update or force flag is set
|
| 131 |
+
if self.new_update or force:
|
| 132 |
+
|
| 133 |
+
self.joint_pos = np.array(self.sim.data.qpos[self.qpos_index])
|
| 134 |
+
self.joint_vel = np.array(self.sim.data.qvel[self.qvel_index])
|
| 135 |
+
# Clear self.new_update
|
| 136 |
+
self.new_update = False
|
| 137 |
+
|
| 138 |
+
def update_initial_joints(self, initial_joints):
|
| 139 |
+
"""
|
| 140 |
+
Updates the internal attribute self.initial_joints. This is useful for updating changes in controller-specific
|
| 141 |
+
behavior, such as with OSC where self.initial_joints is used for determine nullspace actions
|
| 142 |
+
|
| 143 |
+
This function can also be extended by subclassed controllers for additional controller-specific updates
|
| 144 |
+
|
| 145 |
+
Args:
|
| 146 |
+
initial_joints (Iterable): Array of joint position values to update the initial joints
|
| 147 |
+
"""
|
| 148 |
+
self.initial_joint = np.array(initial_joints)
|
| 149 |
+
self.update(force=True)
|
| 150 |
+
|
| 151 |
+
def clip_torques(self, torques):
|
| 152 |
+
"""
|
| 153 |
+
Clips the torques to be within the actuator limits
|
| 154 |
+
|
| 155 |
+
Args:
|
| 156 |
+
torques (Iterable): Torques to clip
|
| 157 |
+
|
| 158 |
+
Returns:
|
| 159 |
+
np.array: Clipped torques
|
| 160 |
+
"""
|
| 161 |
+
return np.clip(torques, self.actuator_min, self.actuator_max)
|
| 162 |
+
|
| 163 |
+
def reset_goal(self):
|
| 164 |
+
"""
|
| 165 |
+
Resets the goal -- usually by setting to the goal to all zeros, but in some cases may be different (e.g.: OSC)
|
| 166 |
+
"""
|
| 167 |
+
raise NotImplementedError
|
| 168 |
+
|
| 169 |
+
@staticmethod
|
| 170 |
+
def nums2array(nums, dim):
|
| 171 |
+
"""
|
| 172 |
+
Convert input @nums into numpy array of length @dim. If @nums is a single number, broadcasts it to the
|
| 173 |
+
corresponding dimension size @dim before converting into a numpy array
|
| 174 |
+
|
| 175 |
+
Args:
|
| 176 |
+
nums (numeric or Iterable): Either single value or array of numbers
|
| 177 |
+
dim (int): Size of array to broadcast input to env.sim.data.actuator_force
|
| 178 |
+
|
| 179 |
+
Returns:
|
| 180 |
+
np.array: Array filled with values specified in @nums
|
| 181 |
+
"""
|
| 182 |
+
# First run sanity check to make sure no strings are being inputted
|
| 183 |
+
if isinstance(nums, str):
|
| 184 |
+
raise TypeError("Error: Only numeric inputs are supported for this function, nums2array!")
|
| 185 |
+
|
| 186 |
+
# Check if input is an Iterable, if so, we simply convert the input to np.array and return
|
| 187 |
+
# Else, input is a single value, so we map to a numpy array of correct size and return
|
| 188 |
+
return np.array(nums) if isinstance(nums, Iterable) else np.ones(dim) * nums
|
| 189 |
+
|
| 190 |
+
@property
|
| 191 |
+
def torque_compensation(self):
|
| 192 |
+
"""
|
| 193 |
+
Gravity compensation for this robot arm
|
| 194 |
+
|
| 195 |
+
Returns:
|
| 196 |
+
np.array: torques
|
| 197 |
+
"""
|
| 198 |
+
return self.sim.data.qfrc_bias[self.qvel_index]
|
| 199 |
+
|
| 200 |
+
@property
|
| 201 |
+
def actuator_limits(self):
|
| 202 |
+
"""
|
| 203 |
+
Torque limits for this controller
|
| 204 |
+
|
| 205 |
+
Returns:
|
| 206 |
+
2-tuple:
|
| 207 |
+
|
| 208 |
+
- (np.array) minimum actuator torques
|
| 209 |
+
- (np.array) maximum actuator torques
|
| 210 |
+
"""
|
| 211 |
+
return self.actuator_min, self.actuator_max
|
| 212 |
+
|
| 213 |
+
@property
|
| 214 |
+
def control_limits(self):
|
| 215 |
+
"""
|
| 216 |
+
Limits over this controller's action space, which defaults to input min/max
|
| 217 |
+
|
| 218 |
+
Returns:
|
| 219 |
+
2-tuple:
|
| 220 |
+
|
| 221 |
+
- (np.array) minimum action values
|
| 222 |
+
- (np.array) maximum action values
|
| 223 |
+
"""
|
| 224 |
+
return self.input_min, self.input_max
|
| 225 |
+
|
| 226 |
+
@property
|
| 227 |
+
def name(self):
|
| 228 |
+
"""
|
| 229 |
+
Name of this controller
|
| 230 |
+
|
| 231 |
+
Returns:
|
| 232 |
+
str: controller name
|
| 233 |
+
"""
|
| 234 |
+
raise NotImplementedError
|
robosuite/controllers/parts/gripper/simple_grip.py
ADDED
|
@@ -0,0 +1,213 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
"""This is a controller that controls the fingers / grippers to do naive gripping. No matter how many fingers the gripper has, they all move in the same direction."""
|
| 2 |
+
|
| 3 |
+
import numpy as np
|
| 4 |
+
|
| 5 |
+
from robosuite.controllers.parts.gripper.gripper_controller import GripperController
|
| 6 |
+
from robosuite.utils.control_utils import *
|
| 7 |
+
|
| 8 |
+
# Supported impedance modes
|
| 9 |
+
|
| 10 |
+
|
| 11 |
+
class SimpleGripController(GripperController):
|
| 12 |
+
"""
|
| 13 |
+
Controller for controlling robot arm via impedance control. Allows position control of the robot's joints.
|
| 14 |
+
|
| 15 |
+
NOTE: Control input actions assumed to be taken relative to the current joint positions. A given action to this
|
| 16 |
+
controller is assumed to be of the form: (dpos_j0, dpos_j1, ... , dpos_jn-1) for an n-joint robot
|
| 17 |
+
|
| 18 |
+
Args:
|
| 19 |
+
sim (MjSim): Simulator instance this controller will pull robot state updates from
|
| 20 |
+
|
| 21 |
+
eef_name (str): Name of controlled robot arm's end effector (from robot XML)
|
| 22 |
+
|
| 23 |
+
joint_indexes (dict): Each key contains sim reference indexes to relevant robot joint information, namely:
|
| 24 |
+
|
| 25 |
+
:`'joints'`: list of indexes to relevant robot joints
|
| 26 |
+
:`'qpos'`: list of indexes to relevant robot joint positions
|
| 27 |
+
:`'qvel'`: list of indexes to relevant robot joint velocities
|
| 28 |
+
|
| 29 |
+
actuator_range (2-tuple of array of float): 2-Tuple (low, high) representing the robot joint actuator range
|
| 30 |
+
|
| 31 |
+
input_max (float or Iterable of float): Maximum above which an inputted action will be clipped. Can be either be
|
| 32 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 33 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 34 |
+
|
| 35 |
+
input_min (float or Iterable of float): Minimum below which an inputted action will be clipped. Can be either be
|
| 36 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 37 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 38 |
+
|
| 39 |
+
output_max (float or Iterable of float): Maximum which defines upper end of scaling range when scaling an input
|
| 40 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 41 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 42 |
+
|
| 43 |
+
output_min (float or Iterable of float): Minimum which defines upper end of scaling range when scaling an input
|
| 44 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 45 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 46 |
+
|
| 47 |
+
policy_freq (int): Frequency at which actions from the robot policy are fed into this controller
|
| 48 |
+
|
| 49 |
+
qpos_limits (2-list of float or 2-list of Iterable of floats): Limits (rad) below and above which the magnitude
|
| 50 |
+
of a calculated goal joint position will be clipped. Can be either be a 2-list (same min/max value for all
|
| 51 |
+
joint dims), or a 2-list of list (specific min/max values for each dim)
|
| 52 |
+
|
| 53 |
+
interpolator (Interpolator): Interpolator object to be used for interpolating from the current joint position to
|
| 54 |
+
the goal joint position during each timestep between inputted actions
|
| 55 |
+
|
| 56 |
+
**kwargs: Does nothing; placeholder to "sink" any additional arguments so that instantiating this controller
|
| 57 |
+
via an argument dict that has additional extraneous arguments won't raise an error
|
| 58 |
+
|
| 59 |
+
Raises:
|
| 60 |
+
AssertionError: [Invalid impedance mode]
|
| 61 |
+
"""
|
| 62 |
+
|
| 63 |
+
def __init__(
|
| 64 |
+
self,
|
| 65 |
+
sim,
|
| 66 |
+
joint_indexes,
|
| 67 |
+
actuator_range,
|
| 68 |
+
input_max=1,
|
| 69 |
+
input_min=-1,
|
| 70 |
+
output_max=1,
|
| 71 |
+
output_min=-1,
|
| 72 |
+
policy_freq=20,
|
| 73 |
+
qpos_limits=None,
|
| 74 |
+
interpolator=None,
|
| 75 |
+
use_action_scaling=True,
|
| 76 |
+
**kwargs, # does nothing; used so no error raised when dict is passed with extra terms used previously
|
| 77 |
+
):
|
| 78 |
+
super().__init__(
|
| 79 |
+
sim,
|
| 80 |
+
joint_indexes,
|
| 81 |
+
actuator_range,
|
| 82 |
+
part_name=kwargs.get("part_name", None),
|
| 83 |
+
naming_prefix=kwargs.get("naming_prefix", None),
|
| 84 |
+
)
|
| 85 |
+
|
| 86 |
+
# Control dimension
|
| 87 |
+
self.control_dim = len(joint_indexes["actuators"])
|
| 88 |
+
|
| 89 |
+
# input and output max and min (allow for either explicit lists or single numbers)
|
| 90 |
+
self.input_max = self.nums2array(input_max, self.control_dim)
|
| 91 |
+
self.input_min = self.nums2array(input_min, self.control_dim)
|
| 92 |
+
self.output_max = self.nums2array(output_max, self.control_dim)
|
| 93 |
+
self.output_min = self.nums2array(output_min, self.control_dim)
|
| 94 |
+
|
| 95 |
+
# limits
|
| 96 |
+
self.position_limits = np.array(qpos_limits) if qpos_limits is not None else qpos_limits
|
| 97 |
+
|
| 98 |
+
# control frequency
|
| 99 |
+
self.control_freq = policy_freq
|
| 100 |
+
|
| 101 |
+
# interpolator
|
| 102 |
+
self.interpolator = interpolator
|
| 103 |
+
|
| 104 |
+
# action scaling
|
| 105 |
+
self.use_action_scaling = use_action_scaling
|
| 106 |
+
|
| 107 |
+
# initialize
|
| 108 |
+
self.goal_qvel = None
|
| 109 |
+
|
| 110 |
+
def set_goal(self, action, set_qpos=None):
|
| 111 |
+
"""
|
| 112 |
+
Sets goal based on input @action. If self.impedance_mode is not "fixed", then the input will be parsed into the
|
| 113 |
+
delta values to update the goal position / pose and the kp and/or damping_ratio values to be immediately updated
|
| 114 |
+
internally before executing the proceeding control loop.
|
| 115 |
+
|
| 116 |
+
Note that @action expected to be in the following format, based on impedance mode!
|
| 117 |
+
|
| 118 |
+
:Mode `'fixed'`: [joint pos command]
|
| 119 |
+
:Mode `'variable'`: [damping_ratio values, kp values, joint pos command]
|
| 120 |
+
:Mode `'variable_kp'`: [kp values, joint pos command]
|
| 121 |
+
|
| 122 |
+
Args:
|
| 123 |
+
action (Iterable): Desired relative joint position goal state
|
| 124 |
+
set_qpos (Iterable): If set, overrides @action and sets the desired absolute joint position goal state
|
| 125 |
+
|
| 126 |
+
Raises:
|
| 127 |
+
AssertionError: [Invalid action dimension size]
|
| 128 |
+
"""
|
| 129 |
+
# Update state
|
| 130 |
+
self.update()
|
| 131 |
+
|
| 132 |
+
# Parse action based on the impedance mode, and update kp / kd as necessary
|
| 133 |
+
delta = action
|
| 134 |
+
|
| 135 |
+
# Check to make sure delta is size self.joint_dim
|
| 136 |
+
assert len(delta) == self.control_dim, (
|
| 137 |
+
f"Delta qpos must be equal to the control dimension of the robot!"
|
| 138 |
+
f"Expected {self.control_dim}, got {len(delta)}"
|
| 139 |
+
)
|
| 140 |
+
|
| 141 |
+
scaled_delta = delta
|
| 142 |
+
if self.use_action_scaling:
|
| 143 |
+
scaled_delta = self.scale_action(delta)
|
| 144 |
+
|
| 145 |
+
self.goal_qvel = scaled_delta
|
| 146 |
+
|
| 147 |
+
if self.interpolator is not None:
|
| 148 |
+
self.interpolator.set_goal(self.goal_qvel)
|
| 149 |
+
|
| 150 |
+
def run_controller(self):
|
| 151 |
+
"""
|
| 152 |
+
Calculates the torques required to reach the desired setpoint
|
| 153 |
+
|
| 154 |
+
Returns:
|
| 155 |
+
np.array: Command torques
|
| 156 |
+
"""
|
| 157 |
+
# Make sure goal has been set
|
| 158 |
+
if self.goal_qvel is None:
|
| 159 |
+
self.set_goal(np.zeros(self.control_dim))
|
| 160 |
+
|
| 161 |
+
# Update state
|
| 162 |
+
self.update()
|
| 163 |
+
|
| 164 |
+
desired_qvel = None
|
| 165 |
+
|
| 166 |
+
# Only linear interpolator is currently supported
|
| 167 |
+
if self.interpolator is not None:
|
| 168 |
+
# Linear case
|
| 169 |
+
if self.interpolator.order == 1:
|
| 170 |
+
desired_qvel = self.interpolator.get_interpolated_goal()
|
| 171 |
+
else:
|
| 172 |
+
# Nonlinear case not currently supported
|
| 173 |
+
pass
|
| 174 |
+
else:
|
| 175 |
+
desired_qvel = np.array(self.goal_qvel)
|
| 176 |
+
|
| 177 |
+
self.vels = desired_qvel
|
| 178 |
+
if self.use_action_scaling:
|
| 179 |
+
ctrl_range = np.stack([self.actuator_min, self.actuator_max], axis=-1)
|
| 180 |
+
bias = 0.5 * (ctrl_range[:, 1] + ctrl_range[:, 0])
|
| 181 |
+
weight = 0.5 * (ctrl_range[:, 1] - ctrl_range[:, 0])
|
| 182 |
+
self.vels = bias + weight * desired_qvel
|
| 183 |
+
|
| 184 |
+
# Always run superclass call for any cleanups at the end
|
| 185 |
+
super().run_controller()
|
| 186 |
+
return self.vels
|
| 187 |
+
|
| 188 |
+
def reset_goal(self):
|
| 189 |
+
"""
|
| 190 |
+
Resets joint position goal to be current position
|
| 191 |
+
"""
|
| 192 |
+
self.goal_qvel = self.joint_vel
|
| 193 |
+
|
| 194 |
+
# Reset interpolator if required
|
| 195 |
+
if self.interpolator is not None:
|
| 196 |
+
self.interpolator.set_goal(self.goal_qvel)
|
| 197 |
+
|
| 198 |
+
@property
|
| 199 |
+
def control_limits(self):
|
| 200 |
+
"""
|
| 201 |
+
Returns the limits over this controller's action space, overrides the superclass property
|
| 202 |
+
Returns the following (generalized for both high and low limits), based on the impedance mode:
|
| 203 |
+
Returns:
|
| 204 |
+
2-tuple:
|
| 205 |
+
|
| 206 |
+
- (np.array) minimum action values
|
| 207 |
+
- (np.array) maximum action values
|
| 208 |
+
"""
|
| 209 |
+
return self.input_min, self.input_max
|
| 210 |
+
|
| 211 |
+
@property
|
| 212 |
+
def name(self):
|
| 213 |
+
return "JOINT_VELOCITY"
|
robosuite/controllers/parts/mobile_base/__init__.py
ADDED
|
@@ -0,0 +1 @@
|
|
|
|
|
|
|
| 1 |
+
from .joint_vel import MobileBaseJointVelocityController, LegacyMobileBaseJointVelocityController
|
robosuite/controllers/parts/mobile_base/joint_vel.py
ADDED
|
@@ -0,0 +1,383 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import numpy as np
|
| 2 |
+
|
| 3 |
+
import robosuite.utils.transform_utils as T
|
| 4 |
+
from robosuite.controllers.parts.mobile_base.mobile_base_controller import MobileBaseController
|
| 5 |
+
from robosuite.utils.control_utils import *
|
| 6 |
+
|
| 7 |
+
# Supported impedance modes
|
| 8 |
+
IMPEDANCE_MODES = {"fixed", "variable", "variable_kp"}
|
| 9 |
+
|
| 10 |
+
|
| 11 |
+
class MobileBaseJointVelocityController(MobileBaseController):
|
| 12 |
+
"""
|
| 13 |
+
Controller for controlling robot arm via impedance control. Allows position control of the robot's joints.
|
| 14 |
+
|
| 15 |
+
NOTE: Control input actions assumed to be taken relative to the current joint positions. A given action to this
|
| 16 |
+
controller is assumed to be of the form: (dpos_j0, dpos_j1, ... , dpos_jn-1) for an n-joint robot
|
| 17 |
+
|
| 18 |
+
Args:
|
| 19 |
+
sim (MjSim): Simulator instance this controller will pull robot state updates from
|
| 20 |
+
|
| 21 |
+
joint_indexes (dict): Each key contains sim reference indexes to relevant robot joint information, namely:
|
| 22 |
+
|
| 23 |
+
:`'joints'`: list of indexes to relevant robot joints
|
| 24 |
+
:`'qpos'`: list of indexes to relevant robot joint positions
|
| 25 |
+
:`'qvel'`: list of indexes to relevant robot joint velocities
|
| 26 |
+
|
| 27 |
+
actuator_range (2-tuple of array of float): 2-Tuple (low, high) representing the robot joint actuator range
|
| 28 |
+
|
| 29 |
+
input_max (float or Iterable of float): Maximum above which an inputted action will be clipped. Can be either be
|
| 30 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 31 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 32 |
+
|
| 33 |
+
input_min (float or Iterable of float): Minimum below which an inputted action will be clipped. Can be either be
|
| 34 |
+
a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the
|
| 35 |
+
latter, dimension should be the same as the control dimension for this controller
|
| 36 |
+
|
| 37 |
+
output_max (float or Iterable of float): Maximum which defines upper end of scaling range when scaling an input
|
| 38 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 39 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 40 |
+
|
| 41 |
+
output_min (float or Iterable of float): Minimum which defines upper end of scaling range when scaling an input
|
| 42 |
+
action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for
|
| 43 |
+
each dimension). If the latter, dimension should be the same as the control dimension for this controller
|
| 44 |
+
|
| 45 |
+
kp (float or Iterable of float): positional gain for determining desired torques based upon the joint pos error.
|
| 46 |
+
Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)
|
| 47 |
+
|
| 48 |
+
damping_ratio (float or Iterable of float): used in conjunction with kp to determine the velocity gain for
|
| 49 |
+
determining desired torques based upon the joint pos errors. Can be either be a scalar (same value for all
|
| 50 |
+
action dims), or a list (specific values for each dim)
|
| 51 |
+
|
| 52 |
+
impedance_mode (str): Impedance mode with which to run this controller. Options are {"fixed", "variable",
|
| 53 |
+
"variable_kp"}. If "fixed", the controller will have fixed kp and damping_ratio values as specified by the
|
| 54 |
+
@kp and @damping_ratio arguments. If "variable", both kp and damping_ratio will now be part of the
|
| 55 |
+
controller action space, resulting in a total action space of num_joints * 3. If "variable_kp", only kp
|
| 56 |
+
will become variable, with damping_ratio fixed at 1 (critically damped). The resulting action space will
|
| 57 |
+
then be num_joints * 2.
|
| 58 |
+
|
| 59 |
+
kp_limits (2-list of float or 2-list of Iterable of floats): Only applicable if @impedance_mode is set to either
|
| 60 |
+
"variable" or "variable_kp". This sets the corresponding min / max ranges of the controller action space
|
| 61 |
+
for the varying kp values. Can be either be a 2-list (same min / max for all kp action dims), or a 2-list
|
| 62 |
+
of list (specific min / max for each kp dim)
|
| 63 |
+
|
| 64 |
+
damping_ratio_limits (2-list of float or 2-list of Iterable of floats): Only applicable if @impedance_mode is
|
| 65 |
+
set to "variable". This sets the corresponding min / max ranges of the controller action space for the
|
| 66 |
+
varying damping_ratio values. Can be either be a 2-list (same min / max for all damping_ratio action dims),
|
| 67 |
+
or a 2-list of list (specific min / max for each damping_ratio dim)
|
| 68 |
+
|
| 69 |
+
policy_freq (int): Frequency at which actions from the robot policy are fed into this controller
|
| 70 |
+
|
| 71 |
+
qpos_limits (2-list of float or 2-list of Iterable of floats): Limits (rad) below and above which the magnitude
|
| 72 |
+
of a calculated goal joint position will be clipped. Can be either be a 2-list (same min/max value for all
|
| 73 |
+
joint dims), or a 2-list of list (specific min/max values for each dim)
|
| 74 |
+
|
| 75 |
+
interpolator (Interpolator): Interpolator object to be used for interpolating from the current joint position to
|
| 76 |
+
the goal joint position during each timestep between inputted actions
|
| 77 |
+
|
| 78 |
+
**kwargs: Does nothing; placeholder to "sink" any additional arguments so that instantiating this controller
|
| 79 |
+
via an argument dict that has additional extraneous arguments won't raise an error
|
| 80 |
+
|
| 81 |
+
Raises:
|
| 82 |
+
AssertionError: [Invalid impedance mode]
|
| 83 |
+
"""
|
| 84 |
+
|
| 85 |
+
def __init__(
|
| 86 |
+
self,
|
| 87 |
+
sim,
|
| 88 |
+
joint_indexes,
|
| 89 |
+
actuator_range,
|
| 90 |
+
input_max=1,
|
| 91 |
+
input_min=-1,
|
| 92 |
+
output_max=1,
|
| 93 |
+
output_min=-1,
|
| 94 |
+
kp=50,
|
| 95 |
+
damping_ratio=1,
|
| 96 |
+
impedance_mode="fixed",
|
| 97 |
+
kp_limits=(0, 300),
|
| 98 |
+
damping_ratio_limits=(0, 100),
|
| 99 |
+
policy_freq=20,
|
| 100 |
+
qpos_limits=None,
|
| 101 |
+
interpolator=None,
|
| 102 |
+
**kwargs, # does nothing; used so no error raised when dict is passed with extra terms used previously
|
| 103 |
+
):
|
| 104 |
+
super().__init__(
|
| 105 |
+
sim,
|
| 106 |
+
joint_indexes,
|
| 107 |
+
actuator_range,
|
| 108 |
+
naming_prefix=kwargs.get("naming_prefix", None),
|
| 109 |
+
)
|
| 110 |
+
|
| 111 |
+
# Control dimension
|
| 112 |
+
self.control_dim = len(joint_indexes["joints"])
|
| 113 |
+
|
| 114 |
+
# input and output max and min (allow for either explicit lists or single numbers)
|
| 115 |
+
self.input_max = self.nums2array(input_max, self.control_dim)
|
| 116 |
+
self.input_min = self.nums2array(input_min, self.control_dim)
|
| 117 |
+
self.output_max = self.nums2array(output_max, self.control_dim)
|
| 118 |
+
self.output_min = self.nums2array(output_min, self.control_dim)
|
| 119 |
+
|
| 120 |
+
# limits
|
| 121 |
+
self.position_limits = np.array(qpos_limits) if qpos_limits is not None else qpos_limits
|
| 122 |
+
|
| 123 |
+
# kp kd
|
| 124 |
+
self.kp = self.nums2array(kp, self.control_dim)
|
| 125 |
+
self.kd = 2 * np.sqrt(self.kp) * damping_ratio
|
| 126 |
+
|
| 127 |
+
# kp and kd limits
|
| 128 |
+
self.kp_min = self.nums2array(kp_limits[0], self.control_dim)
|
| 129 |
+
self.kp_max = self.nums2array(kp_limits[1], self.control_dim)
|
| 130 |
+
self.damping_ratio_min = self.nums2array(damping_ratio_limits[0], self.control_dim)
|
| 131 |
+
self.damping_ratio_max = self.nums2array(damping_ratio_limits[1], self.control_dim)
|
| 132 |
+
|
| 133 |
+
# Verify the proposed impedance mode is supported
|
| 134 |
+
assert impedance_mode in IMPEDANCE_MODES, (
|
| 135 |
+
"Error: Tried to instantiate OSC controller for unsupported "
|
| 136 |
+
"impedance mode! Inputted impedance mode: {}, Supported modes: {}".format(impedance_mode, IMPEDANCE_MODES)
|
| 137 |
+
)
|
| 138 |
+
|
| 139 |
+
# Impedance mode
|
| 140 |
+
self.impedance_mode = impedance_mode
|
| 141 |
+
|
| 142 |
+
# Add to control dim based on impedance_mode
|
| 143 |
+
if self.impedance_mode == "variable":
|
| 144 |
+
self.control_dim *= 3
|
| 145 |
+
elif self.impedance_mode == "variable_kp":
|
| 146 |
+
self.control_dim *= 2
|
| 147 |
+
|
| 148 |
+
# control frequency
|
| 149 |
+
self.control_freq = policy_freq
|
| 150 |
+
|
| 151 |
+
# interpolator
|
| 152 |
+
self.interpolator = interpolator
|
| 153 |
+
|
| 154 |
+
# initialize
|
| 155 |
+
self.goal_qvel = None
|
| 156 |
+
self.init_pos = None
|
| 157 |
+
self.init_ori = None
|
| 158 |
+
|
| 159 |
+
def set_goal(self, action, set_qpos=None):
|
| 160 |
+
"""
|
| 161 |
+
Sets goal based on input @action. If self.impedance_mode is not "fixed", then the input will be parsed into the
|
| 162 |
+
delta values to update the goal position / pose and the kp and/or damping_ratio values to be immediately updated
|
| 163 |
+
internally before executing the proceeding control loop.
|
| 164 |
+
|
| 165 |
+
Note that @action expected to be in the following format, based on impedance mode!
|
| 166 |
+
|
| 167 |
+
:Mode `'fixed'`: [joint pos command]
|
| 168 |
+
:Mode `'variable'`: [damping_ratio values, kp values, joint pos command]
|
| 169 |
+
:Mode `'variable_kp'`: [kp values, joint pos command]
|
| 170 |
+
|
| 171 |
+
Args:
|
| 172 |
+
action (Iterable): Desired relative joint position goal state
|
| 173 |
+
set_qpos (Iterable): If set, overrides @action and sets the desired absolute joint position goal state
|
| 174 |
+
|
| 175 |
+
Raises:
|
| 176 |
+
AssertionError: [Invalid action dimension size]
|
| 177 |
+
"""
|
| 178 |
+
# Update state
|
| 179 |
+
self.update()
|
| 180 |
+
|
| 181 |
+
# Parse action based on the impedance mode, and update kp / kd as necessary
|
| 182 |
+
jnt_dim = len(self.qpos_index)
|
| 183 |
+
if self.impedance_mode == "variable":
|
| 184 |
+
damping_ratio, kp, delta = action[:jnt_dim], action[jnt_dim : 2 * jnt_dim], action[2 * jnt_dim :]
|
| 185 |
+
self.kp = np.clip(kp, self.kp_min, self.kp_max)
|
| 186 |
+
self.kd = 2 * np.sqrt(self.kp) * np.clip(damping_ratio, self.damping_ratio_min, self.damping_ratio_max)
|
| 187 |
+
elif self.impedance_mode == "variable_kp":
|
| 188 |
+
kp, delta = action[:jnt_dim], action[jnt_dim:]
|
| 189 |
+
self.kp = np.clip(kp, self.kp_min, self.kp_max)
|
| 190 |
+
self.kd = 2 * np.sqrt(self.kp) # critically damped
|
| 191 |
+
else: # This is case "fixed"
|
| 192 |
+
delta = action
|
| 193 |
+
|
| 194 |
+
# Check to make sure delta is size self.joint_dim
|
| 195 |
+
assert len(delta) == jnt_dim, "Delta qpos must be equal to the robot's joint dimension space!"
|
| 196 |
+
|
| 197 |
+
if delta is not None:
|
| 198 |
+
scaled_delta = self.scale_action(delta)
|
| 199 |
+
else:
|
| 200 |
+
scaled_delta = None
|
| 201 |
+
|
| 202 |
+
curr_pos, curr_ori = self.get_base_pose()
|
| 203 |
+
|
| 204 |
+
# transform the action relative to initial base orientation
|
| 205 |
+
init_theta = T.mat2euler(self.init_ori)[2] # np.arctan2(self.init_pos[1], self.init_pos[0])
|
| 206 |
+
curr_theta = T.mat2euler(curr_ori)[2] # np.arctan2(curr_pos[1], curr_pos[0])
|
| 207 |
+
theta = curr_theta - init_theta
|
| 208 |
+
|
| 209 |
+
# input raw base action is delta relative to current pose of base
|
| 210 |
+
# controller expects deltas relative to initial pose of base at start of episode
|
| 211 |
+
# transform deltas from current base pose coordinates to initial base pose coordinates
|
| 212 |
+
x, y = action[0:2]
|
| 213 |
+
|
| 214 |
+
# do the reverse of theta rotation
|
| 215 |
+
action[0] = x * np.cos(theta) + y * np.sin(theta)
|
| 216 |
+
action[1] = -x * np.sin(theta) + y * np.cos(theta)
|
| 217 |
+
|
| 218 |
+
self.goal_qvel = action
|
| 219 |
+
if self.interpolator is not None:
|
| 220 |
+
self.interpolator.set_goal(self.goal_qvel)
|
| 221 |
+
|
| 222 |
+
def run_controller(self):
|
| 223 |
+
"""
|
| 224 |
+
Calculates the torques required to reach the desired setpoint
|
| 225 |
+
|
| 226 |
+
Returns:
|
| 227 |
+
np.array: Command torques
|
| 228 |
+
"""
|
| 229 |
+
# Make sure goal has been set
|
| 230 |
+
if self.goal_qvel is None:
|
| 231 |
+
self.set_goal(np.zeros(self.control_dim))
|
| 232 |
+
|
| 233 |
+
# Update state
|
| 234 |
+
self.update()
|
| 235 |
+
|
| 236 |
+
desired_qvel = None
|
| 237 |
+
|
| 238 |
+
# Only linear interpolator is currently supported
|
| 239 |
+
if self.interpolator is not None:
|
| 240 |
+
# Linear case
|
| 241 |
+
if self.interpolator.order == 1:
|
| 242 |
+
desired_qvel = self.interpolator.get_interpolated_goal()
|
| 243 |
+
else:
|
| 244 |
+
# Nonlinear case not currently supported
|
| 245 |
+
pass
|
| 246 |
+
else:
|
| 247 |
+
desired_qvel = np.array(self.goal_qvel)
|
| 248 |
+
|
| 249 |
+
self.vels = desired_qvel
|
| 250 |
+
|
| 251 |
+
ctrl_range = np.stack([self.actuator_min, self.actuator_max], axis=-1)
|
| 252 |
+
bias = 0.5 * (ctrl_range[:, 1] + ctrl_range[:, 0])
|
| 253 |
+
weight = 0.5 * (ctrl_range[:, 1] - ctrl_range[:, 0])
|
| 254 |
+
self.vels = bias + weight * self.vels
|
| 255 |
+
|
| 256 |
+
# Always run superclass call for any cleanups at the end
|
| 257 |
+
super().run_controller()
|
| 258 |
+
|
| 259 |
+
return self.vels
|
| 260 |
+
|
| 261 |
+
def reset_goal(self):
|
| 262 |
+
"""
|
| 263 |
+
Resets joint position goal to be current position
|
| 264 |
+
"""
|
| 265 |
+
self.goal_qvel = self.joint_vel
|
| 266 |
+
|
| 267 |
+
self.init_pos, self.init_ori = self.get_base_pose()
|
| 268 |
+
|
| 269 |
+
# Reset interpolator if required
|
| 270 |
+
if self.interpolator is not None:
|
| 271 |
+
self.interpolator.set_goal(self.goal_qvel)
|
| 272 |
+
|
| 273 |
+
@property
|
| 274 |
+
def control_limits(self):
|
| 275 |
+
"""
|
| 276 |
+
Returns the limits over this controller's action space, overrides the superclass property
|
| 277 |
+
Returns the following (generalized for both high and low limits), based on the impedance mode:
|
| 278 |
+
|
| 279 |
+
:Mode `'fixed'`: [joint pos command]
|
| 280 |
+
:Mode `'variable'`: [damping_ratio values, kp values, joint pos command]
|
| 281 |
+
:Mode `'variable_kp'`: [kp values, joint pos command]
|
| 282 |
+
|
| 283 |
+
Returns:
|
| 284 |
+
2-tuple:
|
| 285 |
+
|
| 286 |
+
- (np.array) minimum action values
|
| 287 |
+
- (np.array) maximum action values
|
| 288 |
+
"""
|
| 289 |
+
if self.impedance_mode == "variable":
|
| 290 |
+
low = np.concatenate([self.damping_ratio_min, self.kp_min, self.input_min])
|
| 291 |
+
high = np.concatenate([self.damping_ratio_max, self.kp_max, self.input_max])
|
| 292 |
+
elif self.impedance_mode == "variable_kp":
|
| 293 |
+
low = np.concatenate([self.kp_min, self.input_min])
|
| 294 |
+
high = np.concatenate([self.kp_max, self.input_max])
|
| 295 |
+
else: # This is case "fixed"
|
| 296 |
+
low, high = self.input_min, self.input_max
|
| 297 |
+
return low, high
|
| 298 |
+
|
| 299 |
+
@property
|
| 300 |
+
def name(self):
|
| 301 |
+
return "JOINT_VELOCITY"
|
| 302 |
+
|
| 303 |
+
|
| 304 |
+
class LegacyMobileBaseJointVelocityController(MobileBaseJointVelocityController):
|
| 305 |
+
"""
|
| 306 |
+
Legacy version of MobileBaseJointVelocityController, created to address
|
| 307 |
+
the recent change in the axis of the forward joint in the mobile base xml.
|
| 308 |
+
This controller is identical to the original MobileBaseJointVelocityController,
|
| 309 |
+
except that it dynamically checks the axis of the forward joint and reorders
|
| 310 |
+
the input action accordingly if the forward axis is the y axis instead of the x axis.
|
| 311 |
+
This allows for backwards compatibility with previously collected datasets
|
| 312 |
+
that were generated using older versions of the mobile base xml.
|
| 313 |
+
"""
|
| 314 |
+
|
| 315 |
+
def __init__(self, *args, **kwargs):
|
| 316 |
+
super().__init__(*args, **kwargs)
|
| 317 |
+
|
| 318 |
+
def _check_forward_joint_reversed(self):
|
| 319 |
+
# Detect the axis for the forward joint and dynamically reorder action accordingly.
|
| 320 |
+
# This is needed because previous versions of the mobile base xml had different forward
|
| 321 |
+
# axis definitions. In order to maintain backwards compatibility with previous datasets
|
| 322 |
+
# we dynamically detect the forward joint axis.
|
| 323 |
+
forward_jnt = None
|
| 324 |
+
forward_jnt_axis = None
|
| 325 |
+
for jnt in self.joint_names:
|
| 326 |
+
if "joint_mobile_forward" in jnt:
|
| 327 |
+
forward_jnt = jnt
|
| 328 |
+
forward_jnt_axis = self.sim.model.jnt_axis[self.sim.model.joint_name2id(jnt)]
|
| 329 |
+
break
|
| 330 |
+
return forward_jnt is not None and (forward_jnt_axis == np.array([0, 1, 0])).all()
|
| 331 |
+
|
| 332 |
+
def set_goal(self, action, set_qpos=None):
|
| 333 |
+
# Update state
|
| 334 |
+
self.update()
|
| 335 |
+
|
| 336 |
+
# Parse action based on the impedance mode, and update kp / kd as necessary
|
| 337 |
+
jnt_dim = len(self.qpos_index)
|
| 338 |
+
if self.impedance_mode == "variable":
|
| 339 |
+
damping_ratio, kp, delta = action[:jnt_dim], action[jnt_dim : 2 * jnt_dim], action[2 * jnt_dim :]
|
| 340 |
+
self.kp = np.clip(kp, self.kp_min, self.kp_max)
|
| 341 |
+
self.kd = 2 * np.sqrt(self.kp) * np.clip(damping_ratio, self.damping_ratio_min, self.damping_ratio_max)
|
| 342 |
+
elif self.impedance_mode == "variable_kp":
|
| 343 |
+
kp, delta = action[:jnt_dim], action[jnt_dim:]
|
| 344 |
+
self.kp = np.clip(kp, self.kp_min, self.kp_max)
|
| 345 |
+
self.kd = 2 * np.sqrt(self.kp) # critically damped
|
| 346 |
+
else: # This is case "fixed"
|
| 347 |
+
delta = action
|
| 348 |
+
|
| 349 |
+
# Check to make sure delta is size self.joint_dim
|
| 350 |
+
assert len(delta) == jnt_dim, "Delta qpos must be equal to the robot's joint dimension space!"
|
| 351 |
+
|
| 352 |
+
if delta is not None:
|
| 353 |
+
scaled_delta = self.scale_action(delta)
|
| 354 |
+
else:
|
| 355 |
+
scaled_delta = None
|
| 356 |
+
|
| 357 |
+
curr_pos, curr_ori = self.get_base_pose()
|
| 358 |
+
|
| 359 |
+
# transform the action relative to initial base orientation
|
| 360 |
+
init_theta = T.mat2euler(self.init_ori)[2] # np.arctan2(self.init_pos[1], self.init_pos[0])
|
| 361 |
+
curr_theta = T.mat2euler(curr_ori)[2] # np.arctan2(curr_pos[1], curr_pos[0])
|
| 362 |
+
theta = curr_theta - init_theta
|
| 363 |
+
|
| 364 |
+
# reorder action if forward axis is y axis
|
| 365 |
+
if self._check_forward_joint_reversed():
|
| 366 |
+
action = np.copy([action[i] for i in [1, 0, 2]])
|
| 367 |
+
|
| 368 |
+
x, y = action[0:2]
|
| 369 |
+
# do the reverse of theta rotation
|
| 370 |
+
action[0] = x * np.cos(theta) + y * np.sin(theta)
|
| 371 |
+
action[1] = -x * np.sin(theta) + y * np.cos(theta)
|
| 372 |
+
else:
|
| 373 |
+
# input raw base action is delta relative to current pose of base
|
| 374 |
+
# controller expects deltas relative to initial pose of base at start of episode
|
| 375 |
+
# transform deltas from current base pose coordinates to initial base pose coordinates
|
| 376 |
+
action = action.copy()
|
| 377 |
+
x, y = action[0:2]
|
| 378 |
+
action[0] = x * np.cos(theta) - y * np.sin(theta)
|
| 379 |
+
action[1] = x * np.sin(theta) + y * np.cos(theta)
|
| 380 |
+
|
| 381 |
+
self.goal_qvel = action
|
| 382 |
+
if self.interpolator is not None:
|
| 383 |
+
self.interpolator.set_goal(self.goal_qvel)
|
robosuite/controllers/parts/mobile_base/mobile_base_controller.py
ADDED
|
@@ -0,0 +1,249 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import abc
|
| 2 |
+
from collections.abc import Iterable
|
| 3 |
+
|
| 4 |
+
import mujoco
|
| 5 |
+
import numpy as np
|
| 6 |
+
|
| 7 |
+
import robosuite.macros as macros
|
| 8 |
+
|
| 9 |
+
|
| 10 |
+
class MobileBaseController(object, metaclass=abc.ABCMeta):
|
| 11 |
+
"""
|
| 12 |
+
General controller interface.
|
| 13 |
+
|
| 14 |
+
Requires reference to mujoco sim object, relevant joint_indexes to that robot, and
|
| 15 |
+
whether an initial_joint is used for nullspace torques or not
|
| 16 |
+
|
| 17 |
+
Args:
|
| 18 |
+
sim (MjSim): Simulator instance this controller will pull robot state updates from
|
| 19 |
+
|
| 20 |
+
joint_indexes (dict): Each key contains sim reference indexes to relevant robot joint information, namely:
|
| 21 |
+
|
| 22 |
+
:`'joints'`: list of indexes to relevant robot joints
|
| 23 |
+
:`'qpos'`: list of indexes to relevant robot joint positions
|
| 24 |
+
:`'qvel'`: list of indexes to relevant robot joint velocities
|
| 25 |
+
|
| 26 |
+
actuator_range (2-tuple of array of float): 2-Tuple (low, high) representing the robot joint actuator range
|
| 27 |
+
"""
|
| 28 |
+
|
| 29 |
+
def __init__(
|
| 30 |
+
self,
|
| 31 |
+
sim,
|
| 32 |
+
joint_indexes,
|
| 33 |
+
actuator_range,
|
| 34 |
+
naming_prefix=None,
|
| 35 |
+
):
|
| 36 |
+
|
| 37 |
+
# Actuator range
|
| 38 |
+
self.actuator_min = actuator_range[0]
|
| 39 |
+
self.actuator_max = actuator_range[1]
|
| 40 |
+
|
| 41 |
+
# Attributes for scaling / clipping inputs to outputs
|
| 42 |
+
self.action_scale = None
|
| 43 |
+
self.action_input_transform = None
|
| 44 |
+
self.action_output_transform = None
|
| 45 |
+
|
| 46 |
+
# Private property attributes
|
| 47 |
+
self.control_dim = None
|
| 48 |
+
self.output_min = None
|
| 49 |
+
self.output_max = None
|
| 50 |
+
self.input_min = None
|
| 51 |
+
self.input_max = None
|
| 52 |
+
|
| 53 |
+
# mujoco simulator state
|
| 54 |
+
self.sim = sim
|
| 55 |
+
self.model_timestep = macros.SIMULATION_TIMESTEP
|
| 56 |
+
self.naming_prefix = naming_prefix
|
| 57 |
+
|
| 58 |
+
self.joint_index = joint_indexes["joints"]
|
| 59 |
+
self.qpos_index = joint_indexes["qpos"]
|
| 60 |
+
self.qvel_index = joint_indexes["qvel"]
|
| 61 |
+
self.joint_names = [self.sim.model.joint_id2name(joint_id) for joint_id in self.joint_index]
|
| 62 |
+
|
| 63 |
+
# robot states
|
| 64 |
+
self.joint_pos = None
|
| 65 |
+
self.joint_vel = None
|
| 66 |
+
|
| 67 |
+
# Joint dimension
|
| 68 |
+
self.joint_dim = len(joint_indexes["joints"])
|
| 69 |
+
|
| 70 |
+
# Torques being outputted by the controller
|
| 71 |
+
self.torques = None
|
| 72 |
+
|
| 73 |
+
# Update flag to prevent redundant update calls
|
| 74 |
+
self.new_update = True
|
| 75 |
+
|
| 76 |
+
# Move forward one timestep to propagate updates before taking first update
|
| 77 |
+
self.sim.forward()
|
| 78 |
+
|
| 79 |
+
# Initialize controller by updating internal state and setting the initial joint, pos, and ori
|
| 80 |
+
self.update()
|
| 81 |
+
self.initial_joint = self.joint_pos
|
| 82 |
+
|
| 83 |
+
self.base_pos = None
|
| 84 |
+
self.base_ori_mat = None
|
| 85 |
+
|
| 86 |
+
self.init_pos = None
|
| 87 |
+
self.init_ori = None
|
| 88 |
+
|
| 89 |
+
def get_base_pose(self):
|
| 90 |
+
base_pos = np.array(self.sim.data.site_xpos[self.sim.model.site_name2id(f"{self.naming_prefix}center")])
|
| 91 |
+
base_ori = np.array(
|
| 92 |
+
self.sim.data.site_xmat[self.sim.model.site_name2id(f"{self.naming_prefix}center")].reshape([3, 3])
|
| 93 |
+
)
|
| 94 |
+
return base_pos, base_ori
|
| 95 |
+
|
| 96 |
+
def reset(self):
|
| 97 |
+
self.init_pos = self.base_pos
|
| 98 |
+
self.init_ori = self.base_ori_mat
|
| 99 |
+
|
| 100 |
+
@abc.abstractmethod
|
| 101 |
+
def run_controller(self):
|
| 102 |
+
"""
|
| 103 |
+
Abstract method that should be implemented in all subclass controllers, and should convert a given action
|
| 104 |
+
into torques (pre gravity compensation) to be executed on the robot.
|
| 105 |
+
Additionally, resets the self.new_update flag so that the next self.update call will occur
|
| 106 |
+
"""
|
| 107 |
+
self.new_update = True
|
| 108 |
+
|
| 109 |
+
def scale_action(self, action):
|
| 110 |
+
"""
|
| 111 |
+
Clips @action to be within self.input_min and self.input_max, and then re-scale the values to be within
|
| 112 |
+
the range self.output_min and self.output_max
|
| 113 |
+
|
| 114 |
+
Args:
|
| 115 |
+
action (Iterable): Actions to scale
|
| 116 |
+
|
| 117 |
+
Returns:
|
| 118 |
+
np.array: Re-scaled action
|
| 119 |
+
"""
|
| 120 |
+
|
| 121 |
+
if self.action_scale is None:
|
| 122 |
+
self.action_scale = abs(self.output_max - self.output_min) / abs(self.input_max - self.input_min)
|
| 123 |
+
self.action_output_transform = (self.output_max + self.output_min) / 2.0
|
| 124 |
+
self.action_input_transform = (self.input_max + self.input_min) / 2.0
|
| 125 |
+
action = np.clip(action, self.input_min, self.input_max)
|
| 126 |
+
transformed_action = (action - self.action_input_transform) * self.action_scale + self.action_output_transform
|
| 127 |
+
|
| 128 |
+
return transformed_action
|
| 129 |
+
|
| 130 |
+
def update(self, force=False):
|
| 131 |
+
"""
|
| 132 |
+
Updates the state of the robot arm, including end effector pose / orientation / velocity, joint pos/vel,
|
| 133 |
+
jacobian, and mass matrix. By default, since this is a non-negligible computation, multiple redundant calls
|
| 134 |
+
will be ignored via the self.new_update attribute flag. However, if the @force flag is set, the update will
|
| 135 |
+
occur regardless of that state of self.new_update. This base class method of @run_controller resets the
|
| 136 |
+
self.new_update flag
|
| 137 |
+
|
| 138 |
+
Args:
|
| 139 |
+
force (bool): Whether to force an update to occur or not
|
| 140 |
+
"""
|
| 141 |
+
|
| 142 |
+
# Only run update if self.new_update or force flag is set
|
| 143 |
+
if self.new_update or force:
|
| 144 |
+
|
| 145 |
+
self.joint_pos = np.array(self.sim.data.qpos[self.qpos_index])
|
| 146 |
+
self.joint_vel = np.array(self.sim.data.qvel[self.qvel_index])
|
| 147 |
+
|
| 148 |
+
# Clear self.new_update
|
| 149 |
+
self.new_update = False
|
| 150 |
+
|
| 151 |
+
def update_initial_joints(self, initial_joints):
|
| 152 |
+
"""
|
| 153 |
+
Updates the internal attribute self.initial_joints. This is useful for updating changes in controller-specific
|
| 154 |
+
behavior, such as with OSC where self.initial_joints is used for determine nullspace actions
|
| 155 |
+
|
| 156 |
+
This function can also be extended by subclassed controllers for additional controller-specific updates
|
| 157 |
+
|
| 158 |
+
Args:
|
| 159 |
+
initial_joints (Iterable): Array of joint position values to update the initial joints
|
| 160 |
+
"""
|
| 161 |
+
self.initial_joint = np.array(initial_joints)
|
| 162 |
+
self.update(force=True)
|
| 163 |
+
self.initial_ref_pos = self.ref_pos
|
| 164 |
+
self.initial_ref_ori_mat = self.ref_ori_mat
|
| 165 |
+
|
| 166 |
+
def clip_torques(self, torques):
|
| 167 |
+
"""
|
| 168 |
+
Clips the torques to be within the actuator limits
|
| 169 |
+
|
| 170 |
+
Args:
|
| 171 |
+
torques (Iterable): Torques to clip
|
| 172 |
+
|
| 173 |
+
Returns:
|
| 174 |
+
np.array: Clipped torques
|
| 175 |
+
"""
|
| 176 |
+
return np.clip(torques, self.actuator_min, self.actuator_max)
|
| 177 |
+
|
| 178 |
+
def reset_goal(self):
|
| 179 |
+
"""
|
| 180 |
+
Resets the goal -- usually by setting to the goal to all zeros, but in some cases may be different (e.g.: OSC)
|
| 181 |
+
"""
|
| 182 |
+
raise NotImplementedError
|
| 183 |
+
|
| 184 |
+
@staticmethod
|
| 185 |
+
def nums2array(nums, dim):
|
| 186 |
+
"""
|
| 187 |
+
Convert input @nums into numpy array of length @dim. If @nums is a single number, broadcasts it to the
|
| 188 |
+
corresponding dimension size @dim before converting into a numpy array
|
| 189 |
+
|
| 190 |
+
Args:
|
| 191 |
+
nums (numeric or Iterable): Either single value or array of numbers
|
| 192 |
+
dim (int): Size of array to broadcast input to env.sim.data.actuator_force
|
| 193 |
+
|
| 194 |
+
Returns:
|
| 195 |
+
np.array: Array filled with values specified in @nums
|
| 196 |
+
"""
|
| 197 |
+
# First run sanity check to make sure no strings are being inputted
|
| 198 |
+
if isinstance(nums, str):
|
| 199 |
+
raise TypeError("Error: Only numeric inputs are supported for this function, nums2array!")
|
| 200 |
+
|
| 201 |
+
# Check if input is an Iterable, if so, we simply convert the input to np.array and return
|
| 202 |
+
# Else, input is a single value, so we map to a numpy array of correct size and return
|
| 203 |
+
return np.array(nums) if isinstance(nums, Iterable) else np.ones(dim) * nums
|
| 204 |
+
|
| 205 |
+
@property
|
| 206 |
+
def torque_compensation(self):
|
| 207 |
+
"""
|
| 208 |
+
Gravity compensation for this robot arm
|
| 209 |
+
|
| 210 |
+
Returns:
|
| 211 |
+
np.array: torques
|
| 212 |
+
"""
|
| 213 |
+
return self.sim.data.qfrc_bias[self.qvel_index]
|
| 214 |
+
|
| 215 |
+
@property
|
| 216 |
+
def actuator_limits(self):
|
| 217 |
+
"""
|
| 218 |
+
Torque limits for this controller
|
| 219 |
+
|
| 220 |
+
Returns:
|
| 221 |
+
2-tuple:
|
| 222 |
+
|
| 223 |
+
- (np.array) minimum actuator torques
|
| 224 |
+
- (np.array) maximum actuator torques
|
| 225 |
+
"""
|
| 226 |
+
return self.actuator_min, self.actuator_max
|
| 227 |
+
|
| 228 |
+
@property
|
| 229 |
+
def control_limits(self):
|
| 230 |
+
"""
|
| 231 |
+
Limits over this controller's action space, which defaults to input min/max
|
| 232 |
+
|
| 233 |
+
Returns:
|
| 234 |
+
2-tuple:
|
| 235 |
+
|
| 236 |
+
- (np.array) minimum action values
|
| 237 |
+
- (np.array) maximum action values
|
| 238 |
+
"""
|
| 239 |
+
return self.input_min, self.input_max
|
| 240 |
+
|
| 241 |
+
@property
|
| 242 |
+
def name(self):
|
| 243 |
+
"""
|
| 244 |
+
Name of this controller
|
| 245 |
+
|
| 246 |
+
Returns:
|
| 247 |
+
str: controller name
|
| 248 |
+
"""
|
| 249 |
+
raise NotImplementedError
|
robosuite/demos/demo_collect_and_playback_data.py
ADDED
|
@@ -0,0 +1,132 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
"""
|
| 2 |
+
Record trajectory data with the DataCollectionWrapper wrapper and play them back.
|
| 3 |
+
|
| 4 |
+
Example:
|
| 5 |
+
$ python demo_collect_and_playback_data.py --environment Lift
|
| 6 |
+
"""
|
| 7 |
+
|
| 8 |
+
import argparse
|
| 9 |
+
import os
|
| 10 |
+
import time
|
| 11 |
+
from glob import glob
|
| 12 |
+
|
| 13 |
+
import numpy as np
|
| 14 |
+
|
| 15 |
+
import robosuite as suite
|
| 16 |
+
from robosuite.wrappers import DataCollectionWrapper
|
| 17 |
+
|
| 18 |
+
|
| 19 |
+
def collect_random_trajectory(env, timesteps=1000, max_fr=None):
|
| 20 |
+
"""Run a random policy to collect trajectories.
|
| 21 |
+
|
| 22 |
+
The rollout trajectory is saved to files in npz format.
|
| 23 |
+
Modify the DataCollectionWrapper wrapper to add new fields or change data formats.
|
| 24 |
+
|
| 25 |
+
Args:
|
| 26 |
+
env (MujocoEnv): environment instance to collect trajectories from
|
| 27 |
+
timesteps(int): how many environment timesteps to run for a given trajectory
|
| 28 |
+
max_fr (int): if specified, pause the simulation whenever simulation runs faster than max_fr
|
| 29 |
+
"""
|
| 30 |
+
|
| 31 |
+
env.reset()
|
| 32 |
+
dof = env.action_dim
|
| 33 |
+
|
| 34 |
+
for t in range(timesteps):
|
| 35 |
+
start = time.time()
|
| 36 |
+
action = np.random.randn(dof)
|
| 37 |
+
env.step(action)
|
| 38 |
+
env.render()
|
| 39 |
+
if t % 100 == 0:
|
| 40 |
+
print(t)
|
| 41 |
+
|
| 42 |
+
# limit frame rate if necessary
|
| 43 |
+
if max_fr is not None:
|
| 44 |
+
elapsed = time.time() - start
|
| 45 |
+
diff = 1 / max_fr - elapsed
|
| 46 |
+
if diff > 0:
|
| 47 |
+
time.sleep(diff)
|
| 48 |
+
|
| 49 |
+
|
| 50 |
+
def playback_trajectory(env, ep_dir, max_fr=None):
|
| 51 |
+
"""Playback data from an episode.
|
| 52 |
+
|
| 53 |
+
Args:
|
| 54 |
+
env (MujocoEnv): environment instance to playback trajectory in
|
| 55 |
+
ep_dir (str): The path to the directory containing data for an episode.
|
| 56 |
+
"""
|
| 57 |
+
|
| 58 |
+
# first reload the model from the xml
|
| 59 |
+
xml_path = os.path.join(ep_dir, "model.xml")
|
| 60 |
+
with open(xml_path, "r") as f:
|
| 61 |
+
env.reset_from_xml_string(f.read())
|
| 62 |
+
|
| 63 |
+
state_paths = os.path.join(ep_dir, "state_*.npz")
|
| 64 |
+
|
| 65 |
+
# read states back, load them one by one, and render
|
| 66 |
+
t = 0
|
| 67 |
+
for state_file in sorted(glob(state_paths)):
|
| 68 |
+
print(state_file)
|
| 69 |
+
dic = np.load(state_file)
|
| 70 |
+
states = dic["states"]
|
| 71 |
+
for state in states:
|
| 72 |
+
start = time.time()
|
| 73 |
+
env.sim.set_state_from_flattened(state)
|
| 74 |
+
env.sim.forward()
|
| 75 |
+
env.viewer.update()
|
| 76 |
+
env.render()
|
| 77 |
+
t += 1
|
| 78 |
+
if t % 100 == 0:
|
| 79 |
+
print(t)
|
| 80 |
+
|
| 81 |
+
if max_fr is not None:
|
| 82 |
+
elapsed = time.time() - start
|
| 83 |
+
diff = 1 / max_fr - elapsed
|
| 84 |
+
if diff > 0:
|
| 85 |
+
time.sleep(diff)
|
| 86 |
+
env.close()
|
| 87 |
+
|
| 88 |
+
|
| 89 |
+
if __name__ == "__main__":
|
| 90 |
+
|
| 91 |
+
parser = argparse.ArgumentParser()
|
| 92 |
+
parser.add_argument("--environment", type=str, default="Door")
|
| 93 |
+
parser.add_argument("--robots", nargs="+", type=str, default="Panda", help="Which robot(s) to use in the env")
|
| 94 |
+
parser.add_argument("--directory", type=str, default="/tmp/")
|
| 95 |
+
parser.add_argument("--timesteps", type=int, default=1000)
|
| 96 |
+
parser.add_argument(
|
| 97 |
+
"--max_fr",
|
| 98 |
+
default=20,
|
| 99 |
+
type=int,
|
| 100 |
+
help="Sleep when simluation runs faster than specified frame rate; 20 fps is real time.",
|
| 101 |
+
)
|
| 102 |
+
args = parser.parse_args()
|
| 103 |
+
|
| 104 |
+
# create original environment
|
| 105 |
+
env = suite.make(
|
| 106 |
+
args.environment,
|
| 107 |
+
robots=args.robots,
|
| 108 |
+
ignore_done=True,
|
| 109 |
+
use_camera_obs=False,
|
| 110 |
+
has_renderer=True,
|
| 111 |
+
has_offscreen_renderer=False,
|
| 112 |
+
control_freq=20,
|
| 113 |
+
)
|
| 114 |
+
data_directory = args.directory
|
| 115 |
+
|
| 116 |
+
# wrap the environment with data collection wrapper
|
| 117 |
+
env = DataCollectionWrapper(env, data_directory)
|
| 118 |
+
|
| 119 |
+
# testing to make sure multiple env.reset calls don't create multiple directories
|
| 120 |
+
env.reset()
|
| 121 |
+
env.reset()
|
| 122 |
+
env.reset()
|
| 123 |
+
|
| 124 |
+
# collect some data
|
| 125 |
+
print("Collecting some random data...")
|
| 126 |
+
collect_random_trajectory(env, timesteps=args.timesteps, max_fr=args.max_fr)
|
| 127 |
+
|
| 128 |
+
# playback some data
|
| 129 |
+
_ = input("Press any key to begin the playback...")
|
| 130 |
+
print("Playing back the data...")
|
| 131 |
+
data_directory = env.ep_directory
|
| 132 |
+
playback_trajectory(env, data_directory, args.max_fr)
|
robosuite/demos/demo_composite_robot.py
ADDED
|
@@ -0,0 +1,85 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import argparse
|
| 2 |
+
import time
|
| 3 |
+
from typing import Dict, List, Union
|
| 4 |
+
|
| 5 |
+
import numpy as np
|
| 6 |
+
|
| 7 |
+
import robosuite as suite
|
| 8 |
+
from robosuite.controllers import load_composite_controller_config
|
| 9 |
+
from robosuite.robots import ROBOT_CLASS_MAPPING
|
| 10 |
+
from robosuite.utils.robot_composition_utils import create_composite_robot
|
| 11 |
+
|
| 12 |
+
|
| 13 |
+
def create_and_test_env(
|
| 14 |
+
env: str,
|
| 15 |
+
robots: Union[str, List[str]],
|
| 16 |
+
controller_config: Dict,
|
| 17 |
+
headless: bool = False,
|
| 18 |
+
max_fr: int = None,
|
| 19 |
+
):
|
| 20 |
+
|
| 21 |
+
config = {
|
| 22 |
+
"env_name": env,
|
| 23 |
+
"robots": robots,
|
| 24 |
+
"controller_configs": controller_config,
|
| 25 |
+
}
|
| 26 |
+
|
| 27 |
+
env = suite.make(
|
| 28 |
+
**config,
|
| 29 |
+
has_renderer=not headless,
|
| 30 |
+
has_offscreen_renderer=headless,
|
| 31 |
+
ignore_done=True,
|
| 32 |
+
use_camera_obs=False,
|
| 33 |
+
reward_shaping=True,
|
| 34 |
+
control_freq=20,
|
| 35 |
+
)
|
| 36 |
+
env.reset()
|
| 37 |
+
low, high = env.action_spec
|
| 38 |
+
low = np.clip(low, -1, 1)
|
| 39 |
+
high = np.clip(high, -1, 1)
|
| 40 |
+
|
| 41 |
+
# Runs a few steps of the simulation as a sanity check
|
| 42 |
+
for i in range(100):
|
| 43 |
+
start = time.time()
|
| 44 |
+
|
| 45 |
+
action = np.random.uniform(low, high)
|
| 46 |
+
obs, reward, done, _ = env.step(action)
|
| 47 |
+
|
| 48 |
+
# limit frame rate if necessary
|
| 49 |
+
if max_fr is not None:
|
| 50 |
+
elapsed = time.time() - start
|
| 51 |
+
diff = 1 / max_fr - elapsed
|
| 52 |
+
if diff > 0:
|
| 53 |
+
time.sleep(diff)
|
| 54 |
+
|
| 55 |
+
env.close()
|
| 56 |
+
|
| 57 |
+
|
| 58 |
+
if __name__ == "__main__":
|
| 59 |
+
|
| 60 |
+
parser = argparse.ArgumentParser()
|
| 61 |
+
|
| 62 |
+
parser.add_argument("--robot", type=str, required=True)
|
| 63 |
+
parser.add_argument("--base", type=str, default=None)
|
| 64 |
+
parser.add_argument("--grippers", nargs="+", type=str, default=["PandaGripper"])
|
| 65 |
+
parser.add_argument("--env", type=str, default="Lift")
|
| 66 |
+
parser.add_argument("--headless", action="store_true")
|
| 67 |
+
parser.add_argument(
|
| 68 |
+
"--max_fr",
|
| 69 |
+
default=20,
|
| 70 |
+
type=int,
|
| 71 |
+
help="Sleep when simluation runs faster than specified frame rate; 20 fps is real time.",
|
| 72 |
+
)
|
| 73 |
+
|
| 74 |
+
args = parser.parse_args()
|
| 75 |
+
|
| 76 |
+
if args.robot not in ROBOT_CLASS_MAPPING:
|
| 77 |
+
raise ValueError(f"Robot {args.robot} not found in ROBOT_CLASS_MAPPING \n" f"{ROBOT_CLASS_MAPPING.keys()}")
|
| 78 |
+
|
| 79 |
+
name = f"Custom{args.robot}"
|
| 80 |
+
create_composite_robot(name, base=args.base, robot=args.robot, grippers=args.grippers)
|
| 81 |
+
controller_config = load_composite_controller_config(controller="BASIC", robot=name)
|
| 82 |
+
|
| 83 |
+
create_and_test_env(
|
| 84 |
+
env="Lift", robots=name, controller_config=controller_config, headless=args.headless, max_fr=args.max_fr
|
| 85 |
+
)
|
robosuite/demos/demo_control.py
ADDED
|
@@ -0,0 +1,185 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
"""
|
| 2 |
+
This demo script demonstrates the various functionalities of each controller available within robosuite.
|
| 3 |
+
|
| 4 |
+
For a given controller, runs through each dimension and executes a perturbation "test_value" from its
|
| 5 |
+
neutral (stationary) value for a certain amount of time "steps_per_action", and then returns to all neutral values
|
| 6 |
+
for time "steps_per_rest" before proceeding with the next action dim.
|
| 7 |
+
|
| 8 |
+
E.g.: Given that the expected action space of the Pos / Ori (OSC_POSE) controller (without a gripper) is
|
| 9 |
+
(dx, dy, dz, droll, dpitch, dyaw), the testing sequence of actions over time will be:
|
| 10 |
+
|
| 11 |
+
***START OF DEMO***
|
| 12 |
+
( dx, 0, 0, 0, 0, 0, grip) <-- Translation in x-direction for 'steps_per_action' steps
|
| 13 |
+
( 0, 0, 0, 0, 0, 0, grip) <-- No movement (pause) for 'steps_per_rest' steps
|
| 14 |
+
( 0, dy, 0, 0, 0, 0, grip) <-- Translation in y-direction for 'steps_per_action' steps
|
| 15 |
+
( 0, 0, 0, 0, 0, 0, grip) <-- No movement (pause) for 'steps_per_rest' steps
|
| 16 |
+
( 0, 0, dz, 0, 0, 0, grip) <-- Translation in z-direction for 'steps_per_action' steps
|
| 17 |
+
( 0, 0, 0, 0, 0, 0, grip) <-- No movement (pause) for 'steps_per_rest' steps
|
| 18 |
+
( 0, 0, 0, dr, 0, 0, grip) <-- Rotation in roll (x) axis for 'steps_per_action' steps
|
| 19 |
+
( 0, 0, 0, 0, 0, 0, grip) <-- No movement (pause) for 'steps_per_rest' steps
|
| 20 |
+
( 0, 0, 0, 0, dp, 0, grip) <-- Rotation in pitch (y) axis for 'steps_per_action' steps
|
| 21 |
+
( 0, 0, 0, 0, 0, 0, grip) <-- No movement (pause) for 'steps_per_rest' steps
|
| 22 |
+
( 0, 0, 0, 0, 0, dy, grip) <-- Rotation in yaw (z) axis for 'steps_per_action' steps
|
| 23 |
+
( 0, 0, 0, 0, 0, 0, grip) <-- No movement (pause) for 'steps_per_rest' steps
|
| 24 |
+
***END OF DEMO***
|
| 25 |
+
|
| 26 |
+
Thus the OSC_POSE controller should be expected to sequentially move linearly in the x direction first,
|
| 27 |
+
then the y direction, then the z direction, and then begin sequentially rotating about its x-axis,
|
| 28 |
+
then y-axis, then z-axis.
|
| 29 |
+
|
| 30 |
+
Please reference the documentation of Controllers in the Modules section for an overview of each controller.
|
| 31 |
+
Controllers are expected to behave in a generally controlled manner, according to their control space. The expected
|
| 32 |
+
sequential qualitative behavior during the test is described below for each controller:
|
| 33 |
+
|
| 34 |
+
* OSC_POSE: Gripper moves sequentially and linearly in x, y, z direction, then sequentially rotates in x-axis, y-axis,
|
| 35 |
+
z-axis, relative to the global coordinate frame
|
| 36 |
+
* OSC_POSITION: Gripper moves sequentially and linearly in x, y, z direction, relative to the global coordinate frame
|
| 37 |
+
* IK_POSE: Gripper moves sequentially and linearly in x, y, z direction, then sequentially rotates in x-axis, y-axis,
|
| 38 |
+
z-axis, relative to the local robot end effector frame
|
| 39 |
+
* JOINT_POSITION: Robot Joints move sequentially in a controlled fashion
|
| 40 |
+
* JOINT_VELOCITY: Robot Joints move sequentially in a controlled fashion
|
| 41 |
+
* JOINT_TORQUE: Unlike other controllers, joint torque controller is expected to act rather lethargic, as the
|
| 42 |
+
"controller" is really just a wrapper for direct torque control of the mujoco actuators. Therefore, a
|
| 43 |
+
"neutral" value of 0 torque will not guarantee a stable robot when it has non-zero velocity!
|
| 44 |
+
|
| 45 |
+
"""
|
| 46 |
+
|
| 47 |
+
import time
|
| 48 |
+
from typing import Dict
|
| 49 |
+
|
| 50 |
+
import robosuite as suite
|
| 51 |
+
from robosuite.controllers.composite.composite_controller_factory import refactor_composite_controller_config
|
| 52 |
+
from robosuite.utils.input_utils import *
|
| 53 |
+
|
| 54 |
+
MAX_FR = 25 # max frame rate for running simluation
|
| 55 |
+
|
| 56 |
+
if __name__ == "__main__":
|
| 57 |
+
|
| 58 |
+
# Create dict to hold options that will be passed to env creation call
|
| 59 |
+
options = {}
|
| 60 |
+
|
| 61 |
+
# print welcome info
|
| 62 |
+
print("Welcome to robosuite v{}!".format(suite.__version__))
|
| 63 |
+
print(suite.__logo__)
|
| 64 |
+
|
| 65 |
+
# Choose environment and add it to options
|
| 66 |
+
options["env_name"] = choose_environment()
|
| 67 |
+
|
| 68 |
+
# If a multi-arm environment has been chosen, choose configuration and appropriate robot(s)
|
| 69 |
+
if "TwoArm" in options["env_name"]:
|
| 70 |
+
# Choose env config and add it to options
|
| 71 |
+
options["env_configuration"] = choose_multi_arm_config()
|
| 72 |
+
|
| 73 |
+
# If chosen configuration was bimanual, the corresponding robot must be Baxter. Else, have user choose robots
|
| 74 |
+
if options["env_configuration"] == "bimanual":
|
| 75 |
+
options["robots"] = "Baxter"
|
| 76 |
+
else:
|
| 77 |
+
options["robots"] = []
|
| 78 |
+
|
| 79 |
+
# Have user choose two robots
|
| 80 |
+
print("A multiple single-arm configuration was chosen.\n")
|
| 81 |
+
|
| 82 |
+
for i in range(2):
|
| 83 |
+
print("Please choose Robot {}...\n".format(i))
|
| 84 |
+
options["robots"].append(choose_robots(exclude_bimanual=True))
|
| 85 |
+
# If a humanoid environment has been chosen, choose humanoid robots
|
| 86 |
+
elif "Humanoid" in options["env_name"]:
|
| 87 |
+
options["robots"] = choose_robots(use_humanoids=True)
|
| 88 |
+
# Else, we simply choose a single (single-armed) robot to instantiate in the environment
|
| 89 |
+
else:
|
| 90 |
+
options["robots"] = choose_robots(exclude_bimanual=True)
|
| 91 |
+
|
| 92 |
+
# Hacky way to grab joint dimension for now
|
| 93 |
+
joint_dim = 6 if options["robots"] == "UR5e" else (16 if options["robots"] == "GR1" else 7)
|
| 94 |
+
|
| 95 |
+
# Choose controller
|
| 96 |
+
controller_name = choose_controller(part_controllers=True)
|
| 97 |
+
|
| 98 |
+
# Load the desired controller
|
| 99 |
+
arm_controller_config = suite.load_part_controller_config(default_controller=controller_name)
|
| 100 |
+
robot = options["robots"][0] if isinstance(options["robots"], list) else options["robots"]
|
| 101 |
+
options["controller_configs"] = refactor_composite_controller_config(
|
| 102 |
+
arm_controller_config, robot, ["right", "left"]
|
| 103 |
+
)
|
| 104 |
+
|
| 105 |
+
# Define the pre-defined controller actions to use (action_dim, num_test_steps, test_value)
|
| 106 |
+
controller_settings = {
|
| 107 |
+
"OSC_POSE": [6, 6, 0.1],
|
| 108 |
+
"OSC_POSITION": [3, 3, 0.1],
|
| 109 |
+
"IK_POSE": [6, 6, 0.01],
|
| 110 |
+
"JOINT_POSITION": [joint_dim, joint_dim, 0.2],
|
| 111 |
+
"JOINT_VELOCITY": [joint_dim, joint_dim, -0.1],
|
| 112 |
+
"JOINT_TORQUE": [joint_dim, joint_dim, 0.25],
|
| 113 |
+
}
|
| 114 |
+
|
| 115 |
+
# Define variables for each controller test
|
| 116 |
+
action_dim = controller_settings[controller_name][0]
|
| 117 |
+
num_test_steps = controller_settings[controller_name][1]
|
| 118 |
+
test_value = controller_settings[controller_name][2]
|
| 119 |
+
|
| 120 |
+
# Define the number of timesteps to use per controller action as well as timesteps in between actions
|
| 121 |
+
steps_per_action = 75
|
| 122 |
+
steps_per_rest = 75
|
| 123 |
+
|
| 124 |
+
# initialize the task
|
| 125 |
+
env = suite.make(
|
| 126 |
+
**options,
|
| 127 |
+
has_renderer=True,
|
| 128 |
+
has_offscreen_renderer=False,
|
| 129 |
+
ignore_done=True,
|
| 130 |
+
use_camera_obs=False,
|
| 131 |
+
horizon=(steps_per_action + steps_per_rest) * num_test_steps,
|
| 132 |
+
control_freq=20,
|
| 133 |
+
)
|
| 134 |
+
env.reset()
|
| 135 |
+
env.viewer.set_camera(camera_id=0)
|
| 136 |
+
|
| 137 |
+
# To accommodate for multi-arm settings (e.g.: Baxter), we need to make sure to fill any extra action space
|
| 138 |
+
# Get total number of arms being controlled
|
| 139 |
+
n = 0
|
| 140 |
+
gripper_dim = 0
|
| 141 |
+
for robot in env.robots:
|
| 142 |
+
gripper_dim = robot.gripper["right"].dof
|
| 143 |
+
n += int(robot.action_dim / (action_dim + gripper_dim))
|
| 144 |
+
|
| 145 |
+
# Define neutral value
|
| 146 |
+
neutral = np.zeros(action_dim + gripper_dim)
|
| 147 |
+
|
| 148 |
+
# Keep track of done variable to know when to break loop
|
| 149 |
+
count = 0
|
| 150 |
+
# Loop through controller space
|
| 151 |
+
while count < num_test_steps:
|
| 152 |
+
action = neutral.copy()
|
| 153 |
+
for i in range(steps_per_action):
|
| 154 |
+
start = time.time()
|
| 155 |
+
if controller_name in {"IK_POSE", "OSC_POSE"} and count > 2:
|
| 156 |
+
# Set this value to be the scaled axis angle vector
|
| 157 |
+
vec = np.zeros(3)
|
| 158 |
+
vec[count - 3] = test_value
|
| 159 |
+
action[3:6] = vec
|
| 160 |
+
else:
|
| 161 |
+
action[count] = test_value
|
| 162 |
+
total_action = np.tile(action, n)
|
| 163 |
+
env.step(total_action)
|
| 164 |
+
env.render()
|
| 165 |
+
|
| 166 |
+
# limit frame rate if necessary
|
| 167 |
+
elapsed = time.time() - start
|
| 168 |
+
diff = 1 / MAX_FR - elapsed
|
| 169 |
+
if diff > 0:
|
| 170 |
+
time.sleep(diff)
|
| 171 |
+
for i in range(steps_per_rest):
|
| 172 |
+
start = time.time()
|
| 173 |
+
total_action = np.tile(neutral, n)
|
| 174 |
+
env.step(total_action)
|
| 175 |
+
env.render()
|
| 176 |
+
|
| 177 |
+
# limit frame rate if necessary
|
| 178 |
+
elapsed = time.time() - start
|
| 179 |
+
diff = 1 / MAX_FR - elapsed
|
| 180 |
+
if diff > 0:
|
| 181 |
+
time.sleep(diff)
|
| 182 |
+
count += 1
|
| 183 |
+
|
| 184 |
+
# Shut down this env before starting the next test
|
| 185 |
+
env.close()
|
robosuite/demos/demo_device_control.py
ADDED
|
@@ -0,0 +1,307 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
"""Teleoperate robot with keyboard or SpaceMouse.
|
| 2 |
+
|
| 3 |
+
***Choose user input option with the --device argument***
|
| 4 |
+
|
| 5 |
+
Keyboard:
|
| 6 |
+
We use the keyboard to control the end-effector of the robot.
|
| 7 |
+
The keyboard provides 6-DoF control commands through various keys.
|
| 8 |
+
The commands are mapped to joint velocities through an inverse kinematics
|
| 9 |
+
solver from Bullet physics.
|
| 10 |
+
|
| 11 |
+
Note:
|
| 12 |
+
To run this script with macOS, you must run it with root access.
|
| 13 |
+
|
| 14 |
+
SpaceMouse:
|
| 15 |
+
|
| 16 |
+
We use the SpaceMouse 3D mouse to control the end-effector of the robot.
|
| 17 |
+
The mouse provides 6-DoF control commands. The commands are mapped to joint
|
| 18 |
+
velocities through an inverse kinematics solver from Bullet physics.
|
| 19 |
+
|
| 20 |
+
The two side buttons of SpaceMouse are used for controlling the grippers.
|
| 21 |
+
|
| 22 |
+
SpaceMouse Wireless from 3Dconnexion: https://www.3dconnexion.com/spacemouse_wireless/en/
|
| 23 |
+
We used the SpaceMouse Wireless in our experiments. The paper below used the same device
|
| 24 |
+
to collect human demonstrations for imitation learning.
|
| 25 |
+
|
| 26 |
+
Reinforcement and Imitation Learning for Diverse Visuomotor Skills
|
| 27 |
+
Yuke Zhu, Ziyu Wang, Josh Merel, Andrei Rusu, Tom Erez, Serkan Cabi, Saran Tunyasuvunakool,
|
| 28 |
+
János Kramár, Raia Hadsell, Nando de Freitas, Nicolas Heess
|
| 29 |
+
RSS 2018
|
| 30 |
+
|
| 31 |
+
Note:
|
| 32 |
+
This current implementation only supports macOS (Linux support can be added).
|
| 33 |
+
Download and install the driver before running the script:
|
| 34 |
+
https://www.3dconnexion.com/service/drivers.html
|
| 35 |
+
|
| 36 |
+
Additionally, --pos_sensitivity and --rot_sensitivity provide relative gains for increasing / decreasing the user input
|
| 37 |
+
device sensitivity
|
| 38 |
+
|
| 39 |
+
|
| 40 |
+
***Choose controller with the --controller argument***
|
| 41 |
+
|
| 42 |
+
Choice of using either inverse kinematics controller (ik) or operational space controller (osc):
|
| 43 |
+
Main difference is that user inputs with ik's rotations are always taken relative to eef coordinate frame, whereas
|
| 44 |
+
user inputs with osc's rotations are taken relative to global frame (i.e.: static / camera frame of reference).
|
| 45 |
+
|
| 46 |
+
|
| 47 |
+
***Choose environment specifics with the following arguments***
|
| 48 |
+
|
| 49 |
+
--environment: Task to perform, e.g.: "Lift", "TwoArmPegInHole", "NutAssembly", etc.
|
| 50 |
+
|
| 51 |
+
--robots: Robot(s) with which to perform the task. Can be any in
|
| 52 |
+
{"Panda", "Sawyer", "IIWA", "Jaco", "Kinova3", "UR5e", "Baxter"}. Note that the environments include sanity
|
| 53 |
+
checks, such that a "TwoArm..." environment will only accept either a 2-tuple of robot names or a single
|
| 54 |
+
bimanual robot name, according to the specified configuration (see below), and all other environments will
|
| 55 |
+
only accept a single single-armed robot name
|
| 56 |
+
|
| 57 |
+
--config: Exclusively applicable and only should be specified for "TwoArm..." environments. Specifies the robot
|
| 58 |
+
configuration desired for the task. Options are {"parallel" and "opposed"}
|
| 59 |
+
|
| 60 |
+
-"parallel": Sets up the environment such that two robots are stationed next to
|
| 61 |
+
each other facing the same direction. Expects a 2-tuple of robot names to be specified
|
| 62 |
+
in the --robots argument.
|
| 63 |
+
|
| 64 |
+
-"opposed": Sets up the environment such that two robots are stationed opposed from
|
| 65 |
+
each other, facing each other from opposite directions. Expects a 2-tuple of robot names
|
| 66 |
+
to be specified in the --robots argument.
|
| 67 |
+
|
| 68 |
+
--arm: Exclusively applicable and only should be specified for "TwoArm..." environments. Specifies which of the
|
| 69 |
+
multiple arm eef's to control. The other (passive) arm will remain stationary. Options are {"right", "left"}
|
| 70 |
+
(from the point of view of the robot(s) facing against the viewer direction)
|
| 71 |
+
|
| 72 |
+
--switch-on-grasp: Exclusively applicable and only should be specified for "TwoArm..." environments. If enabled,
|
| 73 |
+
will switch the current arm being controlled every time the gripper input is pressed
|
| 74 |
+
|
| 75 |
+
--toggle-camera-on-grasp: If enabled, gripper input presses will cycle through the available camera angles
|
| 76 |
+
|
| 77 |
+
Examples:
|
| 78 |
+
|
| 79 |
+
For normal single-arm environment:
|
| 80 |
+
$ python demo_device_control.py --environment PickPlaceCan --robots Sawyer --controller osc
|
| 81 |
+
|
| 82 |
+
For two-arm bimanual environment:
|
| 83 |
+
$ python demo_device_control.py --environment TwoArmLift --robots Baxter --config bimanual --arm left --controller osc
|
| 84 |
+
|
| 85 |
+
For two-arm multi single-arm robot environment:
|
| 86 |
+
$ python demo_device_control.py --environment TwoArmLift --robots Sawyer Sawyer --config parallel --controller osc
|
| 87 |
+
|
| 88 |
+
|
| 89 |
+
"""
|
| 90 |
+
|
| 91 |
+
import argparse
|
| 92 |
+
import time
|
| 93 |
+
|
| 94 |
+
import numpy as np
|
| 95 |
+
|
| 96 |
+
import robosuite as suite
|
| 97 |
+
from robosuite import load_composite_controller_config
|
| 98 |
+
from robosuite.controllers.composite.composite_controller import WholeBody
|
| 99 |
+
from robosuite.wrappers import VisualizationWrapper
|
| 100 |
+
|
| 101 |
+
if __name__ == "__main__":
|
| 102 |
+
parser = argparse.ArgumentParser()
|
| 103 |
+
parser.add_argument("--environment", type=str, default="Lift")
|
| 104 |
+
parser.add_argument(
|
| 105 |
+
"--robots",
|
| 106 |
+
nargs="+",
|
| 107 |
+
type=str,
|
| 108 |
+
default="Panda",
|
| 109 |
+
help="Which robot(s) to use in the env",
|
| 110 |
+
)
|
| 111 |
+
parser.add_argument(
|
| 112 |
+
"--config",
|
| 113 |
+
type=str,
|
| 114 |
+
default="default",
|
| 115 |
+
help="Specified environment configuration if necessary",
|
| 116 |
+
)
|
| 117 |
+
parser.add_argument(
|
| 118 |
+
"--arm",
|
| 119 |
+
type=str,
|
| 120 |
+
default="right",
|
| 121 |
+
help="Which arm to control (eg bimanual) 'right' or 'left'",
|
| 122 |
+
)
|
| 123 |
+
parser.add_argument(
|
| 124 |
+
"--switch-on-grasp",
|
| 125 |
+
action="store_true",
|
| 126 |
+
help="Switch gripper control on gripper action",
|
| 127 |
+
)
|
| 128 |
+
parser.add_argument(
|
| 129 |
+
"--toggle-camera-on-grasp",
|
| 130 |
+
action="store_true",
|
| 131 |
+
help="Switch camera angle on gripper action",
|
| 132 |
+
)
|
| 133 |
+
parser.add_argument(
|
| 134 |
+
"--controller",
|
| 135 |
+
type=str,
|
| 136 |
+
default=None,
|
| 137 |
+
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",
|
| 138 |
+
)
|
| 139 |
+
parser.add_argument("--device", type=str, default="keyboard")
|
| 140 |
+
parser.add_argument(
|
| 141 |
+
"--pos-sensitivity",
|
| 142 |
+
type=float,
|
| 143 |
+
default=1.0,
|
| 144 |
+
help="How much to scale position user inputs",
|
| 145 |
+
)
|
| 146 |
+
parser.add_argument(
|
| 147 |
+
"--rot-sensitivity",
|
| 148 |
+
type=float,
|
| 149 |
+
default=1.0,
|
| 150 |
+
help="How much to scale rotation user inputs",
|
| 151 |
+
)
|
| 152 |
+
parser.add_argument(
|
| 153 |
+
"--max_fr",
|
| 154 |
+
default=20,
|
| 155 |
+
type=int,
|
| 156 |
+
help="Sleep when simluation runs faster than specified frame rate; 20 fps is real time.",
|
| 157 |
+
)
|
| 158 |
+
parser.add_argument(
|
| 159 |
+
"--reverse_xy",
|
| 160 |
+
type=bool,
|
| 161 |
+
default=False,
|
| 162 |
+
help="(DualSense Only)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)",
|
| 163 |
+
)
|
| 164 |
+
args = parser.parse_args()
|
| 165 |
+
|
| 166 |
+
# Get controller config
|
| 167 |
+
controller_config = load_composite_controller_config(
|
| 168 |
+
controller=args.controller,
|
| 169 |
+
robot=args.robots[0],
|
| 170 |
+
)
|
| 171 |
+
|
| 172 |
+
# Create argument configuration
|
| 173 |
+
config = {
|
| 174 |
+
"env_name": args.environment,
|
| 175 |
+
"robots": args.robots,
|
| 176 |
+
"controller_configs": controller_config,
|
| 177 |
+
}
|
| 178 |
+
|
| 179 |
+
# Check if we're using a multi-armed environment and use env_configuration argument if so
|
| 180 |
+
if "TwoArm" in args.environment:
|
| 181 |
+
config["env_configuration"] = args.config
|
| 182 |
+
else:
|
| 183 |
+
args.config = None
|
| 184 |
+
|
| 185 |
+
# Create environment
|
| 186 |
+
env = suite.make(
|
| 187 |
+
**config,
|
| 188 |
+
has_renderer=True,
|
| 189 |
+
has_offscreen_renderer=False,
|
| 190 |
+
render_camera="agentview",
|
| 191 |
+
ignore_done=True,
|
| 192 |
+
use_camera_obs=False,
|
| 193 |
+
reward_shaping=True,
|
| 194 |
+
control_freq=20,
|
| 195 |
+
hard_reset=False,
|
| 196 |
+
)
|
| 197 |
+
|
| 198 |
+
# Wrap this environment in a visualization wrapper
|
| 199 |
+
env = VisualizationWrapper(env, indicator_configs=None)
|
| 200 |
+
|
| 201 |
+
# Setup printing options for numbers
|
| 202 |
+
np.set_printoptions(formatter={"float": lambda x: "{0:0.3f}".format(x)})
|
| 203 |
+
|
| 204 |
+
# initialize device
|
| 205 |
+
if args.device == "keyboard":
|
| 206 |
+
from robosuite.devices import Keyboard
|
| 207 |
+
|
| 208 |
+
device = Keyboard(
|
| 209 |
+
env=env,
|
| 210 |
+
pos_sensitivity=args.pos_sensitivity,
|
| 211 |
+
rot_sensitivity=args.rot_sensitivity,
|
| 212 |
+
)
|
| 213 |
+
env.viewer.add_keypress_callback(device.on_press)
|
| 214 |
+
elif args.device == "spacemouse":
|
| 215 |
+
from robosuite.devices import SpaceMouse
|
| 216 |
+
|
| 217 |
+
device = SpaceMouse(
|
| 218 |
+
env=env,
|
| 219 |
+
pos_sensitivity=args.pos_sensitivity,
|
| 220 |
+
rot_sensitivity=args.rot_sensitivity,
|
| 221 |
+
)
|
| 222 |
+
elif args.device == "dualsense":
|
| 223 |
+
from robosuite.devices import DualSense
|
| 224 |
+
|
| 225 |
+
device = DualSense(
|
| 226 |
+
env=env,
|
| 227 |
+
pos_sensitivity=args.pos_sensitivity,
|
| 228 |
+
rot_sensitivity=args.rot_sensitivity,
|
| 229 |
+
reverse_xy=args.reverse_xy,
|
| 230 |
+
)
|
| 231 |
+
elif args.device == "mjgui":
|
| 232 |
+
from robosuite.devices.mjgui import MJGUI
|
| 233 |
+
|
| 234 |
+
device = MJGUI(env=env)
|
| 235 |
+
else:
|
| 236 |
+
raise Exception("Invalid device choice: choose either 'keyboard', 'dualsene' or 'spacemouse'.")
|
| 237 |
+
|
| 238 |
+
while True:
|
| 239 |
+
# Reset the environment
|
| 240 |
+
obs = env.reset()
|
| 241 |
+
|
| 242 |
+
# Setup rendering
|
| 243 |
+
cam_id = 0
|
| 244 |
+
num_cam = len(env.sim.model.camera_names)
|
| 245 |
+
env.render()
|
| 246 |
+
|
| 247 |
+
# Initialize variables that should the maintained between resets
|
| 248 |
+
last_grasp = 0
|
| 249 |
+
|
| 250 |
+
# Initialize device control
|
| 251 |
+
device.start_control()
|
| 252 |
+
all_prev_gripper_actions = [
|
| 253 |
+
{
|
| 254 |
+
f"{robot_arm}_gripper": np.repeat([0], robot.gripper[robot_arm].dof)
|
| 255 |
+
for robot_arm in robot.arms
|
| 256 |
+
if robot.gripper[robot_arm].dof > 0
|
| 257 |
+
}
|
| 258 |
+
for robot in env.robots
|
| 259 |
+
]
|
| 260 |
+
|
| 261 |
+
# Loop until we get a reset from the input or the task completes
|
| 262 |
+
while True:
|
| 263 |
+
start = time.time()
|
| 264 |
+
|
| 265 |
+
# Set active robot
|
| 266 |
+
active_robot = env.robots[device.active_robot]
|
| 267 |
+
|
| 268 |
+
# Get the newest action
|
| 269 |
+
input_ac_dict = device.input2action()
|
| 270 |
+
|
| 271 |
+
# If action is none, then this a reset so we should break
|
| 272 |
+
if input_ac_dict is None:
|
| 273 |
+
break
|
| 274 |
+
|
| 275 |
+
from copy import deepcopy
|
| 276 |
+
|
| 277 |
+
action_dict = deepcopy(input_ac_dict) # {}
|
| 278 |
+
# set arm actions
|
| 279 |
+
for arm in active_robot.arms:
|
| 280 |
+
if isinstance(active_robot.composite_controller, WholeBody): # input type passed to joint_action_policy
|
| 281 |
+
controller_input_type = active_robot.composite_controller.joint_action_policy.input_type
|
| 282 |
+
else:
|
| 283 |
+
controller_input_type = active_robot.part_controllers[arm].input_type
|
| 284 |
+
|
| 285 |
+
if controller_input_type == "delta":
|
| 286 |
+
action_dict[arm] = input_ac_dict[f"{arm}_delta"]
|
| 287 |
+
elif controller_input_type == "absolute":
|
| 288 |
+
action_dict[arm] = input_ac_dict[f"{arm}_abs"]
|
| 289 |
+
else:
|
| 290 |
+
raise ValueError
|
| 291 |
+
|
| 292 |
+
# Maintain gripper state for each robot but only update the active robot with action
|
| 293 |
+
env_action = [robot.create_action_vector(all_prev_gripper_actions[i]) for i, robot in enumerate(env.robots)]
|
| 294 |
+
env_action[device.active_robot] = active_robot.create_action_vector(action_dict)
|
| 295 |
+
env_action = np.concatenate(env_action)
|
| 296 |
+
for gripper_ac in all_prev_gripper_actions[device.active_robot]:
|
| 297 |
+
all_prev_gripper_actions[device.active_robot][gripper_ac] = action_dict[gripper_ac]
|
| 298 |
+
|
| 299 |
+
env.step(env_action)
|
| 300 |
+
env.render()
|
| 301 |
+
|
| 302 |
+
# limit frame rate if necessary
|
| 303 |
+
if args.max_fr is not None:
|
| 304 |
+
elapsed = time.time() - start
|
| 305 |
+
diff = 1 / args.max_fr - elapsed
|
| 306 |
+
if diff > 0:
|
| 307 |
+
time.sleep(diff)
|
robosuite/demos/demo_domain_randomization.py
ADDED
|
@@ -0,0 +1,78 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
"""
|
| 2 |
+
Script to showcase domain randomization functionality.
|
| 3 |
+
"""
|
| 4 |
+
|
| 5 |
+
import time
|
| 6 |
+
|
| 7 |
+
import robosuite.macros as macros
|
| 8 |
+
from robosuite.utils.input_utils import *
|
| 9 |
+
from robosuite.wrappers import DomainRandomizationWrapper
|
| 10 |
+
|
| 11 |
+
# We'll use instance randomization so that entire geom groups are randomized together
|
| 12 |
+
macros.USING_INSTANCE_RANDOMIZATION = True
|
| 13 |
+
|
| 14 |
+
if __name__ == "__main__":
|
| 15 |
+
# Create dict to hold options that will be passed to env creation call
|
| 16 |
+
options = {}
|
| 17 |
+
|
| 18 |
+
# print welcome info
|
| 19 |
+
print("Welcome to robosuite v{}!".format(suite.__version__))
|
| 20 |
+
print(suite.__logo__)
|
| 21 |
+
|
| 22 |
+
# Choose environment and add it to options
|
| 23 |
+
options["env_name"] = choose_environment()
|
| 24 |
+
|
| 25 |
+
# If a multi-arm environment has been chosen, choose configuration and appropriate robot(s)
|
| 26 |
+
if "TwoArm" in options["env_name"]:
|
| 27 |
+
# Choose env config and add it to options
|
| 28 |
+
options["env_configuration"] = choose_multi_arm_config()
|
| 29 |
+
|
| 30 |
+
# If chosen configuration was bimanual, the corresponding robot must be Baxter. Else, have user choose robots
|
| 31 |
+
if options["env_configuration"] == "bimanual":
|
| 32 |
+
options["robots"] = "Baxter"
|
| 33 |
+
else:
|
| 34 |
+
options["robots"] = []
|
| 35 |
+
|
| 36 |
+
# Have user choose two robots
|
| 37 |
+
print("A multiple single-arm configuration was chosen.\n")
|
| 38 |
+
|
| 39 |
+
for i in range(2):
|
| 40 |
+
print("Please choose Robot {}...\n".format(i))
|
| 41 |
+
options["robots"].append(choose_robots(exclude_bimanual=True))
|
| 42 |
+
# If a humanoid environment has been chosen, choose humanoid robots
|
| 43 |
+
elif "Humanoid" in options["env_name"]:
|
| 44 |
+
options["robots"] = choose_robots(use_humanoids=True)
|
| 45 |
+
# Else, we simply choose a single (single-armed) robot to instantiate in the environment
|
| 46 |
+
else:
|
| 47 |
+
options["robots"] = choose_robots(exclude_bimanual=True)
|
| 48 |
+
|
| 49 |
+
# initialize the task
|
| 50 |
+
env = suite.make(
|
| 51 |
+
**options,
|
| 52 |
+
has_renderer=True,
|
| 53 |
+
has_offscreen_renderer=False,
|
| 54 |
+
ignore_done=True,
|
| 55 |
+
use_camera_obs=False,
|
| 56 |
+
control_freq=20,
|
| 57 |
+
hard_reset=False, # TODO: Not setting this flag to False brings up a segfault on macos or glfw error on linux
|
| 58 |
+
)
|
| 59 |
+
env = DomainRandomizationWrapper(
|
| 60 |
+
env,
|
| 61 |
+
randomize_color=False, # randomize_color currently only works for mujoco==3.1.1
|
| 62 |
+
randomize_camera=False, # less jarring when visualizing
|
| 63 |
+
randomize_dynamics=False,
|
| 64 |
+
)
|
| 65 |
+
env.reset()
|
| 66 |
+
env.viewer.set_camera(camera_id=0)
|
| 67 |
+
|
| 68 |
+
max_frame_rate = 20 # Set the desired maximum frame rate
|
| 69 |
+
|
| 70 |
+
# Get action limits
|
| 71 |
+
low, high = env.action_spec
|
| 72 |
+
|
| 73 |
+
# do visualization
|
| 74 |
+
for i in range(100):
|
| 75 |
+
action = np.random.uniform(low, high)
|
| 76 |
+
obs, reward, done, _ = env.step(action)
|
| 77 |
+
env.render()
|
| 78 |
+
time.sleep(1 / max_frame_rate)
|