Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Push Environments #88

Open
wants to merge 2 commits into
base: dev
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
76 changes: 74 additions & 2 deletions robohive/envs/arms/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ def register_visual_envs(encoder_type):
'robot_site_name': "end_effector",
'object_site_name': "sugarbox",
'target_site_name': "target",
'target_xyz_range': {'high':[-.4, 0.5, 0.78], 'low':[-.4, 0.5, 0.78]}
'target_xyz_range': {'high': [0.5, 0.4, 0.78], 'low': [0.5, 0.4, 0.78]}
}
)

Expand All @@ -91,7 +91,79 @@ def register_visual_envs(encoder_type):
'robot_site_name': "end_effector",
'object_site_name': "sugarbox",
'target_site_name': "target",
'target_xyz_range': {'high':[0.4, 0.5, 0.78], 'low':[-.4, .4, 0.78]}
'target_xyz_range': {'high': [0.5, 0.4, 0.78], 'low': [0.4, -0.4, 0.78]}
}
)

register(
# Init position: [0.51,0.23,0.98]
# Init euler: [-np.pi/4+0.3, np.pi+0.3, -3*np.pi/4,]
id='FrankaBinPush-v0',
entry_point='robohive.envs.arms.push_base_v0:PushBaseV0',
max_episode_steps=50, #50steps*40Skip*2ms = 4s
kwargs={
'model_path': curr_dir+'/franka/assets/franka_bin_push_v0.xml',
'config_path': curr_dir+'/franka/assets/franka_bin_push_v0.config',
'robot_site_name': "end_effector",
'object_site_name': "obj0",
'obj_pos_limits': {'high':[0.52, 0.126, 0.955], 'low':[0.48, 0.125, 0.945]},
'target_site_name': "target",
'target_xyz_range': {'high':[0.5, -0.22, 1.085], 'low':[0.5, -0.22, 1.085]},
'pos_limits': {'eef_low': [0.315, -0.22, 0.89, -0.485, 3.14, -2.36, 0.4],
'eef_high': [0.695, 0.275, 1.125, -0.485, 3.14, -2.36, 0.4]
},
'vel_limits': {'eef':[0.15, 0.15, 0.15],
'jnt': [0.15, 0.25, 0.1, 0.25, 0.1, 0.25, 0.2, 1.0]
},
'init_qpos': [0.534, 0.401, 0.0, -1.971, -0.457, 0.490, 1.617, 0.4, 0.4],
}
)

register(
# Init position: [0.36, 0.0, 1.34]
# Init euler: [3.14, 0.5, -0.8,]
id='FrankaHangPush-v0',
entry_point='robohive.envs.arms.push_base_v0:PushBaseV0',
max_episode_steps=50, #50steps*40Skip*2ms = 4s
kwargs={
'model_path': curr_dir+'/franka/assets/franka_hang_push_v0.xml',
'config_path': curr_dir+'/franka/assets/franka_hang_push_v0.config',
'robot_site_name': "end_effector",
'object_site_name': "obj0",
'obj_pos_limits': {'high':[0.46, 0.01, 1.31], 'low':[0.44, -0.01, 1.3]},
'target_site_name': "target",
'target_xyz_range': {'high':[0.621, 0.0, 1.333], 'low':[0.621, 0.0, 1.333]},
'pos_limits': {'eef_low': [0.3, -0.1, 1.25, 3.14, 0.5, -0.8, 0.2],
'eef_high': [0.8, 0.1, 1.5, 3.14, 0.5, -0.8, 0.2]
},
'vel_limits': {'eef':[0.15, 0.15, 0.15],
'jnt': [0.15, 0.25, 0.1, 0.25, 0.1, 0.25, 0.2, 1.0]
},
'init_qpos': [0.0227, -0.9291, -0.014, -2.5568, -0.029, 0.5052, -0.783, 0.2, 0.2],
}
)

