Tensor Bindings: Read and Write Simulation Data#
This tutorial shows how to read and write simulation data through tensor bindings after you load a USD stage. You learn how to use path patterns to bind multiple prims in one call.
Prerequisites#
Complete the Hello World: Load USD and Step tutorial.
Use a USD scene that contains physics-enabled prims matching your binding pattern.
Code Language#
# Create tensor bindings for DOF velocity targets (control inputs)
# Pattern matches all articulation links - the API will automatically map to DOFs
print("Creating tensor binding for DOF velocity targets...")
velocity_target_binding = physx.create_tensor_binding(
pattern="/World/articulation/articulationLink*",
tensor_type=OVPHYSX_TENSOR_ARTICULATION_DOF_VELOCITY_TARGET_F32,
)
print(f" DOF count: {velocity_target_binding.shape[1]}")
# Create tensor binding for link poses (state observation)
print("Creating tensor binding for link poses...")
link_pose_binding = physx.create_tensor_binding(
pattern="/World/articulation/articulationLink*",
tensor_type=OVPHYSX_TENSOR_ARTICULATION_LINK_POSE_F32,
)
print(f" Link count: {link_pose_binding.shape[1]}, Pose dims: {link_pose_binding.shape[2]}")
# Set joint drive velocities (alternating +25 and -25 rad/s)
num_dofs = velocity_target_binding.shape[1]
velocity_targets = np.zeros(velocity_target_binding.shape, dtype=np.float32)
for i in range(num_dofs):
velocity_targets[0, i] = 25.0 if i % 2 == 0 else -25.0
print("Setting DOF velocity targets (alternating ±25 rad/s)...")
velocity_target_binding.write(velocity_targets)
print(f" Velocity targets: {velocity_targets[0, :5]}... (first 5 DOFs)")
# Run extended simulation with periodic readback
print("\nRunning 1000 simulation steps...")
# Allocate buffer for reading link poses
link_poses = np.zeros(link_pose_binding.shape, dtype=np.float32)
dt = 0.01
for i in range(1000):
# Step simulation forward
current_time = i * dt
physx.step(dt, current_time)
physx.wait_all()
# Read link poses periodically (tensor API is synchronous, no wait needed)
if i % 100 == 0 or i == 999:
link_pose_binding.read(link_poses)
# Extract first link's pose (position + quaternion)
# Pose format: [px, py, pz, qx, qy, qz, qw]
px, py, pz = link_poses[0, 0, 0:3]
Create tensor bindings, write control targets, step, and read back state:
// 3. Create tensor bindings
// 3a. DOF velocity target binding (write control targets)
ovphysx_tensor_binding_handle_t dof_target_binding = 0;
ovphysx_tensor_binding_desc_t dof_target_desc = {
.pattern = OVPHYSX_LITERAL("/World/articulation"),
.tensor_type = OVPHYSX_TENSOR_ARTICULATION_DOF_VELOCITY_TARGET_F32
};
result = ovphysx_create_tensor_binding(handle, &dof_target_desc, &dof_target_binding);
if (!check_result(result, "create DOF target binding")) {
ovphysx_destroy_instance(handle);
return 1;
}
// 3b. Articulation link pose binding
ovphysx_tensor_binding_handle_t link_pose_binding = 0;
ovphysx_tensor_binding_desc_t link_pose_desc = {
.pattern = OVPHYSX_LITERAL("/World/articulation"),
.tensor_type = OVPHYSX_TENSOR_ARTICULATION_LINK_POSE_F32
};
result = ovphysx_create_tensor_binding(handle, &link_pose_desc, &link_pose_binding);
if (!check_result(result, "create articulation link pose binding")) {
ovphysx_destroy_instance(handle);
return 1;
}
printf("Tensor bindings created.\n");
// 4. Query binding specs and allocate tensors
ovphysx_tensor_spec_t dof_spec, link_pose_spec;
result = ovphysx_get_tensor_binding_spec(handle, dof_target_binding, &dof_spec);
if (!check_result(result, "get_tensor_binding_spec (dof target)")) {
ovphysx_destroy_instance(handle);
return 1;
}
result = ovphysx_get_tensor_binding_spec(handle, link_pose_binding, &link_pose_spec);
if (!check_result(result, "get_tensor_binding_spec (link pose)")) {
ovphysx_destroy_instance(handle);
return 1;
}
printf("\nBinding specs:\n");
printf(" Articulation DOFs: shape=[%lld, %lld], ndim=%d\n",
(long long)dof_spec.shape[0], (long long)dof_spec.shape[1], dof_spec.ndim);
printf(" Articulation link poses: shape=[%lld, %lld, %lld], ndim=%d\n",
(long long)link_pose_spec.shape[0],
(long long)link_pose_spec.shape[1],
(long long)link_pose_spec.shape[2],
link_pose_spec.ndim);
// Allocate CPU tensors
const size_t dof_count = (size_t)dof_spec.shape[0];
const size_t dof_components = (size_t)dof_spec.shape[1];
const size_t link_pose_batch = (size_t)link_pose_spec.shape[0];
const size_t link_count = (size_t)link_pose_spec.shape[1];
const size_t link_pose_components = (size_t)link_pose_spec.shape[2];
TensorBuffer dof_target_tensor = make_tensor_f32_2d(dof_count, dof_components);
TensorBuffer link_pose_tensor = make_tensor_f32_3d(link_pose_batch, link_count, link_pose_components);
// 5. Set initial DOF velocity targets and simulate
printf("\n=== Setting initial DOF velocity targets ===\n");
// Initialize all targets to 0.0
float* dof_target_data = (float*)dof_target_tensor.data;
for (size_t i = 0; i < dof_count * dof_components; i++) {
dof_target_data[i] = 0.0f;
}
printf("\n=== Writing initial DOF velocity targets ===\n");
result = ovphysx_write_tensor_binding(handle, dof_target_binding, &dof_target_tensor.tensor, NULL);
if (!check_result(result, "write initial DOF targets")) {
destroy_tensor(&dof_target_tensor);
destroy_tensor(&link_pose_tensor);
ovphysx_destroy_instance(handle);
return 1;
}
// 6. Simulation loop
const float dt = 1.0f / 60.0f;
float sim_time = 0.0f;
const size_t link_index_to_print = (link_count > 0) ? (link_count - 1) : 0;
printf("Running 120 simulation steps...\n");
for (int step = 0; step < 120; ++step) {
// Update DOF targets every 50 steps
if (step % 50 == 0) {
// Alternate between positive and negative target velocities
float target_vel = ((step / 50) % 2 == 0) ? 50.0f : -50.0f;
for (size_t i = 0; i < dof_count * dof_components; ++i) {
// Alternate direction for each DOF
dof_target_data[i] = (i % 2 == 0) ? target_vel : -target_vel;
}
result = ovphysx_write_tensor_binding(handle, dof_target_binding, &dof_target_tensor.tensor, NULL);
if (!check_result(result, "write DOF targets")) {
destroy_tensor(&dof_target_tensor);
destroy_tensor(&link_pose_tensor);
ovphysx_destroy_instance(handle);
return 1;
}
}
// Step simulation
ovphysx_enqueue_result_t step_result = ovphysx_step(handle, dt, sim_time);
if (step_result.status != OVPHYSX_API_SUCCESS) {
fprintf(stderr, "ERROR in step enqueue (status=%d)\n", (int)step_result.status);
if (step_result.error.ptr && step_result.error.length > 0) {
fprintf(stderr, " %.*s\n", (int)step_result.error.length, step_result.error.ptr);
ovphysx_destroy_error(step_result.error);
}
destroy_tensor(&dof_target_tensor);
destroy_tensor(&link_pose_tensor);
ovphysx_destroy_instance(handle);
return 1;
}
if (step_result.error.ptr)
ovphysx_destroy_error(step_result.error);
if (!wait_op(handle, step_result.op_index, "step")) {
destroy_tensor(&dof_target_tensor);
destroy_tensor(&link_pose_tensor);
ovphysx_destroy_instance(handle);
return 1;
}
sim_time += dt;
// Read and print state every 30 steps
if (step % 30 == 0) {
// Read articulation link poses
result = ovphysx_read_tensor_binding(handle, link_pose_binding, &link_pose_tensor.tensor);
if (!check_result(result, "read articulation link poses")) {
destroy_tensor(&dof_target_tensor);
destroy_tensor(&link_pose_tensor);
ovphysx_destroy_instance(handle);
return 1;
}
const float* link_pose_data = (const float*)link_pose_tensor.data;
size_t articulation_index = 0;
size_t link_pose_offset = (articulation_index * link_count + link_index_to_print) * link_pose_components;
printf("Step %3d | Link %zu pos=(%.3f, %.3f, %.3f) quat=(%.3f, %.3f, %.3f, %.3f)\n",
step,
link_index_to_print,
link_pose_data[link_pose_offset + 0],
link_pose_data[link_pose_offset + 1],
link_pose_data[link_pose_offset + 2],
link_pose_data[link_pose_offset + 3],
link_pose_data[link_pose_offset + 4],
link_pose_data[link_pose_offset + 5],
link_pose_data[link_pose_offset + 6]);
}
}
For GPU tensor bindings with CUDA, see tensor_bindings_gpu_c/ in the samples directory.
Tensor Type Reference#
Use this table to pre-allocate tensors without probing binding.shape at runtime.
Symbols:
N: rigid body count in the bindingA: articulation count in the bindingL: max link count across matched articulationsD: max DOF count across matched articulations
Constant |
Shape |
Dimensionality |
Read |
Write |
Component layout |
Behavioral note |
|---|---|---|---|---|---|---|
|
|
2D |
yes |
yes |
|
World-frame rigid body transforms |
|
|
2D |
yes |
yes |
|
World-frame linear and angular velocity |
|
|
2D |
no |
yes |
|
Write-only force at center of mass (control input) |
|
|
2D |
no |
yes |
|
Write-only wrench-at-position in world frame |
|
|
2D |
yes |
yes |
|
Root body transform per articulation |
|
|
2D |
yes |
yes |
|
Root body velocity per articulation |
|
|
3D |
yes |
no |
|
Per-link pose; padded links are zero |
|
|
3D |
yes |
no |
|
Per-link velocity; read-only |
|
|
3D |
no |
yes |
|
Write-only per-link external wrench |
|
|
2D |
yes |
yes |
joint position scalar per DOF |
Joint-space position in articulation DOF order |
|
|
2D |
yes |
yes |
joint velocity scalar per DOF |
Joint-space velocity in articulation DOF order |
|
|
2D |
yes |
yes |
target position scalar per DOF |
Position-control targets |
|
|
2D |
yes |
yes |
target velocity scalar per DOF |
Velocity-control targets |
|
|
2D |
yes |
yes |
actuation scalar per DOF |
Readback is from staging buffer; may differ from solver-applied force |
For canonical enum definitions and low-level semantics, see include/ovphysx/ovphysx_types.h.
Result#
After this tutorial, you can create tensor bindings, push batched simulation inputs, and read back batched results.