Warning

本教程已经过时,不是 5.1 最新版本的,具体代码可能需要修正 但是代码逻辑和类的概念是可以参考的

  1. 代码编程

以 Standalone python 模式运行 Isaac Sim

  • 这两行必须在任何其他的omni相关包导入前执行,否则相关的包路径无法被正确地识别
from isaacsim import SimulationApp
simulation_app = SimulationApp({"headless": False})
  • 使用循环来人为控制Isaac Sim的每次物理步进以及渲染步进
for i in range(3000):
    world.step(render=True)
  • 关闭 Isaac Sim
simulation_app.close()
  1. 创建世界

    • 世界(World):
      • 代表机器人工作的唯一环境
      • World 类是单例的(Singleton),这意味着在运行 Isaac Sim 时只能存在一个 World 实例
      • 通过 World 类,可以处理许多与时间相关的事件,如物理和渲染步进(Step)、添加步进时的回调函数(Callback)、重置整个场景(Scene)以及添加任务(Task)
        • world.add_physics_callback(callback_name="place_holder", callback_fn=func_name)
    • 场景(Scene):
      • World 类的一个属性
      • 管理 USD 舞台(Stage)中已注册到 场景(Scene) 的资产
      • 提供了简洁的 API 来添加(Add)、操作和检查舞台(Stage)中已注册到场景(Scene) 的 USD 资产,并且可以设置这些资产的默认重置状态
        • world.scene.add(user_object)
  2. 创建/导入物体

    • omni.isaac.core.objects 模块包含了用于创建常见形状体(胶囊体、圆锥体、长方体、圆柱体、球体)以及地面,它提供这些常见形状体的仅可视不可碰撞 (Visual)、固定在原处但有碰撞属性 (Fixed)、动力学 (Dynamic) 三个版本
      • 继承 omni,isaac.core.prims.GeometryPrim(_SinglePrimWrapper),因此继承了这个类的各种方法,比如 set/get_world_pose()
      • 其中的一部分还添加了刚体、碰撞体的API,使得具备了相关的方法和属性,例如 get_linear_velocityget_angular_velocity()get_mass()
    # get_object_info.py
    from omni.isaac.core import World
     
    # Instantiate World class
    world = World()
    # Get the DynamicCuboid instance from the scene
    cube = world.scene.get_object("target_cuboid")
    print(cube)
    # Get the world pose of the object
    position, orientation = cube.get_world_pose()
    print(f"Position(x,y,z)={position}")
    print(f"Orientation(qw,qx,qy,qz)={orientation}")
    # Get the linear and angular velocities of the object
    # DynamicCuboid is subclass of RigidPrim, which has the dynamic related methods
    linear_velocity = cube.get_linear_velocity()
    angular_velocity = cube.get_angular_velocity()
    mass = cube.get_mass()
     
    print(f"Linear velocity={linear_velocity}")
    print(f"Angular velocity={angular_velocity}")
    print(f"Mass={mass}")
  3. 导入机器人

    • 关节树类(class Articulation):
      • 在普通 object(_SinglePrimWrapper)的基础上提供了一系列的和机器人相关的类方法和属性,例如控制器、关节限位、设置关节力、速度、力矩控制、获取当前关节状态等
    • 机器人(Robot):
      • omni.isaac.core.robots 中的机器人(Robot)被视作传感器(Sensors)和关节树 (Articulation) 的结合体(继承)
      • 可以使用 Robot 类的 Attributes 和 Properties 来获取一些机器人的参数,例如当前关节值、自由度等
# Wrap the root of robot prim under a Robot(Articulation) class
# to use high level api to set/ get attributes as well as initializing physics handles needed
from omni.isaac.core.robots import Robot
from omni.isaac.core.world import World
 
world = World()
robot = Robot(prim_path="/World/MyRobot", name="my_robot")
# Add robot to the scene
world.scene.add(robot)
print(robot)
 
