tensor API旨在在创建所有环境和角色之后,在模拟期间使用。要设置模拟,可以使用“创建模拟”中描述的“经典”API。要使用张量API,需要注意一些额外的细节。
张量API当前仅适用于PhysX,因此在创建模拟时必须使用SIM_PhysX。
要使用GPU张量,**必须在用于创建模拟的SimParams中将use_GPU_pipeline
标志设置为True。**此外,您还应配置PhysX以使用GPU:
sim_params = gymapi.SimParams()
...
sim_params.use_gpu_pipeline = True
sim_params.physx.use_gpu = True
sim = gym.create_sim(compute_device_id, graphics_device_id, gymapi.SIM_PHYSX, sim_params)
最后,在所有环境完全设置好后,必须调用prepare_sim
来初始化tensor API使用的内部数据结构:
gym.prepare_sim(sim)
一个gym actor可以由一个或多个刚体组成。所有演员都有一个根物体(root body)。根状态张量保存了模拟环境中所有 actor根物体(root body)的状态。每个根体的状态使用13个与GymRigidBodyState
布局相同的浮点数表示:3个浮点数表示位置,4个浮点数代表四元数,3个浮数表示线速度,3个浮动数表示角速度。
获得根状态张量:
_root_tensor = gym.acquire_actor_root_state_tensor(sim)
为了访问张量的内容,可以使用:
root_tensor = gymtorch.wrap_tensor(_root_tensor)
现在你可以在PyTorch中使用这个张量,它提供了所有强大的实用程序,我们无需重新发明所有的轮子.
此张量的形状为**(num_actors,13)**,数据类型为float32
。可以按原样使用此张量,也可以使用标准pytorch语法创建更方便的数据视图或切片:
root_positions = root_tensor[:, 0:3]
root_orientations = root_tensor[:, 3:7]
root_linvels = root_tensor[:, 7:10]
root_angvels = root_tensor[:, 10:13]
只需要在模拟开始之前获取张量并创建视图一次。
如果要使用最新状态更新这些张量的内容:
gym.refresh_actor_root_state_tensor(sim)
此函数将使用物理引擎的最新值填充张量。从这个张量创建的所有视图或切片都将自动更新,因为它们都引用相同的内存缓冲区。
总体流程如下:
# ...create sim, envs, and actors here...
gym.prepare_sim()
# acquire root state tensor descriptor
_root_tensor = gym.acquire_actor_root_state_tensor(sim)
# wrap it in a PyTorch Tensor and create convenient views
root_tensor = gymtorch.wrap_tensor(_root_tensor)
root_positions = root_tensor[:, 0:3]
root_orientations = root_tensor[:, 3:7]
root_linvels = root_tensor[:, 7:10]
root_angvels = root_tensor[:, 10:13]
# main simulation loop
while True:
# step the physics simulation
gym.simulate(sim)
# refresh the state tensors
gym.refresh_actor_root_state_tensor(sim)
# ...use the latest state tensors here...
可以使用根状态张量通过为其根体设置新的位置、方向和速度来传送actor。此功能在重置期间很有用,但不应在每一帧都执行,因为这会干扰物理引擎的作用,并可能导致非物理行为。
例如,希望沿y轴将所有参与者提高一个单位:
offsets = torch.tensor([0, 1, 0]).repeat(num_actors)
root_positions += offsets
这将在适当位置修改根状态张量,您可以像这样应用更改:
gym.set_actor_root_state_tensor(sim, _root_tensor)
以上使用的是_root_tensor
,这是我们在开始时获取的原始Gym张量描述符。我们修改了张量的内容,现在我们使用它在物理引擎中应用更新。其效果是,所有actors都将向上传送一个单位,无论他们是单体actor还是多体actors。
另一个例子是对演员根进行周期性重置,每100步将他们传送到原始位置一次:
# acquire root state tensor descriptor
_root_tensor = gym.acquire_actor_root_state_tensor(sim)
# wrap it in a PyTorch Tensor
root_tensor = gymtorch.wrap_tensor(_root_tensor)
# save a copy of the original root states
saved_root_tensor = root_tensor.clone()
step = 0
# main simulation loop
while True:
# step the physics simulation
gym.simulate(sim)
step += 1
if step % 100 == 0:
gym.set_actor_root_state_tensor(sim, gymtorch.unwrap_tensor(saved_root_tensor))
注意,我们使用torch clone
方法创建了一个新的torch张量,其中包含原始根状态的副本。Gym方法set_actor_root_state_tensor
无法直接使用torch张量,因此我们需要使用gymtorch.unwrap_tensor
将torch张量转换为Gym张量描述符。
更新actor子集的方法为:set_actor_root_state_tensor_indexed
:
它需要一个额外的actor索引张量来重置,它必须是32位整数。
模拟中的actor总数A可以通过调用gym.get_sim_cactor_count(sim)
获得.有效的actor索引范围从0
到A-1
。根状态张量中特定actor的索引可以通过调用gym的get_actor_index(env、actor_handle、gymapi.DOMAIN_SIM)
。下面是使用带有PyTorch索引张量的set_actor_root_state_tensor_indexed的示例:
actor_indices = torch.tensor([0, 17, 42], dtype=torch.int32, device="cuda:0")
gym.set_actor_root_state_tensor_indexed(sim, _root_states, gymtorch.unwrap_tensor(actor_indices), 3)
注意,传递给此方法的状态缓冲区与传递给set_actor_root_state_tensor
的状态缓冲相同,即它是包含所有参与者状态的整个张量,但状态更新将仅应用于索引张量中列出的参与者,不需要构造一个只包含要修改的状态的新状态张量。只需在正确的索引处将更新的状态写入原始根状态张量,然后在对set_actor_root_state_tensor_indexed
的调用中指定这些索引。
为了避免在与Gym共享PyTorch张量(尤其是索引张量)时出现一些常见错误,见张量寿命部分。
铰接的actors具有多个自由度(DOF),其状态可以被查询和更改。每个DOF的状态使用两个32位浮点表示,即DOF位置和DOF速度。对于棱柱(平移)自由度,位置单位为米,速度单位为米/秒。对于旋转(旋转)自由度,位置以弧度为单位,速度以弧度/秒为单位。
DOF状态张量包含模拟中所有DOF的状态。张量的形状为(num_dofs,2)。通过调用gym.get_sim_dof_count(sim)
可以获得dof的总数。DOF状态按顺序排列。张量以actor 0的所有dof开始,然后是actor 1的所有DOFs,依此类推。每个actor的dof顺序与函数get_actor_dof_states
和set_actor_dof _states
相同。演员的DOF数可以通过gym.get_actor_dof_count(env, actor)
获得。 张量中特定DOF的全局索引可以通过多种方式获得:
gym.get_actor_dof_index(env, actor_handle, i, gymapi.DOMAIN_SIM)
:返回指定角色的第i个DOF的全局DOF索引gym.find_actor_dof_index(env, actor_handle, dof_name, gymapi.DOMAIN_SIM)
: 按名称查找全局DOF索引acquire_dof_state_tensor
返回的是一个gym张量描述符,可以将其转换为pytorch 张量如下:
_dof_states = gym.acquire_dof_state_tensor(sim)
dof_states = gymtorch.wrap_tensor(_dof_states)
使用模拟中的最新数据刷新张量:
gym.refresh_dof_state_tensor(sim)
可以修改DOF状态张量中的值并将其应用于模拟,函数set_dof_state_tensor
应用张量中的所有值;这意味着为模拟中的所有参与者设置所有DOF位置和速度:
gym.set_dof_state_tensor(sim, _dof_states)
如果在适当位置修改值,则可以传递从acquired_dof_state_tensor获得的原始张量描述符。或者,您可以创建自己的张量来保存新值,并传递该描述符。
set_dof_state_tensor_indexed
将给定张量中的值应用于actor_index_tensor
中指定的参与者。其他参与者未受影响。actor索引必须是32位整数。例如:
actor_indices = torch.tensor([0, 17, 42], dtype=torch.int32, device="cuda:0")
gym.set_dof_state_tensor_indexed(sim, _dof_states, gymtorch.unwrap_tensor(actor_indices), 3)
可以使用根状态张量中的条目和DOF状态张量中条目来完全定义关节参与者的状态。重置基础固定的角色,如机械臂,可以通过只设置新的自由度状态来完成。重置未固定到位的角色,如行走机器人,需要设置新的根状态和新的DOF状态。在这种情况下,可以使用相同的actor索引张量,如下所示:
actor_indices = torch.tensor([0, 17, 42], dtype=torch.int32, device="cuda:0")
_actor_indices = gymtorch.unwrap_tensor(actor_indices)
gym.set_actor_root_state_tensor_indexed(sim, _root_states, _actor_indices, 3)
gym.set_dof_state_tensor_indexed(sim, _dof_states, _actor_indices, 3)
刚体状态张量包含模拟中所有刚体的状态。每个刚体的状态与根状态张量所描述的相同-13个浮体捕捉位置、方向、线速度和角速度。刚体状态张量的形状为**(num_rigid_bodys,13)**。通过调用gym.get_sim_regid_body_count(sim)
可以获得模拟中刚体的总数。刚体状态按顺序排列。张量以演员0的所有body开始,然后是演员1的所有body,依此类推。每个演员的body顺序与函数get_actor_rigid_body_states
和set_actor_rigid_body_states
相同。演员的刚体数量可以通过gym.get_actor_rigid_body_count(env, actor)
获得。张量中特定刚体的全局指数可以通过多种方式获得:
gym.get_actor_rigid_body_index(env, actor_handle, i, gymapi.DOMAIN_SIM)
:返回指定角色的第i个刚体的全局刚体索引;gym.find_actor_rigid_body_index(env, actor_handle, rb_name, gymapi.DOMAIN_SIM)
:按名称查找全局刚体索引;acquire_rigid_body_state_tensor
返回的gym张量描述符,可以转为pytorch张量:
_rb_states = gym.acquire_rigid_body_state_tensor(sim)
rb_states = gymtorch.wrap_tensor(_rb_states)
函数refresh_rigid_body_state_tensor
使用模拟中的最新数据填充张量:
gym.refresh_rigid_body_state_tensor(sim)
目前,刚体状态张量是只读的。仅允许使用根状态张量为actor根体设置刚体状态。
雅可比矩阵和质量矩阵是机器人控制中的重要工具。雅可比矩阵将自由度的关节空间速度映射为其笛卡尔速度和角速度,而质量矩阵包含机器人的广义质量,具体取决于当前配置。它们用于标准机器人控制算法,如反向运动学或操作空间控制。
雅可比矩阵和质量矩阵都是用张量表示的。该方法与其他张量函数略有不同,因为雅可比矩阵和质量矩阵的大小可能因actor类型而异。获取雅可比矩阵或质量矩阵张量时,必须指定actor名称。然后,张量将包含所有环境中具有该名称的所有参与者的矩阵(假设具有该名称每个参与者的类型相同)。在调用create_actor
时提供参与者名称。
本节的其余部分假设在作为franka资产实例的每个env中都有一个名为“franka”的参与者:
# acquire the jacobian and mass matrix tensors for all actors named "franka"
_jacobian = gym.acquire_jacobian_tensor(sim, "franka")
_massmatrix = gym.acquire_mass_matrix_tensor(sim, "franka")
# wrap as pytorch tensors
jacobian = gymtorch.wrap_tensor(_jacobian)
mm = gymtorch.wrap_tensor(_massmatrix)
雅可比矩阵可用于CPU和GPU管道,但质量矩阵目前仅在CPU上可用。
要刷新获取的所有雅可比矩阵和质量矩阵张量,可以调用以下函数:
gym.refresh_jacobian_tensors(sim)
gym.refresh_mass_matrix_tensors(sim)
质量矩阵的形状为(num_dofs,num_dof)。您可以通过调用get_asset_dof_count
或get_actor_dof_count
来获取DOF的数量。质量矩阵张量将具有形状(num_envs、num_dofs、num_dofs)。Franka资产有9个DOF,因此使用100个env,张量的形状将为(100,9,9)。
雅可比矩阵的形状取决于链接的数量、自由度以及底座是否固定。雅可比矩阵将关节运动与自由度联系起来。行表示链接,列表示DOF。每个物体在雅可比矩阵中有6行表示其沿三个坐标轴的线性和角运动。
如果演员基础可以自由移动(未固定),则雅可比张量的形状将为(num_envs,num_links,6,num_dofs+6)。Franka资产有11个链接和9个DOF,因此使用100个env,张量的形状将为(100,11,6,15)。额外的六个自由度对应于自由根连杆的线性和角度自由度。要检索特定链接和DOF的矩阵元素,您可以这样索引张量:(env_index,link_index、axis_index和DOF_index+6)。例如,要查找“panda_hand”链接和“panda_joint5”DOF的条目,首先需要在资源字典中查找链接和DOF索引:
link_dict = gym.get_asset_rigid_body_dict(franka_asset)
dof_dict = gym.get_asset_dof_dict(franka_asset)
link_index = link_dict["panda_hand"]
dof_index = dof_dict["panda_joint5"]
然后你可以像这样在雅可比张量中查找相应的条目:
# for all envs:
jacobian[:, link_index, :, dof_index + 6]
# for a specific env:
jacobian[env_index, link_index, :, dof_index + 6]
如果演员基数是固定的,则雅可比矩阵的形状是不同的。根链接不可移动,因此在雅可比矩阵中没有行。此外,没有根自由度,因此没有额外的6列。雅可比张量的形状变为(num_envs,num_links-1,6,num_dofs)。将前面的示例转换为查找具有固定基数的雅可比张量中的条目:
# for all envs:
jacobian[:, link_index - 1, :, dof_index]
# for a specific env:
jacobian[env_index, link_index - 1, :, dof_index]
净接触力张量包含每个刚体在最后一个模拟步骤中经历的净接触力,力表示为三维矢量。它是一个形状为(num_rigid_bodys,3)的只读张量。可以使用与刚体状态张量相同的方式对单个刚体进行索引。
_net_cf = gym.acquire_net_contact_force_tensor(sim)
net_cf = gymtorch.wrap_tensor(_net_cf)
函数acquire_net_contact_force_tensor
返回一个Gym张量描述符,它可以包装为PyTorch张量,如前所述:
_net_cf = gym.acquire_net_contact_force_tensor(sim)
net_cf = gymtorch.wrap_tensor(_net_cf)
此函数返回的值受接触收集模式(SimParams.phyx.contact_collection
)和物理子步骤数(SimParams.substeps
)的影响。联系人收集模式允许在联系人报告中平衡性能和准确性。如果接触收集模式为CC_NEVER
,则从未从物理引擎收集任何接触,报告的净接触力将始终为零。如果接触收集模式为CC_ALL_SUBSTEPS
,则将在所有子步骤中收集接触,并将汇总所有子步骤的报告净接触力。如果联系人收集模式为CC_LAST_SUBSTEP
,则仅在最后一个子步骤中收集联系人。注意,当使用单个物理子步骤运行时,CC_LAST_substep
和CC_ALL_SUBSTEPS
是等效的。
默认的联系人收集模式是CC_ALL_SUBSTEPS
,它产生最准确的结果,但在运行多个子步骤时是最慢的模式。CC_LAST_SUBSTEP
是一个性能更高的选项,可以在不需要完全接触报告精度时使用。它适用于在多个物理子步骤中保持稳定接触的情况。如果应用程序根本不需要联系人信息,则CC_NEVER
是确保没有联系人收集开销的最高效模式。
相关库:isaacgym.gymapi.ContactCollection
(在index.html-Python API中可查)
各种状态张量(根状态张量、自由度状态张量和刚体状态张量)对于获取有关参与者的信息以及即时设置新的姿势和速度非常有用。在重置期间,当参与者需要返回到其原始姿势或使用新的初始条件重新启动任务时,这种方式设置状态是合适的。然而,直接使用这些张量来设置新的状态应该是谨慎的。actors的位置和速度由物理引擎管理,它考虑了碰撞、外力、内部约束和驱动。在模拟过程中,通常应避免直接设置新的位置和速度,因为它会超越物理引擎并导致非物理行为。要在模拟期间管理演员行为,可以使用以下API应用DOF力或PD控制。
函数set_dof_actuation_force_sensor可用于为模拟中的所有dof施加力。例如:
# get total number of DOFs
num_dofs = gym.get_sim_dof_count(sim)
# generate a PyTorch tensor with a random force for each DOF
actions = 1.0 - 2.0 * torch.rand(num_dofs, dtype=torch.float32, device="cuda:0")
# apply the forces
gym.set_dof_actuation_force_tensor(sim, gymtorch.unwrap_tensor(actions))
注意,驱动力仅适用于当使用set_actor_dof_properties
将其driveMode
设置为gymapi.DOF_MODE_EFFORT
的情况。对于棱柱(平移)自由度,力单位为牛顿。对于旋转(旋转)自由度,力单位为Nm。力张量中DOF的顺序与DOF状态张量中的顺序相同。
函数set_dof_position_target_sensor
可用于设置模拟中所有dof的PD位置目标。注意,位置目标仅在其 driveMode
通过使用set_actor_dof_properties
设置为gymapi.DOF_MODE_POS
的时候对DOFs有效。对于棱柱(平移)自由度,位置目标以米为单位。对于旋转(旋转)DOF,位置目标以弧度为单位。位置目标张量中DOF的顺序与DOF状态张量中的顺序相同。
函数set_dof_velocity_target_tensor
可以用于为模拟中的所有自由度设置PD速度目标。注意,速度目标仅在其 driveMode
通过使用set_actor_dof_properties
设置为gymapi.DOF_MODE_VEL
的时候对DOFs有效。对于棱柱(平移)自由度,速度目标以米/秒为单位。对于旋转(旋转)自由度,速度目标以弧度/秒为单位。速度目标张量中DOF的顺序与DOF状态张量中的顺序相同。
有基于张量的控制函数的索引变体,可用于控制索引张量中指定的参与者子集,类似于set_dof_state_tensor_indexed
.分别为set_dof_actuation_force_tensor_indexed
,set_dof_position_target_tensor_indexed
,set_dof_velocity_tensor_indexed
.
可以使用两个不同的函数将力应用于刚体。
apply_frigid_body_force_tensors
可用于在模拟中在每个刚体的质心处施加力和/或扭矩:# apply both forces and torques
gym.apply_rigid_body_force_tensors(sim, force_tensor, torque_tensor, gymapi.ENV_SPACE)
# apply only forces
gym.apply_rigid_body_force_tensors(sim, force_tensor, None, gymapi.ENV_SPACE)
# apply only torques
gym.apply_rigid_body_force_tensors(sim, None, torque_tensor, gymapi.ENV_SPACE)
最后一个参数是CoordinateSpace
枚举,它指定力和转矩矢量所在的空间(LOCAL_space
、ENV_space
(默认)或GLOBAL_space
)。
如果希望仅对选定的身体子集施加力或力矩,则将相应的张量项设置为零。
apply_rid_body_force_at_pos_tensors
,它允许您在给定位置向实体施加力。当力位置不在质心时,该功能将自动计算并应用所需扭矩:# apply forces at given positions
gym.apply_rigid_body_force_at_pos_tensors(sim, force_tensor, pos_tensor, gymapi.ENV_SPACE)
具体参考程序:apply_forces.py
以及apply_forces_at_pos.py
Python使用引用计数进行垃圾收集。与任何常规Python对象一样,使用PyTorch创建的Tensor也会受到垃圾收集的影响。Gym C++运行时是一个共享库,它与Python解释器没有连接,因此它不参与对象的引用计数。当将张量传递给Gym时,确保Python不会在对象仍在使用时对其进行垃圾收集是很重要的。这可能是难以调试的棘手内存错误的来源。
这种情况的一种常见情况是与Gym共享索引张量。PyTorch使用LongTensors进行索引,但Gym需要32位索引。因此,在将索引传递给Gym之前,我们需要将LongTensor转换为32位整数张量:
indices_torch = torch.LongTensor([0, 17, 42])
indices_gym = gymtorch.unwrap_tensor(indices_torch.to(torch.int32))
set_actor_root_state_tensor_indexed(sim, states, indices_gym, 3)
unwrap_tensor函数在描述符中收集有关PyTorch张量的信息,稍后将其传递给Gym。为了提高效率,它不复制张量的数据——它只是记录数据的内存地址。然而,在上面的代码片段中,张量是通过调用.to(torch.int32)创建的临时变量。在调用unwrap_tensor之后,Python看不到对这个临时张量的任何引用,所以它可以垃圾收集它。如果该张量在调用set_actor_root_state_tensor_indexed之前被垃圾收集,则结果是未定义的-可能会发生崩溃或数据损坏。
有一个简单的解决方案来避免这种情况。每当您调用unwrap_tensor时,请确保有一个Python对该张量的引用,以防止它立即被垃圾收集。我们可以这样重写上述代码:
indices_torch = torch.LongTensor([0, 17, 42])
indices_torch32 = indices_torch.to(torch.int32) # <--- this reference will keep the tensor alive
set_actor_root_state_tensor_indexed(sim, states, gymtorch.unwrap_tensor(indices_torch32), 3)
张量API目前仅支持PhysX后端;在GPU管道中使用张量API时也存在一些限制。
张量“setter”函数,如set_actor_root_state_tensor_indexed
,每个步骤只能调用一次。换句话说,在对gym.simulate
的调用之间,应该只对特定setter函数进行一次调用。不要为不同的参与者集多次调用函数,而是组合参与者索引,使其可以在一次调用中更新。例如:
# 错误示范:
gym.set_actor_root_state_tensor_indexed(sim, root_states, indices1, n1)
gym.set_actor_root_state_tensor_indexed(sim, root_states, indices2, n2)
应该为:
# 正确示范
gym.set_actor_root_state_tensor_indexed(sim, root_states, combined_indices, n_total)
其中combined_indices
是indices1
和indices2
的并集,而n_total
是组合的combined_indices
的数量。
将状态更新合并到单个调用中也可以提高性能,因此这样做是一种很好的做法。
GPU管道的另一个限制是,在调用张量设置器函数之前,每个步骤只能调用一次张量“refresh”函数。当在setter 函数与refresh函数之间没有调用gym.simulate
时,如果在setter函数后调用refresh函数,可能会返回过时的数据。考虑使用以下函数:
gym.set_dof_state_tensor(sim, dof_states)
gym.refresh_rigid_body_state_tensor(sim)
使用set_dof_state_tensor
来给所有的actor设置新的DOF状态。在后台记录了这些新值,但直到随后调用gym.simulate
时,它们才被应用。因此,调用refresh_rigid_body_state_tensor
将返回陈旧值,直到调用gym.silulate
。因此,推荐在每一次调用gym.simulate
后 并且 在所有setter函数前,更新仅一次张量的状态。