# Copyright 2023, Junjia LIU, jjliu@mae.cuhk.edu.hk
#
# Licensed under the 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
#
# https://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.
import numpy as np
from rofunc.simulator.base_sim import RobotSim
[docs]class QbSoftHandSim(RobotSim):
def __init__(self, args):
super().__init__(args)
[docs] def setup_robot_dof_prop(self, gym=None, envs=None, robot_asset=None, robot_handles=None):
from isaacgym import gymapi
gym = self.gym if gym is None else gym
envs = self.envs if envs is None else envs
robot_asset = self.robot_asset if robot_asset is None else robot_asset
robot_handles = self.robot_handles if robot_handles is None else robot_handles
# configure robot dofs
robot_dof_props = gym.get_asset_dof_properties(robot_asset)
robot_lower_limits = robot_dof_props["lower"]
robot_upper_limits = robot_dof_props["upper"]
robot_ranges = robot_upper_limits - robot_lower_limits
robot_mids = 0.3 * (robot_upper_limits + robot_lower_limits)
robot_dof_props["driveMode"][:].fill(gymapi.DOF_MODE_POS)
robot_dof_props["stiffness"][:].fill(1000.0)
robot_dof_props["damping"][:].fill(180.0)
# default dof states and position targets
robot_num_dofs = gym.get_asset_dof_count(robot_asset)
default_dof_pos = np.zeros(robot_num_dofs, dtype=np.float32)
# default_dof_pos[:] = robot_mids[:]
default_dof_state = np.zeros(robot_num_dofs, gymapi.DofState.dtype)
default_dof_state["pos"] = default_dof_pos
# # send to torch
# default_dof_pos_tensor = to_torch(default_dof_pos, device=device)
for i in range(len(envs)):
# set dof properties
gym.set_actor_dof_properties(envs[i], robot_handles[i], robot_dof_props)
# set initial dof states
gym.set_actor_dof_states(envs[i], robot_handles[i], default_dof_state, gymapi.STATE_ALL)
# set initial position targets
gym.set_actor_dof_position_targets(envs[i], robot_handles[i], default_dof_pos)
[docs] def show(self, visual_obs_flag=False, camera_props=None, attached_body=None, local_transform=None):
"""
Visualize the CURI robot
:param visual_obs_flag: if True, show visual observation
:param camera_props: If visual_obs_flag is True, use this camera_props to config the camera
:param attached_body: If visual_obs_flag is True, use this to refer the body the camera attached to
:param local_transform: If visual_obs_flag is True, use this local transform to adjust the camera pose
"""
from isaacgym import gymapi
if visual_obs_flag:
# Setup a first-person camera embedded in CURI's head
if camera_props is None:
# Camera Sensor
camera_props = gymapi.CameraProperties()
camera_props.width = 1280
camera_props.height = 1280
if attached_body is None:
attached_body = "head_link2"
if local_transform is None:
local_transform = gymapi.Transform()
local_transform.p = gymapi.Vec3(0.12, 0, 0.18)
local_transform.r = gymapi.Quat.from_axis_angle(gymapi.Vec3(1, 0, 0), np.radians(90.0)) * \
gymapi.Quat.from_axis_angle(gymapi.Vec3(0, 1, 0), np.radians(-90.0))
super().show(visual_obs_flag=visual_obs_flag, camera_props=camera_props, attached_body=attached_body,
local_transform=local_transform)
[docs] def update_robot(self, traj, attractor_handles, axes_geom, sphere_geom, index, verbose=True):
from isaacgym import gymutil
for i in range(self.num_envs):
# Update attractor target from current franka state
attractor_properties = self.gym.get_attractor_properties(self.envs[i], attractor_handles[i])
pose = attractor_properties.target
# pose.p: (x, y, z), pose.r: (w, x, y, z)
pose.p.x = traj[index, 0]
pose.p.y = traj[index, 1]
pose.p.z = traj[index, 2]
pose.r.w = traj[index, 6]
pose.r.x = traj[index, 3]
pose.r.y = traj[index, 4]
pose.r.z = traj[index, 5]
self.gym.set_attractor_target(self.envs[i], attractor_handles[i], pose)
if verbose:
# Draw axes and sphere at attractor location
gymutil.draw_lines(axes_geom, self.gym, self.viewer, self.envs[i], pose)
gymutil.draw_lines(sphere_geom, self.gym, self.viewer, self.envs[i], pose)
[docs] def run_traj(self, traj, attracted_rigid_bodies=None, update_freq=0.001, verbose=True, **kwargs):
if attracted_rigid_bodies is None:
attracted_rigid_bodies = ["left_hand", "right_hand"]
self.run_traj_multi_rigid_bodies(traj, attracted_rigid_bodies, update_freq=update_freq, verbose=verbose, **kwargs)