register(
# Init position: [0.36, 0.0, 1.34]
# Init euler: [3.14, 0.5, -0.8,]
id='FrankaPlanarPush-v0',
entry_point='robohive.envs.arms.push_base_v0:PushBaseV0',
max_episode_steps=50, #50steps*40Skip*2ms = 4s
kwargs={
'model_path': curr_dir+'/franka/assets/franka_planar_push_v0.xml',
'config_path': curr_dir+'/franka/assets/franka_planar_push_v0.config',
'robot_site_name': "end_effector",
'object_site_name': "obj0",
'obj_pos_limits': {'high':[0.50, 0.31, 0.855], 'low':[0.46, 0.29, 0.845]},
'target_site_name': "target",
'target_xyz_range': {'high':[0.48, -0.1, 0.845], 'low':[0.48, -0.1, 0.845]},
'pos_limits': {'eef_low': [0.3, -0.4, 0.865, 3.14, 0.0, 0.28, 0.2],
'eef_high': [0.8, 0.4, 0.965, 3.14, 0.0, 1.28, 0.2]
},
'vel_limits': {'eef':[0.15, 0.15, 0.15],
'jnt': [0.15, 0.25, 0.1, 0.25, 0.1, 0.25, 0.2, 1.0]
},
'init_qpos': [0.665, 0.567, 0.0, -1.999, 0.0, 0.9172, 1.4541, 0.2, 0.2],
}
)