# Resetting the world needs to be called before querying anything related to an articulation specifically.
# Its recommended to always do a reset after adding your assets, for physics handles to be propagated properly
world.reset()
  1. 控制机器人
    • 通常机器人的控制借由 omni.isaac.core.controllers 中的 Articulation Controlleromni.isaac.core.articulations 中的 Articulation 实现
      • Articulation Controller 是关节树上所有自由度关节的 PD 控制器,可以应用位置、速度和力来对机器人的整体关节进行控制
      • 可以指定下一次物理步进时要对机器人应用的动作,也可以指定对哪些关节进行操作
    • 如果未给 Articulation 指定 controller,那么它将默认给 Articulation 类实例生成一个 self._articulation_controller = ArticulationController()
# control_robot.py
import numpy as np
from isaacsim import SimulationApp
 
# See DEFAULT_LAUNCHER_CONFIG for available configuration
# https://docs.omniverse.nvidia.com/py/isaacsim/source/extensions/omni.isaac.kit/docs/index.html
launch_config = {
   
   "headless": False}
# Launch the Toolkit
simulation_app = SimulationApp(launch_config)
 
# Locate any other import statement after this point
from omni.isaac.core.world import World
from omni.isaac.core.utils.types import ArticulationAction
from omni.isaac.core.utils.nucleus import get_assets_root_path
from omni.isaac.core.utils.stage import add_reference_to_stage
from omni.isaac.core.robots import Robot
 
# Instantiate World class
world = World()
# Add a ground plane to stage and register it in the scene
world.scene.add_default_ground_plane()
 
# Get isaac sim assets folder root path
# It should be "omniverse://localhost/NVIDIA/Assets/Isaac/4.0"
assets_root_path = get_assets_root_path()
print(assets_root_path)
if assets_root_path is None:
    print("Could not find nucleus server with '/Isaac' folder")
 
# Get franka in isaac sim official assets folder
robot_asset_path = assets_root_path + "/Isaac/Robots/Franka/franka_alt_fingers.usd"
print(robot_asset_path)
 
# Add robot asset reference to stage
# This will create a new XFormPrim and point it to the usd file as a reference
add_reference_to_stage(usd_path=robot_asset_path, prim_path="/World/MyRobot")
 
# Wrap the root of robot prim under a Robot(Articulation) class
# to use high level api to set/ get attributes as well as initializing physics handles needed
robot = Robot(prim_path="/World/MyRobot", name="my_robot")
# Add robot to the scene
world.scene.add(robot)
print(robot)
 
# Resetting the world needs to be called before querying anything related to an articulation specifically.
# Its recommended to always do a reset after adding your assets, for physics handles to be propagated properly
world.reset()
 
# This is an implicit PD controller of the robot articulation
# Stiffness and damping (gains) can be set through the articulation view
articulation_controller = robot.get_articulation_controller()
 
# Get number of active joints in the robot
num_dof = robot.num_dof
# 7 arm joints + 2 gripper joints
print(f"Num of dof(active joints)={num_dof}")
# Get joint limits
joint_limits_lower = robot.dof_properties["lower"]
joint_limits_upper = robot.dof_properties["upper"]
print(f"Joint limits lower={joint_limits_lower} upper={joint_limits_upper}")
 
# Start simulation
all_steps = 10000
for i in range(all_steps):
    # Update joint positions every 500 steps
    if i % (all_steps / 20) == 0:
        # Generate radom joint positions within joint limits
        target_joint_positions = np.random.uniform(
            joint_limits_lower, joint_limits_upper
        )
        # Construct an action to apply to the articulation
        # joint_indices = None will apply the action to all joints
        target_action = ArticulationAction(
            joint_positions=target_joint_positions,
            joint_efforts=None,
            joint_velocities=None,
            joint_indices=None,
        )
        # Apply action
        articulation_controller.apply_action(target_action)
        print(f"Step {i}: target_joint_positions={target_joint_positions}")
    # Update world
    world.step(render=True)
 
 
# Close the running Toolkit
simulation_app.close()