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

Support tele-op for Franka Kitchen environments ("vel" mode) #142

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

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions robohive/envs/multi_task/common/kitchen/franka_kitchen.xml
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@


<!-- Robot -->
<site name='ee_target' type='box' size='.03 .07 .04' pos='-0.4 0.4 2.1' group='1' rgba='0 1 .4 0' euler="0 3.14 3.14"/>
sriramsk1999 marked this conversation as resolved.
Show resolved Hide resolved
<body name="chef" pos='0. 0 1.8' euler='0 0 1.57'>
<geom type='cylinder' size='.120 .90' pos='-.04 0 -0.90' class='panda_viz'/>
<include file="../../../../simhive/franka_sim/assets/chain0.xml"/>
Expand Down
2 changes: 1 addition & 1 deletion robohive/robot/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -574,7 +574,7 @@ def normalize_actions(self, controls, out_space='sim', unnormalize=False):
act_rng = (actuator['pos_range'][1]-actuator['pos_range'][0])/2.0
elif self._act_mode == "vel":
act_mid = (actuator['vel_range'][1]+actuator['vel_range'][0])/2.0
act_rng = (actuator['vel_range'][1]-actuator['pos_range'][0])/2.0
act_rng = (actuator['vel_range'][1]-actuator['vel_range'][0])/2.0
vikashplus marked this conversation as resolved.
Show resolved Hide resolved
else:
raise TypeError("Unknown act mode: {}".format(self._act_mode))

Expand Down
28 changes: 21 additions & 7 deletions robohive/tutorials/ee_teleop.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
- NOTE: Tutorial is written for franka arm and robotiq gripper. This demo is a tutorial, not a generic functionality for any any environment
EXAMPLE:\n
- python tutorials/ee_teleop.py -e rpFrankaRobotiqData-v0\n
- python tutorials/ee_teleop.py -e FK1_LightOnFixed-v4\n
"""
# TODO: (1) Enforce pos/rot/grip limits (b) move gripper to delta commands

Expand Down Expand Up @@ -251,12 +252,25 @@ def main(env_name, env_args, reset_noise, action_noise, input_device, output, ho
if ik_result.success==False:
print(f"IK(t:{i_step}):: Status:{ik_result.success}, total steps:{ik_result.steps}, err_norm:{ik_result.err_norm}")
else:
act[:7] = ik_result.qpos[:7]
act[7:] = gripper_state
if action_noise:
act = act + env.env.np_random.uniform(high=action_noise, low=-action_noise, size=len(act)).astype(act.dtype)
if env.normalize_act:
act = env.env.robot.normalize_actions(act)
if env.env.robot._act_mode == "pos":
act[:7] = ik_result.qpos[:7]
act[7:] = gripper_state
if action_noise:
act = act + env.env.np_random.uniform(high=action_noise, low=-action_noise, size=len(act)).astype(act.dtype)
if env.normalize_act:
act = env.env.robot.normalize_actions(act)
elif env.env.robot._act_mode == "vel":
curr_qpos = env.sim.get_state()['qpos'][:7]
target_qpos = ik_result.qpos[:7]
qvel = (target_qpos - curr_qpos)
act[:7] = qvel
act[7:] = gripper_state
if action_noise:
act = act + env.env.np_random.uniform(high=action_noise, low=-action_noise, size=len(act)).astype(act.dtype)
# if env.normalize_act:
vikashplus marked this conversation as resolved.
Show resolved Hide resolved
# act = env.env.robot.normalize_actions(act)
else:
raise TypeError("Unknown act mode: {}".format(env.env.robot._act_mode))

# nan actions for last log entry
act = np.nan*np.ones(env.action_space.shape) if i_step == horizon else act
Expand Down Expand Up @@ -294,4 +308,4 @@ def main(env_name, env_args, reset_noise, action_noise, input_device, output, ho


if __name__ == '__main__':
main()
main()
Loading