Expand Down
89 changes: 89 additions & 0 deletions robohive/envs/arms/franka/assets/franka_bin_push_v0.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
{
# device1: sensors, actuators
'franka':{
'interface': {'type': 'franka', 'ip_address':'172.16.0.1', 'gain_scale': 0.5},
'sensor':[
{'range':(-2.9, 2.9), 'noise':0.05, 'hdr_id':0, 'scale':1, 'offset':0, 'name':'fr_arm_jp1'},
{'range':(-1.8, 1.8), 'noise':0.05, 'hdr_id':1, 'scale':1, 'offset':0, 'name':'fr_arm_jp2'},
{'range':(-2.9, 2.9), 'noise':0.05, 'hdr_id':2, 'scale':1, 'offset':0, 'name':'fr_arm_jp3'},
{'range':(-3.1, 0.0), 'noise':0.05, 'hdr_id':3, 'scale':1, 'offset':0, 'name':'fr_arm_jp4'},
{'range':(-2.9, 2.9), 'noise':0.05, 'hdr_id':4, 'scale':1, 'offset':0, 'name':'fr_arm_jp5'},
{'range':(-1.7, 3.8), 'noise':0.05, 'hdr_id':5, 'scale':1, 'offset':-np.pi/2, 'name':'fr_arm_jp6'},
{'range':(-2.9, 2.9), 'noise':0.05, 'hdr_id':6, 'scale':1, 'offset':-np.pi/4, 'name':'fr_arm_jp7'},

],

'actuator':[
{'pos_range':(-2.9671, 2.9671), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':0, 'scale':1, 'offset':0, 'name':'panda0_joint1'},
{'pos_range':(-1.8326, 1.8326), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':1, 'scale':1, 'offset':0, 'name':'panda0_joint2'},
{'pos_range':(-2.9671, 2.9671), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':2, 'scale':1, 'offset':0, 'name':'panda0_joint3'},
{'pos_range':(-3.1416, 0.0000), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':3, 'scale':1, 'offset':0, 'name':'panda0_joint4'},
{'pos_range':(-2.9671, 2.9671), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':4, 'scale':1, 'offset':0, 'name':'panda0_joint5'},
{'pos_range':(-1.6600, 2.1817), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':5, 'scale':1, 'offset':np.pi/2, 'name':'panda0_joint6'},
{'pos_range':(-2.9671, 2.9671), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':6, 'scale':1, 'offset':np.pi/4, 'name':'panda0_joint7'},
]
},

'robotiq':{
'interface': {'type': 'robotiq', 'ip_address':'172.16.0.3'},
'sensor':[
{'range':(0, 0.834), 'noise':0.0, 'hdr_id':0, 'name':'robotiq_2f_85', 'scale':-9.81, 'offset':0.834},
],
'actuator':[
{'pos_range':(0, 1), 'vel_range':(-20*np.pi/4, 20*np.pi/4), 'hdr_id':0, 'name':'robotiq_2f_85', 'scale':-0.085, 'offset':0.085},
]
},

'right_cam':{
'interface': {'type': 'realsense',
'rgb_topic':'realsense_819112073358/color/image_raw',
'd_topic': 'realsense_819112073358/depth_uncolored/image_raw',
'data_type':'rgbd'},
'sensor':[],
'cams': [
{'range':(0, 255), 'noise':0.00, 'hdr_id':'rgb', 'scale':1, 'offset':0, 'name':'/color/image_raw'},
{'range':(0, 255), 'noise':0.00, 'hdr_id':'d', 'scale':0.05, 'offset':0, 'name':'/depth_mono/image_raw'},
],
'actuator':[]
},

'left_cam':{
'interface': {'type': 'realsense',
'rgb_topic':'realsense_948522071060/color/image_raw',
'd_topic':'realsense_948522071060/depth_uncolored/image_raw',
'data_type':'rgbd'},
'sensor':[],
'cams': [
{'range':(0, 255), 'noise':0.00, 'hdr_id':'rgb', 'scale':1, 'offset':0, 'name':'/color/image_raw'},
{'range':(0, 255), 'noise':0.00, 'hdr_id':'d', 'scale':0.05, 'offset':0, 'name':'/depth_mono/image_raw'},
],
'actuator':[]
},

'top_cam':{
'interface': {'type': 'realsense',
'rgb_topic':'realsense_815412071252/color/image_raw',
'd_topic': 'realsense_815412071252/depth_uncolored/image_raw',
'data_type':'rgbd'},
'sensor':[],
'cams': [
{'range':(0, 255), 'noise':0.00, 'hdr_id':'rgb', 'scale':1, 'offset':0, 'name':'/color/image_color'},
{'range':(0, 255), 'noise':0.00, 'hdr_id':'d', 'scale':0.05, 'offset':0, 'name':'/depth_mono/image_raw'},
],
'actuator':[]
},

'Franka_wrist_cam':{
'interface': {'type': 'realsense',
'rgb_topic':'realsense_137222072789/color/image_raw',
'd_topic': 'realsense_137222072789/depth_uncolored/image_raw',
'data_type':'rgbd'},
'sensor':[],
'cams': [
{'range':(0, 255), 'noise':0.00, 'hdr_id':'rgb', 'scale':1, 'offset':0, 'name':'/color/image_color'},
{'range':(0, 255), 'noise':0.00, 'hdr_id':'d', 'scale':0.05, 'offset':0, 'name':'/depth_mono/image_raw'},
],
'actuator':[]
},

}
74 changes: 74 additions & 0 deletions robohive/envs/arms/franka/assets/franka_bin_push_v0.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
<mujoco model="RoboPen-BinPush">
<!-- =================================================
Copyright 2022 Vikash Kumar
Model :: BinPick (MuJoCoV2.0)
Author :: Vikash Kumar ([email protected])
source :: https://github.com/vikashplus/robohive
License :: Under Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
====================================================== -->

<size njmax='1000' nconmax='1000'/>

<include file="../../../../simhive/scene_sim/topfloor_scene.xml"/>
<include file="../../../../simhive/furniture_sim/simpleTable/simpleTable_asset.xml"/>
<include file="../../../../simhive/furniture_sim/ventionTable/ventionTable_asset.xml"/>
<include file="../../../../simhive/franka_sim/assets/assets.xml"/>
<include file="../../../../simhive/franka_sim/assets/actuator0.xml"/>
<include file="../../../../simhive/robotiq_sim/assets/assets.xml"/>
<include file="../../../../simhive/furniture_sim/bin/bin_asset.xml"/>

<compiler inertiafromgeom="auto" inertiagrouprange="3 4" angle="radian" meshdir="../../../../simhive/franka_sim" texturedir="../../../../simhive/franka_sim"/>

<worldbody>

<camera name='left_cam' pos='-0.5 1.2 1.8' quat='-0.32 -0.22 0.49 0.78'/>
<camera name='right_cam' pos='-0.5 -1.2 1.8' quat='0.76 0.5 -0.21 -0.35'/>
<camera name='top_cam' pos='0.5 0 2.2' euler='0 0 -1.57'/>
<site name='workspace' type='box' size='.6 .375 .25' pos='0 0.475 1.0' group='3' rgba='0 0 .4 .2'/>

<!-- Franka Arm-->
<body pos='0 0 .823' euler='0 0 0'>
<include file="../../../../simhive/franka_sim/assets/chain0_nogripper.xml"/>
</body>

<!-- Robotiq Hand-->
<body name="ee_mount" pos="0 0 .11" euler="0 0 0">
<include file="../../../../simhive/robotiq_sim/assets/chain.xml"/>
</body>

<!-- Tables -->
<body name="ventiontable" pos='-0.3 0 0' euler='0 0 1.57'>
<include file="../../../../simhive/furniture_sim/ventionTable/ventionTable_body.xml"/>
</body>
<body name="scenetable" pos='0.49 0 0.065' euler="0 0 1.57">
<include file="../../../../simhive/furniture_sim/simpleTable/simpleMarbleTable_body.xml"/>
</body>

<!-- tasks details added here via include-->
<body name="busbin1" pos='0.5 0.0 0.935' euler='-0.4 0.0 0.0'>
<include file="../../../../simhive/furniture_sim/bin/busbin1_body.xml"/>
</body>
<site name="busbin_top" size="0.01" rgba="0.3 .95 .3 0" pos="0.5 -0.22 1.085"/>

<site name='target' type='sphere' size='.02' pos='0.5 -0.22 1.085' group='1' rgba='.1 .8 .2 0.0'/>

<site name='pos_limit_low' type="sphere" size="0.02" pos='0.315 -0.22 1.125' group="1" rgba="0.1 0.8 0.2 0" />
<site name='pos_limit_high' type="sphere" size="0.02" pos='0.695 0.275 0.89' group="1" rgba="0.1 0.8 0.2 0" />

<body name="obj0" pos="0.5 0.125 0.945" euler='0 0 1.57'>
<inertial pos="0 0 0" mass="0.088" diaginertia="0.0001 0.0001 0.0001" />
<geom type="capsule" size="0.02 0.04" pos="0.0 0.0 0.0" euler="1.57 0 0" group="1" rgba=".3 .7 .8 1" mass=".100"/>
<site name="obj0" size="0.01" pos="0 0 0"/>
<freejoint name="obj0"/>
</body>

</worldbody>

<tendon>
<spatial width="0.002" rgba=".95 .3 .3 0" limited="true" range="0 0.4">
<site site="busbin_top"/>
<site site="obj0"/>
</spatial>
</tendon>

</mujoco>
89 changes: 89 additions & 0 deletions robohive/envs/arms/franka/assets/franka_hang_push_v0.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
{
# device1: sensors, actuators
'franka':{
'interface': {'type': 'franka', 'ip_address':'172.16.0.1', 'gain_scale': 0.5},
'sensor':[
{'range':(-2.9, 2.9), 'noise':0.05, 'hdr_id':0, 'scale':1, 'offset':0, 'name':'fr_arm_jp1'},
{'range':(-1.8, 1.8), 'noise':0.05, 'hdr_id':1, 'scale':1, 'offset':0, 'name':'fr_arm_jp2'},
{'range':(-2.9, 2.9), 'noise':0.05, 'hdr_id':2, 'scale':1, 'offset':0, 'name':'fr_arm_jp3'},
{'range':(-3.1, 0.0), 'noise':0.05, 'hdr_id':3, 'scale':1, 'offset':0, 'name':'fr_arm_jp4'},
{'range':(-2.9, 2.9), 'noise':0.05, 'hdr_id':4, 'scale':1, 'offset':0, 'name':'fr_arm_jp5'},
{'range':(-1.7, 3.8), 'noise':0.05, 'hdr_id':5, 'scale':1, 'offset':-np.pi/2, 'name':'fr_arm_jp6'},
{'range':(-2.9, 2.9), 'noise':0.05, 'hdr_id':6, 'scale':1, 'offset':-np.pi/4, 'name':'fr_arm_jp7'},

],

'actuator':[
{'pos_range':(-2.9671, 2.9671), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':0, 'scale':1, 'offset':0, 'name':'panda0_joint1'},
{'pos_range':(-1.8326, 1.8326), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':1, 'scale':1, 'offset':0, 'name':'panda0_joint2'},
{'pos_range':(-2.9671, 2.9671), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':2, 'scale':1, 'offset':0, 'name':'panda0_joint3'},
{'pos_range':(-3.1416, 0.0000), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':3, 'scale':1, 'offset':0, 'name':'panda0_joint4'},
{'pos_range':(-2.9671, 2.9671), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':4, 'scale':1, 'offset':0, 'name':'panda0_joint5'},
{'pos_range':(-1.6600, 2.1817), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':5, 'scale':1, 'offset':np.pi/2, 'name':'panda0_joint6'},
{'pos_range':(-2.9671, 2.9671), 'vel_range':(-4*np.pi/2, 4*np.pi/2), 'hdr_id':6, 'scale':1, 'offset':np.pi/4, 'name':'panda0_joint7'},
]
},

'robotiq':{
'interface': {'type': 'robotiq', 'ip_address':'172.16.0.3'},
'sensor':[
{'range':(0, 0.834), 'noise':0.0, 'hdr_id':0, 'name':'robotiq_2f_85', 'scale':-9.81, 'offset':0.834},
],
'actuator':[
{'pos_range':(0, 1), 'vel_range':(-20*np.pi/4, 20*np.pi/4), 'hdr_id':0, 'name':'robotiq_2f_85', 'scale':-0.085, 'offset':0.085},
]
},

'right_cam':{
'interface': {'type': 'realsense',
'rgb_topic':'realsense_817612071438/color/image_raw',
'd_topic': 'realsense_817612071438/depth_uncolored/image_raw',
'data_type':'rgbd'},
'sensor':[],
'cams': [
{'range':(0, 255), 'noise':0.00, 'hdr_id':'rgb', 'scale':1, 'offset':0, 'name':'/color/image_raw'},
{'range':(0, 255), 'noise':0.00, 'hdr_id':'d', 'scale':0.05, 'offset':0, 'name':'/depth_mono/image_raw'},
],
'actuator':[]
},

'left_cam':{
'interface': {'type': 'realsense',
'rgb_topic':'realsense_923322071682/color/image_raw',
'd_topic':'realsense_923322071682/depth_uncolored/image_raw',
'data_type':'rgbd'},
'sensor':[],
'cams': [
{'range':(0, 255), 'noise':0.00, 'hdr_id':'rgb', 'scale':1, 'offset':0, 'name':'/color/image_raw'},
{'range':(0, 255), 'noise':0.00, 'hdr_id':'d', 'scale':0.05, 'offset':0, 'name':'/depth_mono/image_raw'},
],
'actuator':[]
},

'top_cam':{
'interface': {'type': 'realsense',
'rgb_topic':'realsense_831612071935/color/image_raw',
'd_topic': 'realsense_831612071935/depth_uncolored/image_raw',
'data_type':'rgbd'},
'sensor':[],
'cams': [
{'range':(0, 255), 'noise':0.00, 'hdr_id':'rgb', 'scale':1, 'offset':0, 'name':'/color/image_color'},
{'range':(0, 255), 'noise':0.00, 'hdr_id':'d', 'scale':0.05, 'offset':0, 'name':'/depth_mono/image_raw'},
],
'actuator':[]
},

'Franka_wrist_cam':{
'interface': {'type': 'realsense',
'rgb_topic':'realsense_936322070059/color/image_raw',
'd_topic': 'realsense_936322070059/depth_uncolored/image_raw',
'data_type':'rgbd'},
'sensor':[],
'cams': [
{'range':(0, 255), 'noise':0.00, 'hdr_id':'rgb', 'scale':1, 'offset':0, 'name':'/color/image_color'},
{'range':(0, 255), 'noise':0.00, 'hdr_id':'d', 'scale':0.05, 'offset':0, 'name':'/depth_mono/image_raw'},
],
'actuator':[]
},

}