rofunc.simulator.curi_sim#

1.  Module Contents#

1.1.  Classes#

CURISim

1.2.  Functions#

orientation_error

1.3.  API#

rofunc.simulator.curi_sim.orientation_error(desired, current)[source]#
class rofunc.simulator.curi_sim.CURISim(args)[source]#

Bases: rofunc.simulator.base_sim.RobotSim

Initialization

Initialize the robot-centered simulator

Parameters:

args – arguments

setup_robot_dof_prop()[source]#
add_head_embedded_camera(camera_props=None, attached_body=None, local_transform=None)[source]#
show(visual_obs_flag=False)[source]#

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

update_robot(traj, attractor_handles, axes_geom, sphere_geom, index, verbose=True)[source]#
control_ik(dpose)[source]#
control_osc(dpose, hand_vel, massmatrix, dof_indices)[source]#
run_traj(traj, attracted_rigid_bodies=None, update_freq=0.001, verbose=True, **kwargs)[source]#
run_traj_multi_rigid_bodies_with_interference(traj: List, intf_index: List, intf_mode: str, intf_forces=None, intf_torques=None, intf_joints: List = None, intf_efforts: isaacgym.torch_utils.np.ndarray = None, attracted_rigid_bodies: List = None, update_freq=0.001, save_name=None)[source]#

Run the trajectory with multiple rigid bodies with interference, the default is to run the trajectory with the left and right hand of the CURI robot. Args:

traj: a list of trajectories, each trajectory is a numpy array of shape (N, 7) intf_index: a list of the timing indices of the interference occurs intf_mode: the mode of the interference, [“actor_dof_efforts”, “body_forces”, “body_force_at_pos”] intf_forces: a tensor of shape (num_envs, num_bodies, 3), the interference forces applied to the bodies intf_torques: a tensor of shape (num_envs, num_bodies, 3), the interference torques applied to the bodies intf_joints: [list], e.g. [“panda_left_hand”] intf_efforts: array containing the efforts for all degrees of freedom of the actor. attracted_rigid_bodies: [list], e.g. [“panda_left_hand”, “panda_right_hand”] update_freq: the frequency of updating the robot pose

run_hand_reach_target_pose(target_pose, attracted_hand=None, update_freq=0.001, verbose=True)[source]#
run_with_text_commands(verbose=True)[source]#