-
Notifications
You must be signed in to change notification settings - Fork 135
Robosuite-Scenic Integration [Custom only] #383
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: robosuite
Are you sure you want to change the base?
Changes from all commits
8cfbfe4
8ec7beb
bde69a3
9641225
d8dfc69
6ba582d
4ea472f
70272a4
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,18 @@ | ||
| # examples/robosuite/dual_table_workspace.scenic | ||
| model scenic.simulators.robosuite.model | ||
|
|
||
| # Arena Setup | ||
| back_table = new Table at (-0.6, 0, 0.8) | ||
| front_table = new Table at (0.6, 0, 0.8) | ||
|
|
||
| # OBJECTS | ||
| red_cube = new Box at (Range(-0.7, -0.5), Range(-0.1, 0.1), 0.83), | ||
| with color (1, 0, 0, 1), | ||
|
|
||
|
|
||
| green_cube = new Box at (Range(0.5, 0.7), Range(-0.1, 0.1), 0.83), | ||
| with color (0, 1, 0, 1), | ||
| with width 0.05, with length 0.05, with height 0.05 | ||
|
|
||
| # ROBOT | ||
| ego = new Panda at (0, 0, 0) |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,49 @@ | ||
| # examples/robosuite/four_table_workspace.scenic | ||
| model scenic.simulators.robosuite.model | ||
|
|
||
| # CAMERA CONFIGURATION | ||
| # param camera_view = "sideview" | ||
|
|
||
| TABLE_DISTANCE = 1.0 | ||
|
|
||
| # WORKSPACE: Four tables in cross formation | ||
| back_table = new Table at (-TABLE_DISTANCE, 0, 0.8) | ||
| front_table = new Table at (TABLE_DISTANCE, 0, 0.8) | ||
| right_table = new Table at (0, TABLE_DISTANCE, 0.8) | ||
| left_table = new Table at (0, -TABLE_DISTANCE, 0.8) | ||
|
|
||
| # TABLE 1 (Back): Primitive objects with random positions | ||
| ball = new Ball at (Range(-1.1, -0.9), Range(-0.1, 0.1), 0.83), | ||
| with color (1, 0.5, 0, 1) | ||
|
|
||
| box = new Box at (Range(-1.1, -0.9), Range(-0.1, 0.1), 0.83), | ||
| with color (0, 0, 1, 1) | ||
|
|
||
| capsule = new Capsule at (Range(-1.1, -0.9), Range(-0.1, 0.1), 0.83), | ||
| with color (0.5, 0.5, 0.5, 1) | ||
|
|
||
| cylinder = new Cylinder at (Range(-1.1, -0.9), Range(-0.1, 0.1), 0.83), | ||
| with color (0, 1, 1, 1) | ||
|
|
||
| # TABLE 2 (Front): Nuts and food items | ||
| square_nut = new SquareNut at (Range(0.9, 1.1), Range(-0.1, 0.1), 0.85) | ||
|
|
||
| round_nut = new RoundNut at (Range(0.9, 1.1), Range(-0.1, 0.1), 0.85) | ||
|
|
||
| milk = new Milk at (Range(0.9, 1.1), Range(-0.1, 0.1), 0.85) | ||
|
|
||
| cereal = new Cereal at (Range(0.9, 1.1), Range(-0.1, 0.1), 0.85) | ||
|
|
||
| # TABLE 3 (Right): Various objects | ||
| can = new Can at (Range(-0.1, 0.1), Range(0.9, 1.1), 0.85) | ||
|
|
||
| bread = new Bread at (Range(-0.1, 0.1), Range(0.9, 1.1), 0.85) | ||
|
|
||
| bottle = new Bottle at (Range(-0.1, 0.1), Range(0.9, 1.1), 0.85) | ||
|
|
||
| hammer = new Hammer at (Range(-0.1, 0.1), Range(0.9, 1.1), 0.85) | ||
|
|
||
| # TABLE 4 (Left): Intentionally left empty | ||
|
|
||
| # ROBOT | ||
| ego = new Panda at (0, 0, 0) |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,28 @@ | ||
| model scenic.simulators.robosuite.model | ||
|
|
||
| work_table = new Table at (0.6, 0, 0.8), | ||
| with width 0.6, | ||
| with length 1.2, | ||
| with height 0.05 | ||
|
|
||
| bottom_cube = new Box at (0.6, 0, 0.83), | ||
| with color (0.2, 0.3, 0.8, 1), | ||
| with width 0.06, with length 0.06, with height 0.06 | ||
|
|
||
| top_cube = new Box at (0.6, 0, 0.89) | ||
| with color (0.8, 0.2, 0.2, 1), | ||
|
|
||
| bottle = new Bottle at (0.6, 0.3, 0.83) | ||
|
|
||
| pickup_object = top_cube | ||
|
|
||
| behavior StackLift(): | ||
| """Pick up the top cube from the stack and lift it.""" | ||
| do PickObject(pickup_object) | ||
| do LiftToHeight(1.05) | ||
| for _ in range(10): | ||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. If this limit of 10 steps is exceeded, the behavior will return and so the simulation will never end (unless you imposed a time limit when running Scenic). Did you mean to write
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This was actually leftover from an earlier debugging session where I needed the simulation to continue running after the behavior completed, it allowed me to inspect the final robot state and manipulate the environment directly through Robosuite's viewer for testing purposes. And yes for the release version, this should properly terminate, I'll add the |
||
| if pickup_object.position.z > 1.0: | ||
| terminate simulation | ||
| wait | ||
| ego = new UR5e at (0, 0, 0), | ||
| with behavior StackLift() | ||
| Original file line number | Diff line number | Diff line change | ||||
|---|---|---|---|---|---|---|
| @@ -0,0 +1,19 @@ | ||||||
| model scenic.simulators.robosuite.model | ||||||
|
|
||||||
| # param camera_view = "sideview" | ||||||
|
|
||||||
| work_table = new Table at (0.6, 0, 0.8), | ||||||
| with width 0.6, | ||||||
| with length 1.2, | ||||||
| with height 0.05 | ||||||
|
|
||||||
| bottom_cube = new Box at (0.6, 0, 0.83), | ||||||
| with color (0.2, 0.3, 0.8, 1), | ||||||
| with width 0.06, with length 0.06, with height 0.06 | ||||||
|
|
||||||
| top_cube = new Box at (0.6, 0, 0.89), | ||||||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
This should work if the shape of the
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. yes in the new PR and most recent commit, I have done exactly that. |
||||||
| with color (0.8, 0.2, 0.2, 1), | ||||||
|
|
||||||
| bottle = new Bottle at (0.6, 0.3, 0.83) | ||||||
|
|
||||||
| ego = new UR5e at (0, 0, 0) | ||||||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,5 @@ | ||
| """RoboSuite simulator interface for Scenic.""" | ||
|
|
||
| from .simulator import RobosuiteSimulator, RobosuiteSimulation | ||
|
|
||
| __all__ = ['RobosuiteSimulator', 'RobosuiteSimulation'] |
| Original file line number | Diff line number | Diff line change | ||||||||||||
|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
| @@ -0,0 +1,253 @@ | ||||||||||||||
| # src/scenic/simulators/robosuite/model.scenic | ||||||||||||||
|
|
||||||||||||||
| """Scenic world model for RoboSuite - Custom Environments Only.""" | ||||||||||||||
|
|
||||||||||||||
| from .simulator import RobosuiteSimulator, SetJointPositions, OSCPositionAction | ||||||||||||||
|
|
||||||||||||||
| # Global parameters with defaults matching Robosuite's defaults | ||||||||||||||
| param env_config = {} | ||||||||||||||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Please add documentation for these global parameters to the module docstring (see |
||||||||||||||
| param controller_config = None | ||||||||||||||
| param camera_view = None | ||||||||||||||
| param render = True | ||||||||||||||
| param real_time = True | ||||||||||||||
| param speed = 1.0 | ||||||||||||||
| param lite_physics = None # None = use Robosuite default (True) | ||||||||||||||
|
|
||||||||||||||
| # Simulator - no more use_environment parameter | ||||||||||||||
| simulator RobosuiteSimulator( | ||||||||||||||
| render=globalParameters.render, | ||||||||||||||
| real_time=globalParameters.real_time, | ||||||||||||||
| speed=globalParameters.speed, | ||||||||||||||
| env_config=globalParameters.env_config, | ||||||||||||||
| controller_config=globalParameters.controller_config, | ||||||||||||||
| camera_view=globalParameters.camera_view, | ||||||||||||||
| lite_physics=globalParameters.lite_physics | ||||||||||||||
| ) | ||||||||||||||
|
|
||||||||||||||
| # Default values dictionary | ||||||||||||||
| DEFAULTS = { | ||||||||||||||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I don't think gathering all the defaults into a dict like this makes the code any clearer. I'd just put the values directly into the classes where they are used, so that they're immediately present if you go to look up the default value of a property in the class definition. |
||||||||||||||
| # Object properties | ||||||||||||||
| 'object_size': 0.03, | ||||||||||||||
| 'density': 1000, | ||||||||||||||
| 'friction': (1.0, 0.005, 0.0001), | ||||||||||||||
| 'solref': (0.02, 1.0), | ||||||||||||||
| 'solimp': (0.9, 0.95, 0.001, 0.5, 2.0), | ||||||||||||||
| 'default_color': (0.5, 0.5, 0.5, 1.0), | ||||||||||||||
|
|
||||||||||||||
| # Arena properties | ||||||||||||||
| 'table_height': 0.8, | ||||||||||||||
| 'table_width': 0.8, | ||||||||||||||
| 'table_length': 0.8, | ||||||||||||||
| 'table_thickness': 0.05, | ||||||||||||||
|
|
||||||||||||||
| # Robot properties | ||||||||||||||
| 'robot_width': 0.2, | ||||||||||||||
| 'robot_length': 0.2, | ||||||||||||||
| 'robot_height': 0.5, | ||||||||||||||
|
|
||||||||||||||
| # Control parameters | ||||||||||||||
| 'control_gain': 3.0, | ||||||||||||||
| 'control_limit': 0.3, | ||||||||||||||
| 'position_tolerance': 0.02, | ||||||||||||||
| 'height_tolerance': 0.02, | ||||||||||||||
| 'gripper_open_steps': 20, | ||||||||||||||
| 'gripper_close_steps': 30, | ||||||||||||||
| 'max_control_steps': 100, | ||||||||||||||
| 'max_lift_steps': 200 | ||||||||||||||
| } | ||||||||||||||
|
|
||||||||||||||
| # Base classes | ||||||||||||||
| class RoboSuiteObject(Object): | ||||||||||||||
| """Base class for all RoboSuite objects.""" | ||||||||||||||
| density: DEFAULTS['density'] | ||||||||||||||
| friction: DEFAULTS['friction'] | ||||||||||||||
| solref: DEFAULTS['solref'] | ||||||||||||||
| solimp: DEFAULTS['solimp'] | ||||||||||||||
| shape: BoxShape() | ||||||||||||||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This is the default value, so you don't need to override |
||||||||||||||
| allowCollisions: True | ||||||||||||||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Why allow collisions by default? We don't want to be able to place cubes inside the table, for example. |
||||||||||||||
|
|
||||||||||||||
| # Table for arena setup | ||||||||||||||
| class Table(RoboSuiteObject): | ||||||||||||||
| """Table in environment.""" | ||||||||||||||
| isTable: True | ||||||||||||||
| width: DEFAULTS['table_width'] | ||||||||||||||
| length: DEFAULTS['table_length'] | ||||||||||||||
| height: DEFAULTS['table_thickness'] | ||||||||||||||
| position: (0, 0, DEFAULTS['table_height']) | ||||||||||||||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This should not be necessary if you create the table with |
||||||||||||||
|
|
||||||||||||||
| # Base class for manipulable objects | ||||||||||||||
| class ManipulationObject(RoboSuiteObject): | ||||||||||||||
| """Base class for objects that can be manipulated.""" | ||||||||||||||
| color: DEFAULTS['default_color'] | ||||||||||||||
|
|
||||||||||||||
| # Primitive shape objects (matching RoboSuite's naming) | ||||||||||||||
| class Box(ManipulationObject): | ||||||||||||||
| """Box object.""" | ||||||||||||||
| objectType: "Box" | ||||||||||||||
| width: DEFAULTS['object_size'] | ||||||||||||||
| length: DEFAULTS['object_size'] | ||||||||||||||
| height: DEFAULTS['object_size'] | ||||||||||||||
|
|
||||||||||||||
| class Ball(ManipulationObject): | ||||||||||||||
| """Ball/sphere object.""" | ||||||||||||||
| objectType: "Ball" | ||||||||||||||
| radius: DEFAULTS['object_size'] | ||||||||||||||
| width: DEFAULTS['object_size'] * 2 | ||||||||||||||
| length: DEFAULTS['object_size'] * 2 | ||||||||||||||
| height: DEFAULTS['object_size'] * 2 | ||||||||||||||
|
Comment on lines
+95
to
+97
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
And likewise for the other shapes below. |
||||||||||||||
|
|
||||||||||||||
| class Cylinder(ManipulationObject): | ||||||||||||||
| """Cylinder object.""" | ||||||||||||||
| objectType: "Cylinder" | ||||||||||||||
| width: DEFAULTS['object_size'] * 2 | ||||||||||||||
| length: DEFAULTS['object_size'] * 2 | ||||||||||||||
| height: DEFAULTS['object_size'] * 4 | ||||||||||||||
|
|
||||||||||||||
| class Capsule(ManipulationObject): | ||||||||||||||
| """Capsule object.""" | ||||||||||||||
| objectType: "Capsule" | ||||||||||||||
| width: DEFAULTS['object_size'] * 1.5 | ||||||||||||||
| length: DEFAULTS['object_size'] * 1.5 | ||||||||||||||
| height: DEFAULTS['object_size'] * 3 | ||||||||||||||
|
|
||||||||||||||
| # Complex objects (matching RoboSuite's naming) | ||||||||||||||
| class Milk(ManipulationObject): | ||||||||||||||
| """Milk carton object.""" | ||||||||||||||
| objectType: "Milk" | ||||||||||||||
|
|
||||||||||||||
| class Cereal(ManipulationObject): | ||||||||||||||
| """Cereal box object.""" | ||||||||||||||
| objectType: "Cereal" | ||||||||||||||
|
|
||||||||||||||
| class Can(ManipulationObject): | ||||||||||||||
| """Can object.""" | ||||||||||||||
| objectType: "Can" | ||||||||||||||
|
|
||||||||||||||
| class Bread(ManipulationObject): | ||||||||||||||
| """Bread object.""" | ||||||||||||||
| objectType: "Bread" | ||||||||||||||
|
|
||||||||||||||
| class Bottle(ManipulationObject): | ||||||||||||||
| """Bottle object.""" | ||||||||||||||
| objectType: "Bottle" | ||||||||||||||
|
|
||||||||||||||
| class Hammer(ManipulationObject): | ||||||||||||||
| """Hammer object.""" | ||||||||||||||
| objectType: "Hammer" | ||||||||||||||
|
|
||||||||||||||
| class SquareNut(ManipulationObject): | ||||||||||||||
| """Square nut object.""" | ||||||||||||||
| objectType: "SquareNut" | ||||||||||||||
|
|
||||||||||||||
| class RoundNut(ManipulationObject): | ||||||||||||||
| """Round nut object.""" | ||||||||||||||
| objectType: "RoundNut" | ||||||||||||||
|
|
||||||||||||||
| # Robots (matching RoboSuite's naming) | ||||||||||||||
| class Robot(RoboSuiteObject): | ||||||||||||||
| """Base robot class.""" | ||||||||||||||
| robot_type: "Panda" | ||||||||||||||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. For consistency with Scenic, please use camel case for these properties, e.g. |
||||||||||||||
| gripper_type: "default" | ||||||||||||||
| controller_config: None | ||||||||||||||
| initial_qpos: None | ||||||||||||||
| base_type: "default" | ||||||||||||||
| width: DEFAULTS['robot_width'] | ||||||||||||||
| length: DEFAULTS['robot_length'] | ||||||||||||||
| height: DEFAULTS['robot_height'] | ||||||||||||||
|
|
||||||||||||||
| # Dynamic properties | ||||||||||||||
| joint_positions[dynamic]: [] | ||||||||||||||
| eef_pos[dynamic]: [0, 0, 0] | ||||||||||||||
| gripper_state[dynamic]: [0, 0] | ||||||||||||||
|
|
||||||||||||||
| class Panda(Robot): | ||||||||||||||
| """Franka Emika Panda robot.""" | ||||||||||||||
| robot_type: "Panda" | ||||||||||||||
| gripper_type: "PandaGripper" | ||||||||||||||
|
|
||||||||||||||
| class UR5e(Robot): | ||||||||||||||
| """Universal Robots UR5e.""" | ||||||||||||||
| robot_type: "UR5e" | ||||||||||||||
| gripper_type: "Robotiq85Gripper" | ||||||||||||||
|
|
||||||||||||||
| class Sawyer(Robot): | ||||||||||||||
| """Rethink Robotics Sawyer.""" | ||||||||||||||
| robot_type: "Sawyer" | ||||||||||||||
| gripper_type: "RethinkGripper" | ||||||||||||||
|
|
||||||||||||||
| class Jaco(Robot): | ||||||||||||||
| """Kinova Jaco robot.""" | ||||||||||||||
| robot_type: "Jaco" | ||||||||||||||
| gripper_type: "JacoThreeFingerGripper" | ||||||||||||||
|
|
||||||||||||||
| class IIWA(Robot): | ||||||||||||||
| """KUKA IIWA robot.""" | ||||||||||||||
| robot_type: "IIWA" | ||||||||||||||
| gripper_type: "Robotiq140Gripper" | ||||||||||||||
|
|
||||||||||||||
| # Behavior Library | ||||||||||||||
| behavior OpenGripper(steps=DEFAULTS['gripper_open_steps']): | ||||||||||||||
| """Open gripper over multiple steps.""" | ||||||||||||||
| for _ in range(steps): | ||||||||||||||
| take OSCPositionAction(gripper=-1) | ||||||||||||||
|
|
||||||||||||||
| behavior CloseGripper(steps=DEFAULTS['gripper_close_steps']): | ||||||||||||||
| """Close gripper over multiple steps.""" | ||||||||||||||
| for _ in range(steps): | ||||||||||||||
| take OSCPositionAction(gripper=1) | ||||||||||||||
|
|
||||||||||||||
| behavior MoveToPosition(target_pos, | ||||||||||||||
| tolerance=DEFAULTS['position_tolerance'], | ||||||||||||||
| max_steps=DEFAULTS['max_control_steps'], | ||||||||||||||
| gain=DEFAULTS['control_gain']): | ||||||||||||||
| """Move end-effector to target position.""" | ||||||||||||||
| for _ in range(max_steps): | ||||||||||||||
| eef_pos = self.eef_pos | ||||||||||||||
| error = [target_pos[i] - eef_pos[i] for i in range(3)] | ||||||||||||||
|
|
||||||||||||||
| if sum(e**2 for e in error)**0.5 < tolerance: | ||||||||||||||
| return | ||||||||||||||
|
|
||||||||||||||
| limit = DEFAULTS['control_limit'] | ||||||||||||||
| delta = [max(-limit, min(limit, e * gain)) for e in error] | ||||||||||||||
| take OSCPositionAction(position_delta=delta, gripper=-1) | ||||||||||||||
|
|
||||||||||||||
| behavior MoveAboveObject(target_object, height_offset=0.1): | ||||||||||||||
| """Move above a tracked object.""" | ||||||||||||||
| target_pos = [target_object.position.x, | ||||||||||||||
| target_object.position.y, | ||||||||||||||
| target_object.position.z + height_offset] | ||||||||||||||
| do MoveToPosition(target_pos) | ||||||||||||||
|
|
||||||||||||||
| behavior MoveToGrasp(target_object, grasp_offset=0.02): | ||||||||||||||
| """Move to grasp position for object.""" | ||||||||||||||
| target_pos = [target_object.position.x, | ||||||||||||||
| target_object.position.y, | ||||||||||||||
| target_object.position.z - grasp_offset] | ||||||||||||||
| do MoveToPosition(target_pos, tolerance=0.01) | ||||||||||||||
|
|
||||||||||||||
| behavior LiftToHeight(target_height=1.0, max_steps=DEFAULTS['max_lift_steps']): | ||||||||||||||
| """Lift to absolute height.""" | ||||||||||||||
| for _ in range(max_steps): | ||||||||||||||
| eef_pos = self.eef_pos | ||||||||||||||
| error = [0, 0, target_height - eef_pos[2]] | ||||||||||||||
|
|
||||||||||||||
| if abs(error[2]) < DEFAULTS['height_tolerance']: | ||||||||||||||
| return | ||||||||||||||
|
|
||||||||||||||
| limit = DEFAULTS['control_limit'] | ||||||||||||||
| gain = DEFAULTS['control_gain'] | ||||||||||||||
| delta = [max(-limit, min(limit, e * gain)) for e in error] | ||||||||||||||
| take OSCPositionAction(position_delta=delta, gripper=1) | ||||||||||||||
|
|
||||||||||||||
| behavior PickObject(target_object): | ||||||||||||||
| """Pick up a specific object.""" | ||||||||||||||
| do OpenGripper() | ||||||||||||||
| do MoveAboveObject(target_object) | ||||||||||||||
| do MoveToGrasp(target_object) | ||||||||||||||
| do CloseGripper() | ||||||||||||||
|
|
||||||||||||||
| behavior PickAndLift(target_object, height=1.05): | ||||||||||||||
| """Complete pick and lift for specific object.""" | ||||||||||||||
| do PickObject(target_object) | ||||||||||||||
| do LiftToHeight(height) | ||||||||||||||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.