# Copyright (c) 2022-2024, The Isaac Lab Project Developers.# All rights reserved.## SPDX-License-Identifier: BSD-3-Clause"""This script demonstrates different legged robots... code-block:: bash # Usage ./isaaclab.sh -p source/standalone/demos/quadrupeds.py""""""Launch Isaac Sim Simulator first."""importargparsefromomni.isaac.lab.appimportAppLauncher# add argparse argumentsparser=argparse.ArgumentParser(description="This script demonstrates different legged robots.")# append AppLauncher cli argsAppLauncher.add_app_launcher_args(parser)# parse the argumentsargs_cli=parser.parse_args()# launch omniverse appapp_launcher=AppLauncher(args_cli)simulation_app=app_launcher.app"""Rest everything follows."""importnumpyasnpimporttorchimportomni.isaac.core.utils.primsasprim_utilsimportomni.isaac.lab.simassim_utilsfromomni.isaac.lab.assetsimportArticulation### Pre-defined configs##fromomni.isaac.lab_assets.anymalimportANYMAL_B_CFG,ANYMAL_C_CFG,ANYMAL_D_CFG# isort:skipfromomni.isaac.lab_assets.spotimportSPOT_CFG# isort:skipfromomni.isaac.lab_assets.unitreeimportUNITREE_A1_CFG,UNITREE_GO1_CFG,UNITREE_GO2_CFG# isort:skipfromomni.isaac.lab.assets.articulationimportArticulationCfgimportomni.isaac.lab.simassim_utilsfromomni.isaac.lab.actuatorsimportActuatorNetMLPCfg,DCMotorCfg,ImplicitActuatorCfgdefdefine_origins(num_origins:int,spacing:float)->list[list[float]]:"""Defines the origins of the the scene."""# create tensor based on number of environmentsenv_origins=torch.zeros(num_origins,3)# create a grid of originsnum_cols=np.floor(np.sqrt(num_origins))num_rows=np.ceil(num_origins/num_cols)xx,yy=torch.meshgrid(torch.arange(num_rows),torch.arange(num_cols),indexing="xy")env_origins[:,0]=spacing*xx.flatten()[:num_origins]-spacing*(num_rows-1)/2env_origins[:,1]=spacing*yy.flatten()[:num_origins]-spacing*(num_cols-1)/2env_origins[:,2]=0.0# return the originsreturnenv_origins.tolist()defdesign_scene()->tuple[dict,list[list[float]]]:"""Designs the scene."""fromomni.isaac.lab.actuatorsimportActuatorBaseCfg# Define Dynamixel servo configurationDYNAMIXEL_SERVO_CFG=ActuatorBaseCfg(joint_names_expr=[".*_hip_joint",".*_thigh_joint",".*_calf_joint"],effort_limit=12.0,# Adjust based on the Dynamixel servo usedvelocity_limit=5.0,# Adjust as neededstiffness=1000.0,# Adjust for control stabilitydamping=500.0,# Adjust for better performancefriction=0.1,# Account for any friction if necessary)# Apply this configuration to the Akabeko robotFABO_AKABEKO_CFG=ArticulationCfg(spawn=sim_utils.UsdFileCfg(usd_path="E:/isaac_sim/isaac-sim-4.0.0/MyExtentions/MyTest/data/fabo_jetdog/fabo_jetdog.usd",activate_contact_sensors=True,rigid_props=sim_utils.RigidBodyPropertiesCfg(disable_gravity=False,retain_accelerations=False,linear_damping=0.0,angular_damping=0.0,max_linear_velocity=1000.0,max_angular_velocity=1000.0,max_depenetration_velocity=1.0,),articulation_props=sim_utils.ArticulationRootPropertiesCfg(enabled_self_collisions=False,solver_position_iteration_count=4,solver_velocity_iteration_count=0),),init_state=ArticulationCfg.InitialStateCfg(pos=(0.0,0.0,0.4),joint_pos={".*L_hip_joint":0.1,".*R_hip_joint":-0.1,"F[L,R]_thigh_joint":0.1,"R[L,R]_thigh_joint":0.1,".*_calf_joint":-0.1,},joint_vel={".*":0.0},),soft_joint_pos_limit_factor=0.9,actuators={"base_legs":DYNAMIXEL_SERVO_CFG,# Replace with Dynamixel config},)"""Configuration of Unitree Go2 using DC-Motor actuator model."""# Ground-planecfg=sim_utils.GroundPlaneCfg()cfg.func("/World/defaultGroundPlane",cfg)# Lightscfg=sim_utils.DomeLightCfg(intensity=2000.0,color=(0.75,0.75,0.75))cfg.func("/World/Light",cfg)# Create separate groups called "Origin1", "Origin2", "Origin3"# Each group will have a mount and a robot on top of itorigins=define_origins(num_origins=7,spacing=1.25)# Origin 1 with Anymal Bprim_utils.create_prim("/World/Origin1","Xform",translation=origins[0])# -- Robotanymal_b=Articulation(ANYMAL_B_CFG.replace(prim_path="/World/Origin1/Robot"))# Origin 2 with Anymal Cprim_utils.create_prim("/World/Origin2","Xform",translation=origins[1])# -- Robotanymal_c=Articulation(ANYMAL_C_CFG.replace(prim_path="/World/Origin2/Robot"))# Origin 3 with Anymal Dprim_utils.create_prim("/World/Origin3","Xform",translation=origins[2])# -- Robotanymal_d=Articulation(ANYMAL_D_CFG.replace(prim_path="/World/Origin3/Robot"))# Origin 4 with Unitree A1prim_utils.create_prim("/World/Origin4","Xform",translation=origins[3])# -- Robotunitree_a1=Articulation(UNITREE_A1_CFG.replace(prim_path="/World/Origin4/Robot"))# Origin 5 with Unitree Go1prim_utils.create_prim("/World/Origin5","Xform",translation=origins[4])# -- Robotunitree_go1=Articulation(UNITREE_GO1_CFG.replace(prim_path="/World/Origin5/Robot"))# Origin 6 with Unitree Go2prim_utils.create_prim("/World/Origin6","Xform",translation=origins[5])# -- Robotunitree_go2=Articulation(UNITREE_GO2_CFG.replace(prim_path="/World/Origin6/Robot"))# Origin 7 with Boston Dynamics Spot#prim_utils.create_prim("/World/Origin7", "Xform", translation=origins[6])# -- Robot#spot = Articulation(SPOT_CFG.replace(prim_path="/World/Origin7/Robot"))# Origin 7 with Boston Dynamics Spotprim_utils.create_prim("/World/Origin7","Xform",translation=origins[6])# -- Robotakabeko=Articulation(FABO_AKABEKO_CFG.replace(prim_path="/World/Origin7/Robot"))# return the scene informationscene_entities={"anymal_b":anymal_b,"anymal_c":anymal_c,"anymal_d":anymal_d,"unitree_a1":unitree_a1,"unitree_go1":unitree_go1,"unitree_go2":unitree_go2,#"spot": spot,"akabeko":akabeko,}returnscene_entities,originsdefrun_simulator(sim:sim_utils.SimulationContext,entities:dict[str,Articulation],origins:torch.Tensor):"""Runs the simulation loop."""# Define simulation steppingsim_dt=sim.get_physics_dt()sim_time=0.0count=0# Simulate physicsprint(f"{entities}")whilesimulation_app.is_running():# resetifcount%200==0:# reset counterssim_time=0.0count=0# reset robotsforindex,robotinenumerate(entities.values()):# root stateroot_state=robot.data.default_root_state.clone()root_state[:,:3]+=origins[index]robot.write_root_state_to_sim(root_state)# joint statejoint_pos,joint_vel=robot.data.default_joint_pos.clone(),robot.data.default_joint_vel.clone()robot.write_joint_state_to_sim(joint_pos,joint_vel)# reset the internal staterobot.reset()print("[INFO]: Resetting robots state...")# apply default actions to the quadrupedal robotsforrobotinentities.values():# generate random joint positionsjoint_pos_target=robot.data.default_joint_pos+torch.randn_like(robot.data.joint_pos)*0.1# apply action to the robotrobot.set_joint_position_target(joint_pos_target)# write data to simrobot.write_data_to_sim()# perform stepsim.step()# update sim-timesim_time+=sim_dtcount+=1# update buffersforrobotinentities.values():robot.update(sim_dt)defmain():"""Main function."""# Initialize the simulation contextsim=sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01))# Set main camerasim.set_camera_view(eye=[2.5,2.5,2.5],target=[0.0,0.0,0.0])# design scenescene_entities,scene_origins=design_scene()scene_origins=torch.tensor(scene_origins,device=sim.device)# Play the simulatorsim.reset()# Now we are ready!print("[INFO]: Setup complete...")# Run the simulatorrun_simulator(sim,scene_entities,scene_origins)if__name__=="__main__":# run the main functionmain()# close sim appsimulation_app.close()