C API Reference#

The full C API is defined in these headers:

C++ convenience wrappers (experimental, C++17):

For rendered documentation with full descriptions, see the built HTML docs.

C API Functions#

Functions

ovphysx_result_t ovphysx_create_instance(
const ovphysx_create_args *create_args,
ovphysx_handle_t *out_handle,
)#

Create a new ovphysx instance.

Initialize create_args with OVPHYSX_CREATE_ARGS_DEFAULT for sensible defaults:

ovphysx_set_log_level(OVPHYSX_LOG_VERBOSE);  // optional: default is WARNING
ovphysx_create_args args = OVPHYSX_CREATE_ARGS_DEFAULT;
ovphysx_handle_t handle = OVPHYSX_INVALID_HANDLE;
ovphysx_result_t r = ovphysx_create_instance(&args, &handle);

Side Effects

Loads runtime components and initializes process-level state.

Threading

Safe to call from any thread. The resulting handle is not thread-safe for concurrent use.

Ownership

Caller owns the instance handle and must destroy it.

Errors

  • OVPHYSX_API_INVALID_ARGUMENT on null pointers

  • OVPHYSX_API_GPU_NOT_AVAILABLE if GPU is required (OVPHYSX_DEVICE_GPU) but unavailable

  • OVPHYSX_API_ERROR for other initialization failures

Warning

The device mode (CPU vs GPU) is locked in by the first call in the process. OVPHYSX_DEVICE_AUTO resolves to an effective mode (CPU or GPU) on first use. Subsequent calls with a different effective mode will fail with OVPHYSX_API_INVALID_ARGUMENT. See ovphysx_device_t documentation for details.

Parameters:
  • create_args – Configuration for the ovphysx instance (must not be NULL).

  • out_handle – [out] ovphysx handle (must not be NULL).

Returns:

ovphysx_result_t with status and error info.

Pre:

create_args != NULL, out_handle != NULL.

Post:

On success, *out_handle is a valid handle that must be destroyed with ovphysx_destroy_instance().

ovphysx_result_t ovphysx_destroy_instance(ovphysx_handle_t handle)#

Destroy an ovphysx instance and release all associated resources.

When the last instance is destroyed, performs full framework teardown: stops background threads, unloads all plugins in dependency order, and releases the framework. This prevents crashes from non-deterministic DLL/SO unload at process exit.

ovphysx_destroy_instance(handle);
Side Effects

Releases internal resources, plugins, and cached data for this instance. On last instance, tears down the Carbonite framework if ovphysx owns it.

Threading

Do not destroy an instance while it is in use on other threads.

Ownership

After destruction, any bindings created by this instance are invalid.

Errors

  • OVPHYSX_API_ERROR if destruction fails. No error string is returned; consult logs.

Parameters:

handle – ovphysx handle to destroy.

Returns:

ovphysx_result_t with status and error info.

Pre:

handle must be a valid instance handle.

Post:

The handle is invalid and must not be reused.

ovphysx_result_t ovphysx_set_shutting_down(void)#

Begin global shutdown for all instances of ovphysx.

Call this before triggering any bulk unload/destroy operations during process exit so the SDK can enter shutdown mode and skip redundant teardown work safely.

ovphysx_set_shutting_down();
Side Effects

Alters global shutdown behavior for all instances in the process.

Threading

Safe to call from any thread.

Errors

  • OVPHYSX_API_ERROR for unexpected shutdown failures (no error string).

Returns:

ovphysx_result_t with status. Never returns an error message.

Pre:

None.

Post:

Global shutdown mode is enabled.

void ovphysx_get_version(
uint32_t *out_major,
uint32_t *out_minor,
uint32_t *out_patch,
)#

Get runtime version of the library.

Useful for checking ABI compatibility between headers and shared library. For compile-time version macros, include ovphysx/version.h.

Parameters:
  • out_major – [out] Major version (must not be NULL)

  • out_minor – [out] Minor version (must not be NULL)

  • out_patch – [out] Patch version (must not be NULL)

const char *ovphysx_get_version_string(void)#

Get version as string (e.g., “0.1.0”).

Returns:

Version string with static storage duration (valid for lifetime of process, do not free).

ovphysx_result_t ovphysx_set_global_config(
ovphysx_config_entry_t entry,
)#

Set a typed global config entry at runtime (process-global).

IMPORTANT: Config is PROCESS-GLOBAL. Changes affect all ovphysx instances in the current process. Configure before creating instances or loading USD for predictable behavior.

Use the builder functions in ovphysx_config.h for convenient construction:

#include "ovphysx/ovphysx_config.h"
ovphysx_set_global_config(ovphysx_config_entry_num_threads(4));
ovphysx_set_global_config(ovphysx_config_entry_disable_contact_processing(true));
// Escape hatch for arbitrary Carbonite paths:
ovphysx_set_global_config(ovphysx_config_entry_carbonite(
    OVPHYSX_LITERAL("/physics/fabricUpdateVelocities"), OVPHYSX_LITERAL("true")));

Parameters:

entry – Typed config entry to apply.

Returns:

ovphysx_result_t with status and error info.

ovphysx_result_t ovphysx_get_global_config_bool(
ovphysx_config_bool_t key,
bool *out_value,
)#

Get a boolean config value.

Parameters:
  • key – Boolean config key.

  • out_value – [out] Current value.

Returns:

ovphysx_result_t with status and error info.

ovphysx_result_t ovphysx_get_global_config_int32(
ovphysx_config_int32_t key,
int32_t *out_value,
)#

Get an int32 config value.

Parameters:
  • key – Int32 config key.

  • out_value – [out] Current value.

Returns:

ovphysx_result_t with status and error info.

ovphysx_result_t ovphysx_get_global_config_float(
ovphysx_config_float_t key,
float *out_value,
)#

Get a float config value.

Parameters:
  • key – Float config key.

  • out_value – [out] Current value.

Returns:

ovphysx_result_t with status and error info.

ovphysx_result_t ovphysx_get_global_config_string(
ovphysx_config_string_t key,
ovphysx_string_t *value_out,
size_t *out_required_size,
)#

Get a string config value into a user-provided buffer.

Parameters:
  • key – String config key.

  • value_out – [in/out] String with pre-allocated buffer (ptr+length).

  • out_required_size – [out] Required buffer size including null terminator.

Returns:

ovphysx_result_t with status and error info.

ovphysx_result_t ovphysx_configure_s3(
const char *host,
const char *bucket,
const char *region,
const char *access_key_id,
const char *secret_access_key,
const char *session_token,
)#

Configure S3 credentials for remote USD loading via HTTPS S3 URLs.

Credentials are process-global and take effect immediately for all ovphysx instances. Call before ovphysx_add_usd() with an S3 HTTPS URL.

Requires that an ovphysx instance has been created (the remote-loading runtime is initialized automatically during instance creation).

Side Effects

Configures S3 settings for the entire process.

Threading

Thread-safe (serialized internally).

Errors

  • OVPHYSX_API_INVALID_ARGUMENT if required parameters are NULL or empty.

  • OVPHYSX_API_ERROR if the remote-loading runtime is unavailable or the call fails.

Parameters:
  • host – S3 endpoint host (e.g., “my-bucket.s3.us-east-1.amazonaws.com”). Required.

  • bucket – S3 bucket name. Required.

  • region – AWS region (e.g., “us-east-1”). Required.

  • access_key_id – AWS access key ID. Required.

  • secret_access_key – AWS secret access key. Required.

  • session_token – STS session token. Optional (NULL if not using temporary credentials).

Returns:

ovphysx_result_t with status and error info.

Pre:

An ovphysx instance must have been created (so the runtime is loaded).

Post:

S3 credentials are configured for the process.

ovphysx_result_t ovphysx_configure_azure_sas(
const char *host,
const char *container,
const char *sas_token,
)#

Configure an Azure SAS token for remote USD loading via Azure Blob Storage.

Credentials are process-global and take effect immediately for all ovphysx instances. Call before ovphysx_add_usd() with an Azure Blob URL.

Requires that an ovphysx instance has been created (the remote-loading runtime is initialized automatically during instance creation).

Side Effects

Configures Azure settings for the entire process.

Threading

Thread-safe (serialized internally).

Errors

  • OVPHYSX_API_INVALID_ARGUMENT if required parameters are NULL or empty.

  • OVPHYSX_API_ERROR if the remote-loading runtime is unavailable or the call fails.

Parameters:
  • host – Azure Blob host (e.g., “myaccount.blob.core.windows.net”). Required.

  • container – Azure container name. Required.

  • sas_token – SAS token string (without leading ‘?’). Required.

Returns:

ovphysx_result_t with status and error info.

Pre:

An ovphysx instance must have been created (so the runtime is loaded).

Post:

Azure SAS token is configured for the process.

ovphysx_enqueue_result_t ovphysx_add_usd(
ovphysx_handle_t handle,
ovphysx_string_t usd_file_path,
ovphysx_string_t path_prefix,
ovphysx_usd_handle_t *out_usd_handle,
)#
ovphysx_enqueue_result_t ovphysx_remove_usd(
ovphysx_handle_t handle,
ovphysx_usd_handle_t usd_handle,
)#
ovphysx_enqueue_result_t ovphysx_reset(ovphysx_handle_t handle)#
ovphysx_result_t ovphysx_get_stage_id(
ovphysx_handle_t handle,
int64_t *out_stage_id,
)#

Get the USD stage ID for the currently loaded stage.

Returns the internal USD stage identifier for the stage attached to this ovphysx instance. This can be used to correlate PhysX instances with USD stages in multi-stage scenarios.

int64_t stage_id = 0;
ovphysx_get_stage_id(handle, &stage_id);
Side Effects

None.

Errors

  • OVPHYSX_API_INVALID_ARGUMENT for null out_stage_id

  • OVPHYSX_API_ERROR for internal failures

Note

This is a synchronous operation. Use ovphysx_wait_op(handle, result.op_index, …) to wait in case add_usd / remove_usd / reset are enqueued before this operation.

Parameters:
  • handle – The ovphysx instance

  • out_stage_id – Pointer to receive the stage ID (must not be NULL)

Returns:

ovphysx_result_t with status and error info

Pre:

handle and out_stage_id must be valid.

Post:

out_stage_id contains the current stage ID on success.

ovphysx_enqueue_result_t ovphysx_clone(
ovphysx_handle_t handle,
ovphysx_string_t source_path_in_usd,
ovphysx_string_t *target_paths,
uint32_t num_target_paths,
const float *parent_transforms,
)#

Enqueue an asynchronous operation to clone the subtree under the source path to one or more target paths in the runtime stage representation (internal representation only, USD untouched).

The source path must exist in the stage. The target paths must not already exist in the stage.

Clones are created in the internal representation only (USD file will not be modified) and immediately participate in physics simulation. This is optimized for RL training scenarios with mass replication (1000s of instances).

ovphysx_string_t targets[2] = { ovphysx_cstr("/World/env1"), ovphysx_cstr("/World/env2") };
ovphysx_enqueue_result_t r = ovphysx_clone(handle, ovphysx_cstr("/World/env0"), targets, 2, NULL);
Side Effects

Adds new runtime-stage prims for each target path.

Ownership

The target_paths array is read during the call; caller retains ownership.

Errors

  • OVPHYSX_API_INVALID_ARGUMENT for invalid inputs

  • OVPHYSX_API_NOT_FOUND if source path does not exist

  • OVPHYSX_API_ERROR for internal failures

Note

Collision isolation between clones (e.g., preventing clones in env1 from colliding with clones in env2) is configured through USD scene properties (collision groups, filtering) rather than through clone API parameters. Set up collision filtering in your USD scene before cloning if you need isolated parallel environments.

Note

This is an asynchronous operation. Use ovphysx_wait_op(handle, result.op_index, …) to wait for completion before using the cloned objects outside of the stream operations.

Parameters:
  • handle – PhysX instance handle

  • source_path_in_usd – Path to the source subtree to clone (must exist)

  • target_paths – Array of target paths to clone to (must not exist)

  • num_target_paths – Number of target paths to clone to

  • parent_transforms – World-space placement for each cloned environment’s parent Xform prim. Flat array of [num_target_paths x 7] floats: (px, py, pz, qx, qy, qz, qw) per target — position followed by quaternion rotation. Quaternion convention: imaginary-first, matching the tensor binding pose format (OVPHYSX_TENSOR_RIGID_BODY_POSE_F32). Identity rotation = (0, 0, 0, 1). Pass NULL to place all parent prims at identity (use it when you don’t care about spatial separation).

Returns:

ovphysx_enqueue_result_t with status, error, and operation index for the clone

Pre:

handle must be valid.

Pre:

source_path_in_usd must exist; target_paths must be valid and unique.

Pre:

Must be called before warmup_gpu() or the first simulate() call. Cloning after GPU warmup may reallocate GPU buffers and corrupt already-initialised state. A warning is logged if this order is violated.

Post:

Clone is visible in the runtime stage once the op completes.

ovphysx_enqueue_result_t ovphysx_step(
ovphysx_handle_t handle,
float step_dt,
float current_time,
)#
ovphysx_result_t ovphysx_step_sync(
ovphysx_handle_t handle,
float step_dt,
float current_time,
)#

Synchronous step: simulate one physics timestep and wait for completion in a single call.

Functionally equivalent to ovphysx_step() followed by ovphysx_wait_all_pending_ops(), but bypasses the async event machinery entirely (mutex acquisitions, operation map insert/lookup/cleanup). This is a measurable performance improvement for the common synchronous use case: in IsaacLab RL training at 4096 environments, step_sync saves ~0.2 ms per substep compared to step() + wait_op(), recovering roughly 5-6% of total throughput.

Use this whenever you step and immediately wait for results (i.e. you do not overlap GPU simulation with CPU work between dispatch and fetch).

Parameters:
  • handle – Physics instance handle.

  • step_dt – Timestep [s].

  • current_time – Current simulation time [s].

Returns:

ovphysx_result_t with OVPHYSX_API_SUCCESS on success.

ovphysx_result_t ovphysx_step_n_sync(
ovphysx_handle_t handle,
int32_t n_steps,
float step_dt,
float current_time,
)#

Run n_steps consecutive physics steps in a single C call.

Step i is executed with duration step_dt at simulation time current_time + i * step_dt. This saves (n_steps-1) ctypes round-trips for workloads that use decimation (one RL step = multiple physics steps).

Equivalent to calling ovphysx_step_sync(handle, step_dt, current_time + i * step_dt) for i in [0, n_steps).

Parameters:
  • handle – Physics instance handle.

  • n_steps – Number of steps to run (must be > 0).

  • step_dt – Duration of each step [s].

  • current_time – Simulation time at the start of the first step [s].

Returns:

ovphysx_result_t with OVPHYSX_API_SUCCESS on success.

ovphysx_result_t ovphysx_create_tensor_binding(
ovphysx_handle_t handle,
const ovphysx_tensor_binding_desc_t *desc,
ovphysx_tensor_binding_handle_t *out_binding_handle,
)#

Create a tensor binding for bulk data access (synchronous).

A tensor binding connects a USD prim pattern (e.g., “/World/robot*”) to a tensor type (e.g., OVPHYSX_TENSOR_RIGID_BODY_POSE_F32), enabling efficient bulk read/write of physics data for all matching prims.

If the pattern matches zero prims, the binding is still created successfully with element_count = 0. This allows the scene to be populated later.

Example: ovphysx_tensor_binding_desc_t desc = { .pattern = OVPHYSX_LITERAL(“/World/robot*”), // compile-time string literal .tensor_type = OVPHYSX_TENSOR_RIGID_BODY_POSE_F32 }; ovphysx_create_tensor_binding(handle, &desc, &binding);

ovphysx_tensor_binding_handle_t binding = 0;
ovphysx_create_tensor_binding(handle, &desc, &binding);
Side Effects

Allocates internal binding resources.

Errors

  • OVPHYSX_API_INVALID_ARGUMENT for invalid inputs

  • OVPHYSX_API_ERROR for internal failures

Parameters:
  • handle – Instance handle

  • desc – Binding descriptor with pattern and tensor_type

  • out_binding_handle – [out] Binding handle on success

Returns:

ovphysx_result_t (synchronous - completes before returning)

Pre:

handle, desc, and out_binding_handle must be valid.

Post:

Binding handle is valid until explicitly destroyed via ovphysx_destroy_tensor_binding(), or until the parent instance is destroyed.

ovphysx_result_t ovphysx_destroy_tensor_binding(
ovphysx_handle_t handle,
ovphysx_tensor_binding_handle_t binding_handle,
)#

Destroy a tensor binding and release associated resources (synchronous).

ovphysx_destroy_tensor_binding(handle, binding);
Side Effects

Releases internal resources.

Errors

  • OVPHYSX_API_NOT_FOUND if binding handle is unknown

  • OVPHYSX_API_ERROR for internal failures

Parameters:
  • handle – Instance handle

  • binding_handle – Binding to destroy

Returns:

ovphysx_result_t

Pre:

handle and binding_handle must be valid.

Post:

Binding handle is invalid after call.

ovphysx_result_t ovphysx_get_tensor_binding_spec(
ovphysx_handle_t handle,
ovphysx_tensor_binding_handle_t binding_handle,
ovphysx_tensor_spec_t *out_spec,
)#

Get complete tensor specification for a binding (preferred).

Returns dtype, ndim, and shape needed to allocate a compatible DLTensor. This is the preferred API for constructing DLTensors correctly.

NOTE: ovphysx_tensor_spec_t stores shape in a fixed-size int64[4] for a stable C ABI. Only the first ndim entries are meaningful; the remaining entries are always set to 0.

See ovphysx_tensor_type_t documentation for shapes and layouts per tensor type. Layout is always row-major contiguous (C-order). dtype is always float32.

ovphysx_tensor_spec_t spec;
ovphysx_get_tensor_binding_spec(handle, binding, &spec);
Side Effects

None.

Errors

  • OVPHYSX_API_NOT_FOUND if binding handle is unknown

  • OVPHYSX_API_ERROR for internal failures

Parameters:
  • handle – Instance handle

  • binding_handle – Tensor binding

  • out_spec – [out] Full tensor specification

Returns:

ovphysx_result_t

Pre:

handle, binding_handle, and out_spec must be valid.

Post:

out_spec is populated with dtype/shape for the binding.

ovphysx_result_t ovphysx_read_tensor_binding(
ovphysx_handle_t handle,
ovphysx_tensor_binding_handle_t binding_handle,
DLTensor *dst_tensor,
)#

The warmup is a real physics step that advances simulation time by a minimal timestep (~1ns). Physics state may change infinitesimally; this is not a dry run.

GPU tensor auto-warmup note

In GPU mode, the first tensor read or write after loading USD may perform an automatic warmup simulation step to initialize PhysX DirectGPU buffers.

For deterministic behavior, explicitly control warmup timing by loading USD, waiting for completion, then calling ovphysx_warmup_gpu() before the first tensor read or write. If you want the first observed state change to happen under your chosen timestep instead, call ovphysx_step() explicitly with that dt.

Because warmup is a real simulation step, a true “pre-warmup” GPU tensor state cannot be observed. Calling ovphysx_warmup_gpu() explicitly only makes the timing of that unavoidable step predictable. Read data from simulation into a user-provided DLTensor (synchronous).

GPU MODE WARNING: On the first GPU tensor read after loading USD, an automatic warmup simulation step may be performed to initialize PhysX DirectGPU buffers. See GPU tensor auto-warmup note.

DLTensor requirements:

  • MUST be pre-allocated with correct shape (use ovphysx_get_tensor_binding_spec())

  • dtype must be float32 (kDLFloat, 32 bits, 1 lane)

  • device must match the instance (CPU: kDLCPU, GPU: kDLCUDA)

  • layout must be contiguous row-major (C-order)

This is a blocking call that completes before returning.

ovphysx_read_tensor_binding(handle, binding, &tensor);
Side Effects

May trigger GPU warmup on first read in GPU mode.

Ownership

Caller owns dst_tensor memory.

Errors

  • OVPHYSX_API_DEVICE_MISMATCH if tensor device is incompatible

  • OVPHYSX_API_INVALID_ARGUMENT for invalid inputs

  • OVPHYSX_API_ERROR for internal failures

Parameters:
  • handle – Instance handle

  • binding_handle – Tensor binding

  • dst_tensor – Pre-allocated DLTensor with shape from ovphysx_get_tensor_binding_spec()

Returns:

ovphysx_result_t

Pre:

handle and binding_handle must be valid.

Pre:

dst_tensor must be pre-allocated and match spec (dtype/shape/device).

Post:

dst_tensor is filled with simulation data on success.

ovphysx_result_t ovphysx_warmup_gpu(ovphysx_handle_t handle)#

Explicitly initialize GPU buffers (optional, synchronous).

In GPU mode, PhysX DirectGPU buffers need one simulation step to initialize. This is normally done automatically on the first tensor read (auto-warmup).

IMPORTANT: The warmup performs a real physics simulation step with a minimal timestep (~1ns). While the effect is negligible, this means:

  • Simulation state is advanced (positions may change infinitesimally)

  • This is NOT a “dry run” - it mutates physics state

  • For deterministic initial conditions, call this before reading initial state

Call this function explicitly if you want to:

  • Control exactly when the warmup latency occurs

  • Avoid a latency spike on the first tensor read

  • Verify GPU initialization succeeded before starting your main loop

  • Ensure deterministic behavior by controlling when state mutation happens

This function is idempotent - calling it multiple times has no effect after the first successful call (per stage). In CPU mode, this is a no-op.

Note: Warmup state is reset when the stage changes (e.g., after reset() or loading a new USD file). The next tensor read will trigger warmup again.

ovphysx_warmup_gpu(handle);
Side Effects

Advances simulation by a minimal timestep in GPU mode.

Errors

  • OVPHYSX_API_GPU_NOT_AVAILABLE if GPU initialization fails

  • OVPHYSX_API_ERROR for internal failures

Parameters:

handle – Instance handle

Returns:

ovphysx_result_t

Pre:

handle must be valid.

Post:

GPU warmup completed for the active stage (if in GPU mode).

ovphysx_result_t ovphysx_write_tensor_binding(
ovphysx_handle_t handle,
ovphysx_tensor_binding_handle_t binding_handle,
const DLTensor *src_tensor,
const DLTensor *index_tensor,
)#

Write data from a user-provided DLTensor into the simulation (synchronous).

Not all tensor types are writable:

  • RIGID_BODY_FORCE_F32, RIGID_BODY_WRENCH_F32, ARTICULATION_LINK_WRENCH_F32 are WRITE-ONLY (external control inputs applied each step; reading them returns an error).

  • ARTICULATION_LINK_POSE_F32, ARTICULATION_LINK_VELOCITY_F32, ARTICULATION_LINK_ACCELERATION_F32 are READ-ONLY (no setter for individual link state).

  • Dynamics query tensors (JACOBIAN, MASS_MATRIX, CORIOLIS_AND_CENTRIFUGAL_FORCE, GRAVITY_FORCE, LINK_INCOMING_JOINT_FORCE, DOF_PROJECTED_JOINT_FORCE, BODY_INV_MASS, BODY_INV_INERTIA) are READ-ONLY.

  • DOF_ACTUATION_FORCE_F32 is read-write (not write-only). See ovphysx_tensor_type_t documentation for shapes, layouts, and read/write semantics.

GPU MODE WARNING: On the first GPU tensor write after loading USD, an automatic warmup simulation step may be performed to initialize PhysX DirectGPU buffers. See GPU tensor auto-warmup note.

This is a blocking call that completes before returning.

ovphysx_write_tensor_binding(handle, binding, &tensor, NULL);
Side Effects

Writes control or state data into the simulation.

Ownership

Caller owns src_tensor and index_tensor memory.

Errors

  • OVPHYSX_API_DEVICE_MISMATCH if tensor device is incompatible

  • OVPHYSX_API_INVALID_ARGUMENT for invalid inputs

  • OVPHYSX_API_ERROR for internal failures

Parameters:
  • handle – Instance handle

  • binding_handle – Tensor binding

  • src_tensor – User tensor with data to write (must match ovphysx_get_tensor_binding_spec())

  • index_tensor – Optional int32[K] indices for subset write. NULL = write all.

    • When index_tensor != NULL: src_tensor must still have full shape [N, …] matching the binding spec. Only the rows specified by index_tensor are written; other rows in src_tensor are ignored.

    • Indices are 0-based into the first dimension N of the binding, and must satisfy 0 <= idx < N.

    • K (index count) must satisfy K <= N.

Returns:

ovphysx_result_t

Pre:

handle and binding_handle must be valid.

Pre:

src_tensor must match dtype/shape/device.

Post:

Simulation state is updated with new values.

ovphysx_result_t ovphysx_write_tensor_binding_masked(
ovphysx_handle_t handle,
ovphysx_tensor_binding_handle_t binding_handle,
const DLTensor *src_tensor,
const DLTensor *mask_tensor,
)#

Write data from a user-provided DLTensor into the simulation using a binary mask (synchronous).

Only elements where mask[i] != 0 are written; other elements are left unchanged. This is the mask-based alternative to indexed writes via ovphysx_write_tensor_binding.

GPU MODE WARNING: On the first GPU tensor write after loading USD, an automatic warmup simulation step may be performed to initialize PhysX DirectGPU buffers. See GPU tensor auto-warmup note.

This is a blocking call that completes before returning.

ovphysx_write_tensor_binding_masked(handle, binding, &tensor, &mask);
Side Effects

Writes control or state data into the simulation for selected elements.

Ownership

Caller owns src_tensor and mask_tensor memory.

Errors

  • OVPHYSX_API_DEVICE_MISMATCH if tensor device is incompatible

  • OVPHYSX_API_INVALID_ARGUMENT for invalid inputs

  • OVPHYSX_API_ERROR for internal failures

Note

There is intentionally no corresponding read_masked function. Reads always return the full [N,…] tensor via ovphysx_read_tensor_binding(); callers that need a subset can index the result on the host/device side. This write-only mask design matches other reinforcement-learning physics APIs (e.g. Newton’s selectionAPI) where masks are used to selectively apply actions but observations are always returned in full.

Parameters:
  • handle – Instance handle

  • binding_handle – Tensor binding

  • src_tensor – User tensor with data to write. Must be full shape [N, …] matching ovphysx_get_tensor_binding_spec(). Must be float32 on matching device.

  • mask_tensor – Binary mask selecting which elements to update. Must be 1D with shape [N] where N matches the binding’s first dimension. Dtype must be bool (kDLBool, bits=8) or uint8 (kDLUInt, bits=8). Device must match the binding.

Returns:

ovphysx_result_t

Pre:

handle and binding_handle must be valid.

Pre:

src_tensor must match dtype/shape/device of the binding spec.

Pre:

mask_tensor must be 1D uint8/bool with length N on matching device.

Post:

Simulation state is updated for masked elements only.

ovphysx_result_t ovphysx_get_articulation_metadata(
ovphysx_handle_t handle,
ovphysx_tensor_binding_handle_t binding_handle,
ovphysx_articulation_metadata_t *out_metadata,
)#

Get all scalar topology metadata for an articulation binding in one call.

Fills out_metadata with dof_count, body_count, joint_count, fixed_tendon_count, spatial_tendon_count, and is_fixed_base. All values are stable for the binding lifetime; cache the result if calling more than once.

Homogeneous topology requirement: all articulations covered by this binding must have the same topology (same dof_count, body_count, joint_count, etc.). This is a fundamental constraint of the TensorAPI &#8212; tensor shapes are fixed at binding creation time. If you need to work with articulations of different sizes (e.g. a 7-DOF arm and a 30-DOF humanoid), create a separate binding for each.

For name arrays (DOF names, body names, joint names) use the corresponding ovphysx_articulation_get_*_names functions.

ovphysx_articulation_metadata_t meta;
ovphysx_get_articulation_metadata(handle, binding, &meta);
printf("DOFs: %d  Links: %d\n", meta.dof_count, meta.body_count);

Parameters:
  • handle – Instance handle

  • binding_handle – Tensor binding (must be an articulation binding)

  • out_metadata – [out] Caller-allocated struct to fill

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_articulation_get_dof_names(
ovphysx_handle_t handle,
ovphysx_tensor_binding_handle_t binding_handle,
ovphysx_string_t *out_names,
uint32_t max_names,
uint32_t *out_count,
)#

Get DOF names for the articulation.

String pointers remain valid until the binding is destroyed.

Parameters:
  • handle – Instance handle

  • binding_handle – Tensor binding (must be an articulation binding)

  • out_names – [out] Array of ovphysx_string_t to fill

  • max_names – Capacity of out_names array; set to metadata.dof_count (from ovphysx_get_articulation_metadata()) to receive all names.

  • out_count – [out] Actual number of names written

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_articulation_get_body_names(
ovphysx_handle_t handle,
ovphysx_tensor_binding_handle_t binding_handle,
ovphysx_string_t *out_names,
uint32_t max_names,
uint32_t *out_count,
)#

Get body (link) names for the articulation.

String pointers remain valid until the binding is destroyed.

Parameters:
  • handle – Instance handle

  • binding_handle – Tensor binding (must be an articulation binding)

  • out_names – [out] Array of ovphysx_string_t to fill

  • max_names – Capacity of out_names array; set to metadata.body_count (from ovphysx_get_articulation_metadata()) to receive all names.

  • out_count – [out] Actual number of names written

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_articulation_get_joint_names(
ovphysx_handle_t handle,
ovphysx_tensor_binding_handle_t binding_handle,
ovphysx_string_t *out_names,
uint32_t max_names,
uint32_t *out_count,
)#

Get joint names for the articulation.

String pointers remain valid until the binding is destroyed.

Parameters:
  • handle – Instance handle

  • binding_handle – Tensor binding (must be an articulation binding)

  • out_names – [out] Array of ovphysx_string_t to fill

  • max_names – Capacity of out_names array; set to metadata.joint_count (from ovphysx_get_articulation_metadata()) to receive all names.

  • out_count – [out] Actual number of names written

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_create_contact_binding(
ovphysx_handle_t handle,
const ovphysx_string_t *sensor_patterns,
uint32_t sensor_patterns_count,
const ovphysx_string_t *filter_patterns,
uint32_t filters_per_sensor,
uint32_t max_contact_data_count,
ovphysx_contact_binding_handle_t *out_handle,
)#

Create a contact binding for reading net contact forces and force matrices.

// Track contacts on the robot end-effector against the box obstacle.
ovphysx_string_t sensors[]  = { ovphysx_cstr("/World/robot_0/ee") };
ovphysx_string_t filters[]  = { ovphysx_cstr("/World/obstacles/box") };
ovphysx_contact_binding_handle_t cb;
ovphysx_create_contact_binding(
    handle,
    sensors, 1,          // 1 sensor pattern
    filters, 1,          // 1 filter pattern per sensor
    256,                 // max raw contact pairs
    &cb);
// After ovphysx_step():
// - net forces  tensor shape: [S, 3]   (S = matched sensor count)
// - force matrix tensor shape: [S, F, 3] (F = matched filter count per sensor)

Parameters:
  • handle – Instance handle

  • sensor_patterns – Array of USD prim path patterns matching sensor bodies

  • sensor_patterns_count – Number of sensor patterns

  • filter_patterns – Flat array of filter prim path patterns. All sensors must have the same number of filters. Total length = sensor_patterns_count * filters_per_sensor. Pass NULL with filters_per_sensor=0 for unfiltered contacts.

  • filters_per_sensor – Number of filter patterns per sensor (same for all sensors)

  • max_contact_data_count – Max contact pairs to track (for raw contact queries)

  • out_handle – [out] Contact binding handle

Returns:

ovphysx_result_t

Post:

Binding handle is valid until explicitly destroyed via ovphysx_destroy_contact_binding(), or until the parent instance is destroyed.

ovphysx_result_t ovphysx_destroy_contact_binding(
ovphysx_handle_t handle,
ovphysx_contact_binding_handle_t contact_handle,
)#

Destroy a contact binding.

Parameters:
  • handle – Instance handle

  • contact_handle – Contact binding to destroy

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_get_contact_binding_spec(
ovphysx_handle_t handle,
ovphysx_contact_binding_handle_t contact_handle,
int32_t *out_sensor_count,
int32_t *out_filter_count,
)#

Query contact view dimensions.

Parameters:
  • handle – Instance handle

  • contact_handle – Contact binding

  • out_sensor_count – [out] Number of sensor bodies matched

  • out_filter_count – [out] Number of filter bodies per sensor

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_read_contact_net_forces(
ovphysx_handle_t handle,
ovphysx_contact_binding_handle_t contact_handle,
DLTensor *dst_tensor,
)#

Read net contact forces.

dst shape: [S, 3] where S = sensor_count.

The dt for impulse-to-force conversion is taken automatically from the last ovphysx_step() call.

Parameters:
  • handle – Instance handle

  • contact_handle – Contact binding

  • dst_tensor – Pre-allocated DLTensor with shape [S, 3]

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_read_contact_force_matrix(
ovphysx_handle_t handle,
ovphysx_contact_binding_handle_t contact_handle,
DLTensor *dst_tensor,
)#

Read contact force matrix.

dst shape: [S, F, 3].

The dt for impulse-to-force conversion is taken automatically from the last ovphysx_step() call.

Parameters:
  • handle – Instance handle

  • contact_handle – Contact binding

  • dst_tensor – Pre-allocated DLTensor with shape [S, F, 3]

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_get_contact_report(
ovphysx_handle_t handle,
const ovphysx_contact_event_header_t **out_event_headers,
uint32_t *out_num_event_headers,
const ovphysx_contact_point_t **out_contact_data,
uint32_t *out_num_contact_data,
const ovphysx_friction_anchor_t **out_friction_anchors,
uint32_t *out_num_friction_anchors,
)#

Get raw contact report data for the current simulation step.

Returns per-contact-point event data &#8212; position, normal, impulse, and separation for every contact point this step. Use this for custom contact sensors, collision debugging, or per-point force analysis.

For aggregate force tensors (net forces or force matrices between sensor/filter body sets, delivered as DLPack tensors), see the Contact Binding API: ovphysx_create_contact_binding().

The header array describes contact pairs (which actors/colliders are in contact); each header references a slice of the contact data array containing per-contact-point information (position, normal, impulse, separation).

Prims involved in contacts must have PhysxContactReportAPI applied in the USD stage for contacts to be reported.

Ownership: The caller does NOT own the returned arrays. They are read-only views into internal simulation buffers. Copy any data you need to keep beyond the current step.

Pointer lifetime / invalidation: The returned pointers are valid only until the next call that advances or tears down the simulation. The following operations invalidate both arrays:

  • ovphysx_step() (the next simulation step overwrites the buffers)

  • ovphysx_reset()

  • ovphysx_remove_usd()

  • ovphysx_destroy_instance()

Parameters:
  • handle – Instance handle.

  • out_event_headers[out] Receives a pointer to the contact event header array (read-only, valid until next step).

  • out_num_event_headers[out] Number of headers in the array.

  • out_contact_data[out] Receives a pointer to the contact point array (read-only, valid until next step).

  • out_num_contact_data[out] Number of contact point entries.

  • out_friction_anchors[out] Optional. If non-NULL, receives a pointer to the friction anchor array. Each anchor has position[3] and impulse[3] in world space. Pass NULL to skip.

  • out_num_friction_anchors[out] Optional. If non-NULL, receives the friction anchor count. Pass NULL to skip.

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_get_physx_ptr(
ovphysx_handle_t handle,
const char *prim_path,
ovphysx_physx_type_t physx_type,
void **out_ptr,
)#

Get a raw PhysX SDK object pointer by USD prim path and type.

Returns the underlying PhysX object as an opaque void*. The caller must cast to the appropriate PhysX C++ type (see ovphysx_physx_type_t).

This mirrors the internal IPhysx::getPhysXPtr(path, PhysXType) API that has been used successfully in Kit-based workflows for years. A single function covers all PhysX object types &#8212; no per-type variants are needed.

Pointer lifetime: Returned pointers are valid until the next call to ovphysx_remove_usd(), ovphysx_reset(), or ovphysx_destroy(). Calls to ovphysx_step() and ovphysx_clone() do NOT invalidate existing pointers. Do not call release() on returned pointers &#8212; ovphysx owns them.

Thread safety: PhysX APIs on returned pointers must only be called between simulation steps &#8212; specifically after wait_op() completes for the preceding step and before the next ovphysx_step() call. Calling PhysX APIs while a step is in-flight is a data race.

Shapes: PxShape objects are reachable from a PxRigidActor pointer via PxRigidActor::getShapes(). You can also query them directly with OVPHYSX_PHYSX_TYPE_SHAPE.

PhysX SDK headers: Casting the returned pointer requires the PhysX SDK C++ headers (e.g. PxScene.h, PxRigidDynamic.h). The ovphysx SDK ships these headers under include/physx/; find_package(ovphysx) sets ovphysx_PHYSX_INCLUDE_DIR to point there. No PhysX library linking is needed. ovphysx bundles PhysX 5.x &#8212; obtain matching headers from the open-source repository at NVIDIA-Omniverse/PhysX (same repo that contains ovphysx). Use the headers from the same commit/release as the ovphysx build to ensure ABI compatibility.

void* scene = NULL;
ovphysx_result_t r = ovphysx_get_physx_ptr(
    handle, "/World/physicsScene", OVPHYSX_PHYSX_TYPE_SCENE, &scene);
if (r.status == OVPHYSX_API_SUCCESS && scene) {
    // Cast: physx::PxScene* pxScene = static_cast<physx::PxScene*>(scene);
}
Parameters:
  • handle – ovphysx instance handle.

  • prim_path – Null-terminated USD prim path (e.g. “/World/physicsScene”, “/World/Cube”, “/World/articulation”).

  • physx_type – Which PhysX object type to look up at that path. See ovphysx_physx_type_t for the mapping to PhysX C++ types.

  • out_ptr[out] Receives the PhysX pointer (NULL if not found).

Returns:

ovphysx_result_t with status and error info.

Pre:

A USD stage must be loaded and at least one simulation step completed (so PhysX objects exist). prim_path must be a valid absolute USD path.

ovphysx_result_t ovphysx_raycast(
ovphysx_handle_t handle,
const float origin[3],
const float direction[3],
float distance,
bool both_sides,
ovphysx_scene_query_mode_t mode,
const ovphysx_scene_query_hit_t **out_hits,
uint32_t *out_count,
)#

Cast a ray and return hits.

const ovphysx_scene_query_hit_t* hits = NULL;
uint32_t count = 0;
float origin[3] = {0, 10, 0};
float dir[3]    = {0, -1, 0};
ovphysx_raycast(handle, origin, dir, 100.0f, false,
                OVPHYSX_SCENE_QUERY_MODE_CLOSEST, &hits, &count);
if (count > 0) {
    printf("Hit at distance %f\n", hits[0].distance);
}

Parameters:
  • handle – Instance handle.

  • origin – Ray origin (world space, 3 floats).

  • direction – Normalized ray direction (3 floats).

  • distance – Maximum ray distance. Must be >= 0.

  • both_sides – If true, test both sides of mesh triangles.

  • mode – CLOSEST (0 or 1 hit), ANY (0 or 1), or ALL.

  • out_hits[out] Receives pointer to internal hit array.

  • out_count[out] Number of hits in the array.

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_sweep(
ovphysx_handle_t handle,
const ovphysx_scene_query_geometry_desc_t *geometry,
const float direction[3],
float distance,
bool both_sides,
ovphysx_scene_query_mode_t mode,
const ovphysx_scene_query_hit_t **out_hits,
uint32_t *out_count,
)#

Sweep a geometry shape along a direction and return hits.

Parameters:
  • handle – Instance handle.

  • geometry – Geometry descriptor (sphere, box, or arbitrary shape).

  • direction – Normalized sweep direction (3 floats).

  • distance – Maximum sweep distance. Must be >= 0.

  • both_sides – If true, test both sides of mesh triangles.

  • mode – CLOSEST (0 or 1 hit), ANY (0 or 1), or ALL.

  • out_hits[out] Receives pointer to internal hit array.

  • out_count[out] Number of hits in the array.

Returns:

ovphysx_result_t

ovphysx_result_t ovphysx_overlap(
ovphysx_handle_t handle,
const ovphysx_scene_query_geometry_desc_t *geometry,
ovphysx_scene_query_mode_t mode,
const ovphysx_scene_query_hit_t **out_hits,
uint32_t *out_count,
)#

Test geometry overlap against objects in the scene.

Overlap queries do not have a direction or distance. Location fields in the hit struct (normal, position, distance, face_index, material) are zeroed &#8212; only object identity (collision, rigid_body, proto_index) is populated.

Parameters:
  • handle – Instance handle.

  • geometry – Geometry descriptor (sphere, box, or arbitrary shape).

  • mode – ANY (0 or 1 result) or ALL. CLOSEST is treated as ALL.

  • out_hits[out] Receives pointer to internal hit array.

  • out_count[out] Number of hits (or overlaps) in the array.

Returns:

ovphysx_result_t

ovphysx_enqueue_result_t ovphysx_add_user_task(
ovphysx_handle_t handle,
const ovphysx_user_task_desc_t *desc,
)#
ovphysx_result_t ovphysx_wait_op(
ovphysx_handle_t handle,
ovphysx_op_index_t op_index,
uint64_t timeout_ns,
ovphysx_op_wait_result_t *out_wait_result,
)#
ovphysx_string_t ovphysx_get_last_error(void)#

Query the error string for the last failed API call on the calling thread.

The returned string is valid until the next ovphysx API call on the same thread. Returns {NULL, 0} if the last call succeeded.

ovphysx_result_t r = ovphysx_create_instance(&args, &handle);
if (r.status != OVPHYSX_API_SUCCESS) {
    ovphysx_string_t err = ovphysx_get_last_error();
    if (err.ptr)
        fprintf(stderr, "Error: %.*s\n", (int)err.length, err.ptr);
}
Threading

Thread-local storage; safe to call from any thread.

Returns:

ovphysx_string_t with the error message, or {NULL, 0} on success.

ovphysx_string_t ovphysx_get_last_op_error(
ovphysx_op_index_t op_index,
)#

Query the error string for a specific failed op_index from the last wait_op call.

After ovphysx_wait_op() reports failed operations via error_op_indices, call this function for each failed op_index to retrieve the error message. The returned string is valid until the next ovphysx_wait_op() call on the same thread.

for (size_t i = 0; i < wait_result.num_errors; ++i) {
    ovphysx_string_t err = ovphysx_get_last_op_error(wait_result.error_op_indices[i]);
    fprintf(stderr, "Op %llu failed: %.*s\n",
            wait_result.error_op_indices[i], (int)err.length, err.ptr);
}
Threading

Thread-local storage; safe to call from any thread.

Parameters:

op_index – The failed operation index (from ovphysx_op_wait_result_t.error_op_indices).

Returns:

ovphysx_string_t with the error message, or {NULL, 0} if op_index has no error.

void ovphysx_destroy_wait_result(ovphysx_op_wait_result_t *result)#

Free the error_op_indices array in an ovphysx_op_wait_result_t.

Call this after processing the wait result to release the dynamically allocated error_op_indices array.

ovphysx_destroy_wait_result(&wait_result);

Parameters:

result – Pointer to the wait result to clean up (NULL-safe).

Pre:

Safe to call with NULL or already-cleaned result.

Post:

result->error_op_indices is NULL and num_errors is 0.

ovphysx_result_t ovphysx_set_log_level(uint32_t level)#

Set the global log level threshold.

Messages below this level are suppressed for all outputs (console and registered callbacks). Callable at any time. If called before instance creation, the level is stored and applied when Carbonite initializes.

Threading

Thread-safe. Uses atomic storage internally.

Parameters:

level – Log level threshold (ovphysx_log_level_t). Default: OVPHYSX_LOG_WARNING. Must be between OVPHYSX_LOG_VERBOSE and OVPHYSX_LOG_NONE inclusive.

Returns:

ovphysx_result_t with OVPHYSX_API_SUCCESS on success, or OVPHYSX_API_INVALID_ARGUMENT if the level was out of range (no state change is applied).

uint32_t ovphysx_get_log_level(void)#

Get the current global log level threshold.

Threading

Thread-safe. Uses atomic load internally.

Returns:

The current log level (ovphysx_log_level_t).

ovphysx_result_t ovphysx_enable_default_log_output(bool enable)#

Enable or disable Carbonite’s built-in console log output.

By default, Carbonite logs to the console (stdout/stderr). When custom callbacks are registered via ovphysx_register_log_callback(), both the built-in console output and the custom callbacks receive messages, which may cause duplicate output if the callback also writes to the console.

Call this function with false to suppress the built-in console output while keeping custom callbacks active. Call with true to re-enable it.

This function is independent of callback registration and the global log level &#8212; it only controls the built-in console logger.

Callable at any time. If called before Carbonite initializes, the preference is stored and applied during initialization.

Threading

Thread-safe. Uses atomic storage internally.

Parameters:

enabletrue to enable (default), false to disable.

Returns:

ovphysx_result_t with OVPHYSX_API_SUCCESS.

ovphysx_result_t ovphysx_register_log_callback(
ovphysx_log_fn fn,
void *user_data,
)#

Register a log callback.

Multiple callbacks may be registered simultaneously. Each receives all messages at or above the global log level threshold. The caller must ensure fn and any resources referenced by user_data remain valid until ovphysx_unregister_log_callback() is called. If the callback and its resources naturally outlive the process (e.g. a static function with no user_data), calling ovphysx_unregister_log_callback() is not required.

Registering the same fn and user_data pair twice returns OVPHYSX_API_INVALID_ARGUMENT. Use different user_data values to register the same function pointer multiple times.

Note

The callback may be invoked from any thread. The implementation is thread-safe, but the callback itself must also be thread-safe.

Note

Must not be called from within a log callback. Returns OVPHYSX_API_ERROR if called during callback dispatch.

Parameters:
  • fn – Callback function pointer (must not be NULL).

  • user_data – Opaque pointer forwarded to every callback invocation (may be NULL).

Returns:

ovphysx_result_t with status.

ovphysx_result_t ovphysx_unregister_log_callback(
ovphysx_log_fn fn,
void *user_data,
)#

Unregister a previously registered log callback.

Both fn and user_data must match the values passed to ovphysx_register_log_callback(). After this function returns, the callback is guaranteed to not be running on any thread and will never be invoked again. The caller may safely destroy the callback context.

Note

Must not be called from within a log callback. Returns OVPHYSX_API_ERROR if called during callback dispatch.

Parameters:
  • fn – Callback function pointer.

  • user_data – Opaque pointer that was passed during registration (may be NULL).

Returns:

ovphysx_result_t with OVPHYSX_API_SUCCESS if found and removed.

C API Types#

Defines

OVPHYSX_LITERAL(s)#

Create ovphysx_string_t from a string LITERAL only.

For runtime strings (variables, user input), use ovphysx_cstr() instead.

OVPHYSX_INVALID_HANDLE#

Sentinel value representing an invalid/null ovphysx instance handle.

Valid handles start at 1, so 0 is reserved to indicate “no handle” or “invalid handle”. Use this when a handle parameter is required but no valid instance is available.

OVPHYSX_OP_INDEX_ALL#

Sentinel value for ovphysx_wait_op to wait for all operations submitted up to the call.

Use this when you want to ensure all outstanding operations have completed.

OVPHYSX_CREATE_ARGS_DEFAULT#

Default initializer for ovphysx_create_args.

Sets device=AUTO (GPU preferred), gpu_index=0.

Typedefs

typedef uint64_t ovphysx_handle_t#
typedef uint64_t ovphysx_usd_handle_t#
typedef uint64_t ovphysx_attribute_binding_handle_t#
typedef uint64_t ovphysx_write_map_handle_t#
typedef uint64_t ovphysx_read_map_handle_t#
typedef uint64_t ovphysx_op_index_t#
typedef uint64_t ovphysx_tensor_binding_handle_t#
typedef uint64_t ovphysx_contact_binding_handle_t#
typedef void (*ovphysx_log_fn)(uint32_t level, const char *message, void *user_data)#

Log callback function type.

Called for each message that passes the global log level threshold. The caller must ensure the function pointer remains valid until ovphysx_unregister_log_callback() is called.

Param level:

The ovphysx_log_level_t severity of the message.

Param message:

The log message string (UTF-8, null-terminated). Only valid for the duration of the callback; copy it if you need to retain it after returning.

Param user_data:

Opaque pointer passed during registration.

typedef ovphysx_result_t (*ovphysx_user_task_fn)(ovphysx_handle_t handle, ovphysx_op_index_t op_index, void *user_data)#

User task callback function type.

Called in stream order when the task executes.

Param handle:

Physics handle

Param op_index:

Operation index of this task

Param user_data:

User-provided context data

Return:

Result status (typically OVPHYSX_API_SUCCESS)

Enums

enum ovphysx_log_level_t#

Values:

enumerator OVPHYSX_LOG_VERBOSE#

All messages including verbose/debug (maps to Carbonite kLevelVerbose)

enumerator OVPHYSX_LOG_INFO#

Info, warnings, and errors.

enumerator OVPHYSX_LOG_WARNING#

Warnings and errors (default)

enumerator OVPHYSX_LOG_ERROR#

Error messages only.

enumerator OVPHYSX_LOG_NONE#

No logging.

enum ovphysx_physx_type_t#

Identifies the type of PhysX object at a USD prim path.

Used with ovphysx_get_physx_ptr() to retrieve raw PhysX SDK pointers. Values match the internal omni::physx::PhysXType enum; the named constants below cover common types. Any valid omni::physx::PhysXType integer may be passed; PhysX returns NULL for unrecognized path/type combinations.

Enum value

PhysX SDK C++ type

OVPHYSX_PHYSX_TYPE_SCENE

physx::PxScene

OVPHYSX_PHYSX_TYPE_MATERIAL

physx::PxMaterial

OVPHYSX_PHYSX_TYPE_SHAPE

physx::PxShape

OVPHYSX_PHYSX_TYPE_COMPOUND_SHAPE

omni::physx::PhysXCompoundShape (see note)

OVPHYSX_PHYSX_TYPE_ACTOR

physx::PxRigidDynamic/PxRigidStatic

OVPHYSX_PHYSX_TYPE_JOINT

physx::PxJoint (standalone joints)

OVPHYSX_PHYSX_TYPE_CUSTOM_JOINT

physx::PxJoint (custom joints)

OVPHYSX_PHYSX_TYPE_ARTICULATION

physx::PxArticulationReducedCoordinate

OVPHYSX_PHYSX_TYPE_LINK

physx::PxArticulationLink

OVPHYSX_PHYSX_TYPE_LINK_JOINT

physx::PxArticulationJointReducedCoordinate

OVPHYSX_PHYSX_TYPE_PARTICLE_SYSTEM

physx::PxPBDParticleSystem

OVPHYSX_PHYSX_TYPE_PARTICLE_SET

physx::PxParticleBuffer

OVPHYSX_PHYSX_TYPE_PHYSICS

physx::PxPhysics

Note: COMPOUND_SHAPE returns an omni::physx::PhysXCompoundShape*, defined in the PhysX repo at omni/include/private/omni/physx/PhysXCompoundShape.h. Call getShapes() on the result to access the underlying physx::PxShape pointers.

Values:

enumerator OVPHYSX_PHYSX_TYPE_SCENE#
enumerator OVPHYSX_PHYSX_TYPE_MATERIAL#
enumerator OVPHYSX_PHYSX_TYPE_SHAPE#
enumerator OVPHYSX_PHYSX_TYPE_COMPOUND_SHAPE#
enumerator OVPHYSX_PHYSX_TYPE_ACTOR#
enumerator OVPHYSX_PHYSX_TYPE_JOINT#
enumerator OVPHYSX_PHYSX_TYPE_CUSTOM_JOINT#
enumerator OVPHYSX_PHYSX_TYPE_ARTICULATION#
enumerator OVPHYSX_PHYSX_TYPE_LINK#
enumerator OVPHYSX_PHYSX_TYPE_PARTICLE_SYSTEM#
enumerator OVPHYSX_PHYSX_TYPE_PARTICLE_SET#
enumerator OVPHYSX_PHYSX_TYPE_PHYSICS#
enum ovphysx_scene_query_mode_t#

Scene query mode &#8212; controls how many hits are returned.

Values:

enumerator OVPHYSX_SCENE_QUERY_MODE_CLOSEST#

Return the single closest hit (or none).

enumerator OVPHYSX_SCENE_QUERY_MODE_ANY#

Return whether any hit exists (0 or 1 result).

enumerator OVPHYSX_SCENE_QUERY_MODE_ALL#

Return all hits.

enum ovphysx_scene_query_geometry_type_t#

Geometry type for sweep and overlap queries.

SHAPE accepts any UsdGeomGPrim path (sphere, box, capsule, cone, cylinder, mesh, etc.). For meshes the runtime uses a convex approximation internally.

Values:

enumerator OVPHYSX_SCENE_QUERY_GEOMETRY_SPHERE#

Sphere defined by radius + center position.

enumerator OVPHYSX_SCENE_QUERY_GEOMETRY_BOX#

Oriented box defined by half-extents + pose.

enumerator OVPHYSX_SCENE_QUERY_GEOMETRY_SHAPE#

Arbitrary UsdGeomGPrim identified by prim path.

enum ovphysx_api_status_t#

Values:

enumerator OVPHYSX_API_SUCCESS#

Operation completed or enqueued successfully.

enumerator OVPHYSX_API_ERROR#

Operation failed - check error field.

enumerator OVPHYSX_API_TIMEOUT#

Operation timed out.

enumerator OVPHYSX_API_NOT_IMPLEMENTED#

Feature not yet implemented.

enumerator OVPHYSX_API_INVALID_ARGUMENT#

Invalid argument provided.

enumerator OVPHYSX_API_NOT_FOUND#

Requested resource not found (handle unknown, binding invalidated)

enumerator OVPHYSX_API_BUFFER_TOO_SMALL#

Caller-supplied buffer is too small; check out_required_size.

enumerator OVPHYSX_API_DEVICE_MISMATCH#

Tensor device doesn’t match binding’s expected device.

enumerator OVPHYSX_API_GPU_NOT_AVAILABLE#

GPU requested but not available or CUDA init failed.

enum ovphysx_tensor_type_t#

Tensor type identifiers for bulk GPU data access.

Each value specifies what physical quantity the tensor represents, its shape, data type, and coordinate frame.

Coordinate conventions:

  • All poses and velocities are in WORLD FRAME

  • DOF data (positions, velocities, targets) are in JOINT SPACE

  • Quaternions use [qx, qy, qz, qw] ordering (xyzw)

RIGID BODY TENSORS#

OVPHYSX_TENSOR_RIGID_BODY_POSE_F32 Shape: [N, 7] where N = number of rigid bodies Layout: [px, py, pz, qx, qy, qz, qw] (position xyz, quaternion xyzw) Frame: World DType: float32

OVPHYSX_TENSOR_RIGID_BODY_VELOCITY_F32 Shape: [N, 6] where N = number of rigid bodies Layout: [vx, vy, vz, wx, wy, wz] (linear xyz, angular xyz) Frame: World DType: float32

ARTICULATION ROOT TENSORS#

OVPHYSX_TENSOR_ARTICULATION_ROOT_POSE_F32 Shape: [N, 7] where N = number of articulations Layout: [px, py, pz, qx, qy, qz, qw] Frame: World DType: float32

OVPHYSX_TENSOR_ARTICULATION_ROOT_VELOCITY_F32 Shape: [N, 6] where N = number of articulations Layout: [vx, vy, vz, wx, wy, wz] Frame: World DType: float32

ARTICULATION LINK TENSORS (3D - per-link data)#

OVPHYSX_TENSOR_ARTICULATION_LINK_POSE_F32 Shape: [N, L, 7] where N = articulations, L = max links Layout: [px, py, pz, qx, qy, qz, qw] per link Frame: World DType: float32 Note: For articulations with fewer than L links, extra entries are zero-padded

OVPHYSX_TENSOR_ARTICULATION_LINK_VELOCITY_F32 Shape: [N, L, 6] where N = articulations, L = max links Layout: [vx, vy, vz, wx, wy, wz] per link Frame: World DType: float32

ARTICULATION DOF TENSORS (joint space)#

OVPHYSX_TENSOR_ARTICULATION_DOF_POSITION_F32 Shape: [N, D] where N = articulations, D = max DOFs Layout: Joint positions in articulation DOF order Units: Radians (revolute) or meters (prismatic) DType: float32 Note: For articulations with fewer than D DOFs, extra entries are zero-padded

OVPHYSX_TENSOR_ARTICULATION_DOF_VELOCITY_F32 Shape: [N, D] Layout: Joint velocities Units: rad/s or m/s DType: float32

OVPHYSX_TENSOR_ARTICULATION_DOF_POSITION_TARGET_F32 Shape: [N, D] Layout: Position targets for position-controlled joints DType: float32

OVPHYSX_TENSOR_ARTICULATION_DOF_VELOCITY_TARGET_F32 Shape: [N, D] Layout: Velocity targets for velocity-controlled joints DType: float32

OVPHYSX_TENSOR_ARTICULATION_DOF_ACTUATION_FORCE_F32 Shape: [N, D] Layout: Actuation forces/torques applied to joints. Units: N or Nm DType: float32

NOTE: This reads the staging buffer associated with the PhysX GPU joint-force API (write-only internally). Depending on simulation settings, it may not match the solver-applied joint forces for the current step.

RIGID BODY PROPERTY TENSORS (standalone non-articulated bodies)#

OVPHYSX_TENSOR_RIGID_BODY_MASS_F32 Shape: [N] where N = number of rigid bodies Layout: scalar mass per body Units: kilograms DType: float32

OVPHYSX_TENSOR_RIGID_BODY_INERTIA_F32 Shape: [N, 9] where N = number of rigid bodies Layout: row-major 3x3 inertia tensor in center-of-mass frame Units: kg*m^2 DType: float32

OVPHYSX_TENSOR_RIGID_BODY_COM_POSE_F32 Shape: [N, 7] where N = number of rigid bodies Layout: [px, py, pz, qx, qy, qz, qw] (position xyz, quaternion xyzw) Frame: Local frame (relative to body origin) DType: float32

ARTICULATION LINK ACCELERATION (READ-ONLY)#

OVPHYSX_TENSOR_ARTICULATION_LINK_ACCELERATION_F32 Shape: [N, L, 6] where N = articulations, L = max links Layout: [ax, ay, az, alpha_x, alpha_y, alpha_z] (linear + angular acc) Frame: World DType: float32

ARTICULATION DOF PROPERTY TENSORS (read/write)#

OVPHYSX_TENSOR_ARTICULATION_DOF_STIFFNESS_F32 Shape: [N, D] where N = articulations, D = max DOFs Layout: Joint stiffness values DType: float32

OVPHYSX_TENSOR_ARTICULATION_DOF_DAMPING_F32 Shape: [N, D] Layout: Joint damping values DType: float32

OVPHYSX_TENSOR_ARTICULATION_DOF_LIMIT_F32 Shape: [N, D, 2] Layout: (lower, upper) position limit per DOF DType: float32

OVPHYSX_TENSOR_ARTICULATION_DOF_MAX_VELOCITY_F32 Shape: [N, D] Layout: Maximum velocity per DOF Units: rad/s or m/s DType: float32

OVPHYSX_TENSOR_ARTICULATION_DOF_MAX_FORCE_F32 Shape: [N, D] Layout: Maximum force/torque per DOF Units: N or Nm DType: float32

OVPHYSX_TENSOR_ARTICULATION_DOF_ARMATURE_F32 Shape: [N, D] Layout: Armature (reflected inertia) per DOF DType: float32

OVPHYSX_TENSOR_ARTICULATION_DOF_FRICTION_PROPERTIES_F32 Shape: [N, D, 3] Layout: (static, dynamic, viscous) friction coefficients per DOF DType: float32

ARTICULATION BODY PROPERTY TENSORS (read/write, except where noted)#

OVPHYSX_TENSOR_ARTICULATION_BODY_MASS_F32 Shape: [N, L] where N = articulations, L = max links Layout: Mass per link Units: kilograms DType: float32

OVPHYSX_TENSOR_ARTICULATION_BODY_COM_POSE_F32 Shape: [N, L, 7] Layout: [px, py, pz, qx, qy, qz, qw] (COM local pose per link) Frame: Local frame (relative to link origin) DType: float32

OVPHYSX_TENSOR_ARTICULATION_BODY_INERTIA_F32 Shape: [N, L, 9] Layout: row-major 3x3 inertia tensor in COM frame per link Units: kg*m^2 DType: float32

OVPHYSX_TENSOR_ARTICULATION_BODY_INV_MASS_F32 (READ-ONLY) Shape: [N, L] Layout: Inverse mass (1/m) per link DType: float32

OVPHYSX_TENSOR_ARTICULATION_BODY_INV_INERTIA_F32 (READ-ONLY) Shape: [N, L, 9] Layout: row-major 3x3 inverse inertia in COM frame per link DType: float32

DYNAMICS QUERY TENSORS (READ-ONLY)#

OVPHYSX_TENSOR_ARTICULATION_JACOBIAN_F32 Shape: [N, R, C] &#8212; obtain R, C from getJacobianShape() Fixed-base: R = (numLinks - 1) * 6, C = numDofs Floating-base: R = (numLinks - 1) * 6 + 6, C = numDofs + 6 Floating-base columns: base 6 DOFs at indices 0..5, joint DOFs at 6..C-1 DType: float32

OVPHYSX_TENSOR_ARTICULATION_MASS_MATRIX_F32 Shape: [N, M, M] &#8212; obtain M from getGeneralizedMassMatrixShape() Layout: Generalized (joint-space) mass matrix DType: float32

OVPHYSX_TENSOR_ARTICULATION_CORIOLIS_AND_CENTRIFUGAL_FORCE_F32 Shape: [N, M] Layout: Combined Coriolis and centrifugal compensation forces DType: float32

OVPHYSX_TENSOR_ARTICULATION_GRAVITY_FORCE_F32 Shape: [N, M] Layout: Gravity compensation forces DType: float32

OVPHYSX_TENSOR_ARTICULATION_LINK_INCOMING_JOINT_FORCE_F32 Shape: [N, L, 6] Layout: [fx, fy, fz, tx, ty, tz] per link incoming joint force DType: float32

OVPHYSX_TENSOR_ARTICULATION_DOF_PROJECTED_JOINT_FORCE_F32 Shape: [N, D] Layout: Projected joint forces per DOF DType: float32

FIXED TENDON PROPERTY TENSORS (read/write, require articulation with tendons)#

OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_STIFFNESS_F32 Shape: [N, T] where N = articulations, T = max fixed tendons Layout: Tendon stiffness DType: float32

OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_DAMPING_F32 Shape: [N, T] Layout: Tendon damping DType: float32

OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_LIMIT_STIFFNESS_F32 Shape: [N, T] Layout: Stiffness of the tendon length limit spring DType: float32

OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_LIMIT_F32 Shape: [N, T, 2] Layout: (lower, upper) tendon length limits DType: float32

OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_REST_LENGTH_F32 Shape: [N, T] Layout: Tendon rest length DType: float32

OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_OFFSET_F32 Shape: [N, T] Layout: Tendon offset DType: float32

SPATIAL TENDON PROPERTY TENSORS (read/write, require articulation with spatial tendons)#

OVPHYSX_TENSOR_ARTICULATION_SPATIAL_TENDON_STIFFNESS_F32 Shape: [N, T] where N = articulations, T = max spatial tendons Layout: Spatial tendon stiffness DType: float32

OVPHYSX_TENSOR_ARTICULATION_SPATIAL_TENDON_DAMPING_F32 Shape: [N, T] Layout: Spatial tendon damping DType: float32

OVPHYSX_TENSOR_ARTICULATION_SPATIAL_TENDON_LIMIT_STIFFNESS_F32 Shape: [N, T] Layout: Stiffness of the spatial tendon length limit spring DType: float32

OVPHYSX_TENSOR_ARTICULATION_SPATIAL_TENDON_OFFSET_F32 Shape: [N, T] Layout: Spatial tendon offset DType: float32

Values:

enumerator OVPHYSX_TENSOR_INVALID#
enumerator OVPHYSX_TENSOR_RIGID_BODY_POSE_F32#

[N, 7] poses in world frame

enumerator OVPHYSX_TENSOR_RIGID_BODY_VELOCITY_F32#

[N, 6] velocities in world frame

enumerator OVPHYSX_TENSOR_RIGID_BODY_MASS_F32#

[N] mass per body

enumerator OVPHYSX_TENSOR_RIGID_BODY_INERTIA_F32#

[N, 9] row-major 3x3 inertia tensor

enumerator OVPHYSX_TENSOR_RIGID_BODY_COM_POSE_F32#

[N, 7] COM local pose (px,py,pz,qx,qy,qz,qw)

enumerator OVPHYSX_TENSOR_ARTICULATION_ROOT_POSE_F32#

[N, 7] root poses

enumerator OVPHYSX_TENSOR_ARTICULATION_ROOT_VELOCITY_F32#

[N, 6] root velocities

[N, L, 7] link poses

[N, L, 6] link velocities

[N, L, 6] link accelerations (lin_acc xyz + ang_acc xyz), READ-ONLY

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_POSITION_F32#

[N, D] joint positions

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_VELOCITY_F32#

[N, D] joint velocities

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_POSITION_TARGET_F32#

[N, D] position targets

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_VELOCITY_TARGET_F32#

[N, D] velocity targets

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_ACTUATION_FORCE_F32#

[N, D] actuation forces

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_STIFFNESS_F32#

[N, D] joint stiffness

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_DAMPING_F32#

[N, D] joint damping

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_LIMIT_F32#

[N, D, 2] (lower, upper) per DOF

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_MAX_VELOCITY_F32#

[N, D] max velocity per DOF

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_MAX_FORCE_F32#

[N, D] max force per DOF

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_ARMATURE_F32#

[N, D] armature per DOF

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_FRICTION_PROPERTIES_F32#

[N, D, 3] (static, dynamic, viscous)

enumerator OVPHYSX_TENSOR_RIGID_BODY_FORCE_F32#

External forces/wrenches - WRITE-ONLY (control inputs applied each step).

All components are in global (world) frame, including application position.

WRENCH layout: [fx, fy, fz, tx, ty, tz, px, py, pz]

  • (fx,fy,fz) = force vector in world frame

  • (tx,ty,tz) = torque vector in world frame

  • (px,py,pz) = force application position in world frame [N, 3] forces at center of mass

enumerator OVPHYSX_TENSOR_RIGID_BODY_WRENCH_F32#

[N, 9] row-major: [fx,fy,fz,tx,ty,tz,px,py,pz] per body

[N, L, 9] row-major: same layout per link

enumerator OVPHYSX_TENSOR_ARTICULATION_BODY_MASS_F32#

[N, L] mass per link

enumerator OVPHYSX_TENSOR_ARTICULATION_BODY_COM_POSE_F32#

[N, L, 7] COM local pose (px,py,pz,qx,qy,qz,qw)

enumerator OVPHYSX_TENSOR_ARTICULATION_BODY_INERTIA_F32#

[N, L, 9] row-major 3x3 inertia in COM frame

enumerator OVPHYSX_TENSOR_ARTICULATION_BODY_INV_MASS_F32#

[N, L] inverse mass (1/m) per link (READ-ONLY)

enumerator OVPHYSX_TENSOR_ARTICULATION_BODY_INV_INERTIA_F32#

[N, L, 9] inverse inertia in COM frame (READ-ONLY)

enumerator OVPHYSX_TENSOR_ARTICULATION_JACOBIAN_F32#

[N, R, C] from getJacobianShape().

For fixed-base: R = (numLinks-1)*6, C = numDofs. For floating-base: R = (numLinks-1)*6 + 6, C = numDofs + 6. Floating-base columns: base 6 DOFs at indices 0..5, joint DOFs at 6..C-1.

enumerator OVPHYSX_TENSOR_ARTICULATION_MASS_MATRIX_F32#

[N, M, M] from getGeneralizedMassMatrixShape()

enumerator OVPHYSX_TENSOR_ARTICULATION_CORIOLIS_AND_CENTRIFUGAL_FORCE_F32#

[N, M] Coriolis + centrifugal forces (both terms, from getCoriolisAndCentrifugalCompensationForces())

enumerator OVPHYSX_TENSOR_ARTICULATION_GRAVITY_FORCE_F32#

[N, M] gravity compensation

[N, L, 6] per-link incoming joint force

enumerator OVPHYSX_TENSOR_ARTICULATION_DOF_PROJECTED_JOINT_FORCE_F32#

[N, D] projected joint forces (READ-ONLY)

enumerator OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_STIFFNESS_F32#

[N, T] tendon stiffness

enumerator OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_DAMPING_F32#

[N, T] tendon damping

enumerator OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_LIMIT_STIFFNESS_F32#

[N, T] tendon limit stiffness

enumerator OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_LIMIT_F32#

[N, T, 2] (lower, upper) tendon limits

enumerator OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_REST_LENGTH_F32#

[N, T] tendon rest length

enumerator OVPHYSX_TENSOR_ARTICULATION_FIXED_TENDON_OFFSET_F32#

[N, T] tendon offset

enumerator OVPHYSX_TENSOR_ARTICULATION_SPATIAL_TENDON_STIFFNESS_F32#

[N, T] spatial tendon stiffness

enumerator OVPHYSX_TENSOR_ARTICULATION_SPATIAL_TENDON_DAMPING_F32#

[N, T] spatial tendon damping

enumerator OVPHYSX_TENSOR_ARTICULATION_SPATIAL_TENDON_LIMIT_STIFFNESS_F32#

[N, T] spatial tendon limit stiffness

enumerator OVPHYSX_TENSOR_ARTICULATION_SPATIAL_TENDON_OFFSET_F32#

[N, T] spatial tendon offset

enumerator OVPHYSX_TENSOR_RIGID_BODY_SHAPE_FRICTION_AND_RESTITUTION_F32#

[N, S, 3] (static friction, dynamic friction, restitution) per shape

enumerator OVPHYSX_TENSOR_RIGID_BODY_CONTACT_OFFSET_F32#

[N, S] contact offset per shape

enumerator OVPHYSX_TENSOR_RIGID_BODY_REST_OFFSET_F32#

[N, S] rest offset per shape

enumerator OVPHYSX_TENSOR_ARTICULATION_SHAPE_FRICTION_AND_RESTITUTION_F32#

[N, S, 3] (static friction, dynamic friction, restitution) per link shape

enumerator OVPHYSX_TENSOR_ARTICULATION_CONTACT_OFFSET_F32#

[N, S] contact offset per link shape

enumerator OVPHYSX_TENSOR_ARTICULATION_REST_OFFSET_F32#

[N, S] rest offset per link shape

enum ovphysx_device_t#

Simulation device/backend selection.

Controls whether physics simulation runs on CPU or GPU.

AUTO mode (default, OVPHYSX_DEVICE_AUTO):

  • GPU preferred: uses GPU if a usable CUDA driver is detected, otherwise CPU

  • Recommended for portable applications that should work on any machine

GPU mode (OVPHYSX_DEVICE_GPU):

  • Enables PhysX GPU acceleration and DirectGPU API

  • TensorBinding works with GPU tensors (kDLCUDA) for zero-copy access

  • Requires a warmup step() before GPU tensor reads

CPU mode (OVPHYSX_DEVICE_CPU):

  • Uses standard PhysX CPU simulation

  • TensorBinding works with CPU tensors (kDLCPU)

  • No warmup step required

Warning

All instances within the same process must use the same device mode. The device setting is applied to process-global Carbonite/PhysX state during the first ovphysx_create_instance() call and cannot be changed afterwards. Creating a CPU instance after a GPU instance (or vice versa) in the same process will fail with OVPHYSX_API_INVALID_ARGUMENT.

Values:

enumerator OVPHYSX_DEVICE_AUTO#

AUTO (GPU PREFERRED) &#8212; zero-init safe default.

ovphysx prefers GPU simulation when a usable CUDA driver + CUDA device are available. If CUDA is unavailable, ovphysx falls back to CPU-only simulation and still creates the instance successfully.

This is the recommended default for best developer UX: a single wheel/ SDK works on both GPU and CPU-only machines without special casing.

GPU ordinal handling:

  • If gpu_index >= 0, that ordinal is used when GPU is selected.

  • If gpu_index == -1, ovphysx uses PhysX’s default CUDA selection.

enumerator OVPHYSX_DEVICE_GPU#

GPU simulation (GPU REQUIRED).

This mode requires a usable CUDA driver + at least one CUDA device. If CUDA is unavailable, ovphysx_create_instance() fails with OVPHYSX_API_GPU_NOT_AVAILABLE. There is no silent fallback to CPU.

Use this when your application depends on GPU/DirectGPU behavior and you want an explicit error on CPU-only machines.

enumerator OVPHYSX_DEVICE_CPU#

CPU-only simulation (GPU DISABLED).

This mode never attempts to use CUDA and is expected to work on machines without a CUDA driver/GPU.

enum ovphysx_config_key_type_t#

Config key type discriminator — selects which key/value union members are valid.

Values:

enumerator OVPHYSX_CONFIG_KEY_TYPE_BOOL#

Key from ovphysx_config_bool_t, value is bool.

enumerator OVPHYSX_CONFIG_KEY_TYPE_INT32#

Key from ovphysx_config_int32_t, value is int32_t.

enumerator OVPHYSX_CONFIG_KEY_TYPE_FLOAT#

Key from ovphysx_config_float_t, value is float.

enumerator OVPHYSX_CONFIG_KEY_TYPE_STRING#

Key from ovphysx_config_string_t, value is ovphysx_string_t.

enumerator OVPHYSX_CONFIG_KEY_TYPE_CARBONITE#

Escape hatch: arbitrary Carbonite path (string key + string value)

enumerator OVPHYSX_CONFIG_KEY_TYPE_COUNT#
enum ovphysx_config_bool_t#

Boolean config keys.

Value type: bool.

Values:

enumerator OVPHYSX_CONFIG_DISABLE_CONTACT_PROCESSING#

/physics/disableContactProcessing

enumerator OVPHYSX_CONFIG_COLLISION_CONE_CUSTOM_GEOMETRY#

/physics/collisionConeCustomGeometry

enumerator OVPHYSX_CONFIG_COLLISION_CYLINDER_CUSTOM_GEOMETRY#

/physics/collisionCylinderCustomGeometry

enumerator OVPHYSX_CONFIG_BOOL_COUNT#
enum ovphysx_config_int32_t#

Int32 config keys.

Value type: int32_t.

Values:

enumerator OVPHYSX_CONFIG_NUM_THREADS#

/physics/numThreads

enumerator OVPHYSX_CONFIG_SCENE_MULTI_GPU_MODE#

/physics/sceneMultiGPUMode (0=disabled, 1=all, 2=skip-first)

enumerator OVPHYSX_CONFIG_INT32_COUNT#
enum ovphysx_config_float_t#

Float config keys (reserved for future use).

Value type: float.

Values:

enumerator OVPHYSX_CONFIG_FLOAT_COUNT#
enum ovphysx_config_string_t#

String config keys (reserved for future use).

Value type: ovphysx_string_t.

Values:

enumerator OVPHYSX_CONFIG_STRING_COUNT#

Functions

static inline ovphysx_string_t ovphysx_cstr(const char *cstr)#

Helper function to create ovphysx_string_t from a null-terminated C string.

Returns empty string if cstr is NULL.

struct ovphysx_string_t#
#include <include/ovphysx/ovphysx_types.h>

String with pointer and length.

Strings are NOT guaranteed to be null-terminated. Always use the length field. Use OVPHYSX_LITERAL(“literal”) or ovphysx_cstr() for convenient construction.

Public Members

const char *ptr#

Pointer to string data (not guaranteed null-terminated)

size_t length#

Length in bytes.

struct ovphysx_scene_query_geometry_desc_t#
#include <include/ovphysx/ovphysx_types.h>

Geometry descriptor for sweep/overlap queries.

Set type and fill the corresponding union member.

Public Members

ovphysx_scene_query_geometry_type_t type#
float radius#

Sphere radius.

float position[3]#

Sphere center (world space).

Box center (world space).

struct ovphysx_scene_query_geometry_desc_t::[anonymous]::[anonymous] sphere#
float half_extent[3]#

Box half-extents.

float rotation[4]#

Box orientation quaternion (x, y, z, w).

struct ovphysx_scene_query_geometry_desc_t::[anonymous]::[anonymous] box#
const char *prim_path#

Null-terminated USD prim path for any UsdGeomGPrim.

struct ovphysx_scene_query_geometry_desc_t::[anonymous]::[anonymous] shape#
union ovphysx_scene_query_geometry_desc_t::[anonymous] [anonymous]#
struct ovphysx_scene_query_hit_t#
#include <include/ovphysx/ovphysx_types.h>

Scene query hit result.

Used for raycast, sweep, and overlap queries. For overlap queries the location fields (normal, position, distance, face_index, material) are zeroed &#8212; only the object identity fields are populated.

Path fields (collision, rigid_body, material) are uint64-encoded SdfPaths matching the internal Omni PhysX representation.

Public Members

uint64_t collision#

Collision shape SdfPath (uint64 encoded).

uint64_t rigid_body#

Rigid body SdfPath (uint64 encoded).

uint32_t proto_index#

Point instancer prototype index (0xFFFFFFFF if N/A).

float normal[3]#

Hit normal (world space).

Zero for overlap queries.

float position[3]#

Hit position (world space).

Zero for overlap queries.

float distance#

Hit distance along ray/sweep direction.

Zero for overlap.

uint32_t face_index#

Triangle mesh face index.

Zero for non-mesh hits.

uint64_t material#

Material SdfPath (uint64 encoded).

Zero for overlap.

struct ovphysx_result_t#
#include <include/ovphysx/ovphysx_types.h>

Result returned by synchronous API functions.

On failure (status != OVPHYSX_API_SUCCESS), call ovphysx_get_last_error() on the same thread to retrieve the error message.

Public Members

ovphysx_api_status_t status#

Operation status code.

struct ovphysx_enqueue_result_t#
#include <include/ovphysx/ovphysx_types.h>

Result returned by asynchronous API functions.

On failure (status != OVPHYSX_API_SUCCESS), call ovphysx_get_last_error() on the same thread to retrieve the error message.

Public Members

ovphysx_api_status_t status#

Operation status code.

ovphysx_op_index_t op_index#

Operation index for async tracking.

struct ovphysx_op_wait_result_t#
#include <include/ovphysx/ovphysx_types.h>

Result from ovphysx_wait_op() containing failed op indices and pending operation status.

For each failed op index, call ovphysx_get_last_op_error(op_index) to retrieve the error message. Free this struct via ovphysx_destroy_wait_result().

Public Members

ovphysx_op_index_t *error_op_indices#

Array of op indices that failed (free via ovphysx_destroy_wait_result)

size_t num_errors#

Number of failed op indices.

ovphysx_op_index_t lowest_pending_op_index#

Lowest operation index still pending, 0 if all complete.

struct ovphysx_tensor_binding_desc_t#
#include <include/ovphysx/ovphysx_types.h>

Descriptor for creating a tensor binding.

A tensor binding connects a list of USD prim paths to a tensor type, enabling bulk read/write of physics data for all matching prims.

Prim selection (mutually exclusive - use ONE of these):

  • pattern: Glob pattern like “/World/robot*” or “/World/env[N]/robot”

  • prim_paths: Explicit list of exact prim paths

Precedence rules:

  1. If prim_paths != NULL AND prim_paths_count > 0, uses explicit paths

  2. Else if pattern.ptr != NULL AND pattern.length > 0, uses pattern

  3. Else returns OVPHYSX_API_INVALID_ARGUMENT

When prim_paths is used, pattern is completely ignored (not combined).

Example with pattern: ovphysx_tensor_binding_desc_t desc = { .pattern = OVPHYSX_LITERAL(“/World/robot*”), .tensor_type = OVPHYSX_TENSOR_RIGID_BODY_POSE_F32 };

Example with explicit prim paths: ovphysx_string_t paths[] = { OVPHYSX_LITERAL(“/World/env1/robot”), OVPHYSX_LITERAL(“/World/env4/robot”), OVPHYSX_LITERAL(“/World/env5/robot”) }; ovphysx_tensor_binding_desc_t desc = { .prim_paths = paths, .prim_paths_count = 3, .tensor_type = OVPHYSX_TENSOR_RIGID_BODY_POSE_F32 };

Public Members

ovphysx_string_t pattern#

USD path glob pattern (ignored if prim_paths is set)

const ovphysx_string_t *prim_paths#

Explicit list of exact prim paths (NULL = use pattern)

uint32_t prim_paths_count#

Number of prim paths (0 = use pattern)

ovphysx_tensor_type_t tensor_type#

Type of tensor data to bind.

struct ovphysx_tensor_spec_t#
#include <include/ovphysx/ovphysx_types.h>

Complete tensor specification for DLTensor construction.

Use ovphysx_get_tensor_binding_spec() to get the exact dtype, rank, and shape needed to allocate a compatible tensor. This is the preferred API for constructing DLTensors.

Tensor specifications by type:

  • Rigid body pose: ndim=2, shape=[N, 7]

  • Rigid body velocity: ndim=2, shape=[N, 6]

  • Articulation root: ndim=2, shape=[N, 7] or [N, 6]

  • Articulation links: ndim=3, shape=[N, L, 7] or [N, L, 6]

  • Articulation DOF: ndim=2, shape=[N, D]

All tensor types use:

  • dtype: float32 (kDLFloat, 32 bits, 1 lane)

  • Layout: row-major contiguous (C-order)

Public Members

DLDataType dtype#

DLPack data type (always float32 currently)

int32_t ndim#

Number of dimensions (2 or 3)

int64_t shape[4]#

Shape dimensions [dim0, dim1, dim2, 0].

struct ovphysx_articulation_metadata_t#
#include <include/ovphysx/ovphysx_types.h>

Articulation topology metadata returned by ovphysx_get_articulation_metadata().

All fields are read at binding-creation time and remain constant for the lifetime of the binding.

String arrays (DOF names, body names, joint names) are NOT included here because they are variable-length and require caller-allocated buffers; use ovphysx_articulation_get_dof_names / get_body_names / get_joint_names instead.

Public Members

int32_t dof_count#

Number of degrees of freedom (DOFs)

int32_t body_count#

Number of links.

int32_t joint_count#

Number of joints.

int32_t fixed_tendon_count#

Max fixed tendons (0 if none)

int32_t spatial_tendon_count#

Max spatial tendons (0 if none)

bool is_fixed_base#

True if base link is fixed in world.

struct ovphysx_cuda_sync_t#
#include <include/ovphysx/ovphysx_types.h>

CUDA synchronization for GPU operations.

Controls when the system accesses user memory and when completion is signaled.

Fields: stream: CUDA stream for the operation

  • 0 = use default CUDA stream

  • ~0 (all bits set) = unspecified, system chooses

  • other = cudaStream_t cast to uintptr_t

wait_event: CUDA event the system waits on BEFORE accessing user memory

  • 0 = no wait (system may access memory immediately during operation execution)

  • non-zero = cudaEvent_t cast to uintptr_t

  • System waits: cudaStreamWaitEvent(internal_stream, wait_event, 0)

  • Use this to ensure your GPU kernels have finished writing to buffers

signal_event: CUDA event the system records AFTER operation completes

  • 0 = no signal

  • non-zero = cudaEvent_t cast to uintptr_t

  • System records: cudaEventRecord(signal_event, internal_stream)

  • Use this to synchronize downstream GPU work with operation completion

See individual function documentation for operation-specific semantics.

Public Members

uintptr_t stream#

CUDA stream: 0=default, ~0=unspecified.

uintptr_t wait_event#

CUDA event to wait on before accessing user memory: 0=none.

uintptr_t signal_event#

CUDA event to record after operation completes: 0=none.

struct ovphysx_user_task_desc_t#
#include <include/ovphysx/ovphysx_types.h>

Description for enqueueing a user task.

Public Members

ovphysx_user_task_fn run#

Task callback function.

void *user_data#

User context (lifetime must be synchronized through events)

struct ovphysx_contact_event_header_t#
#include <include/ovphysx/ovphysx_types.h>

Contact event header — describes one contact pair.

ABI-compatible with omni::physx::ContactEventHeader. Each header references a slice of the contact data array (contactDataOffset .. contactDataOffset + numContactData).

Public Members

int32_t type#

0 = found, 1 = lost, 2 = persist

int64_t stageId#

USD stage ID.

uint64_t actor0#

Actor 0 USD path (SdfPath encoded as uint64)

uint64_t actor1#

Actor 1 USD path.

uint64_t collider0#

Collider 0 USD path.

uint64_t collider1#

Collider 1 USD path.

uint32_t contactDataOffset#

Index into the contact data array.

uint32_t numContactData#

Number of contact points for this pair.

uint32_t frictionAnchorsDataOffset#

Index into the friction anchors array.

uint32_t numfrictionAnchorsData#

Number of friction anchors for this pair.

uint32_t protoIndex0#

Point instancer index (0xFFFFFFFF if N/A)

uint32_t protoIndex1#

Point instancer index (0xFFFFFFFF if N/A)

struct ovphysx_contact_point_t#
#include <include/ovphysx/ovphysx_types.h>

Per-contact-point data — ABI-compatible with omni::physx::ContactData.

position, normal, and impulse are float[3] in world space.

Public Members

float position[3]#

Contact position (world space)

float normal[3]#

Contact normal.

float impulse[3]#

Contact impulse (divide by dt for force)

float separation#

Contact separation distance.

uint32_t faceIndex0#

Triangle mesh face index for collider 0.

uint32_t faceIndex1#

Triangle mesh face index for collider 1.

uint64_t material0#

Material SdfPath for collider 0.

uint64_t material1#

Material SdfPath for collider 1.

struct ovphysx_friction_anchor_t#
#include <include/ovphysx/ovphysx_types.h>

Friction anchor data — ABI-compatible with omni::physx::FrictionAnchor.

Public Members

float position[3]#

Anchor position (world space)

float impulse[3]#

Friction impulse (divide by dt for force)

struct ovphysx_prim_list_t#
#include <include/ovphysx/ovphysx_types.h>

List of USD prim paths for batch operations.

Public Members

const ovphysx_string_t *prim_paths#

Array of USD prim path strings.

size_t num_paths#

Number of paths in array.

struct ovphysx_config_entry_t#
#include <include/ovphysx/ovphysx_types.h>

A typed config entry (tagged union).

key_type selects which member of key and value is valid. Use the builder functions in ovphysx_config.h for convenient construction.

Public Members

ovphysx_config_key_type_t key_type#

Discriminator.

ovphysx_config_bool_t bool_key#
ovphysx_config_int32_t int32_key#
ovphysx_config_float_t float_key#
ovphysx_config_string_t string_key#
ovphysx_string_t carbonite_key#

For KEY_TYPE_CARBONITE: arbitrary Carbonite path.

union ovphysx_config_entry_t::[anonymous] key#
bool bool_value#
int32_t int32_value#
float float_value#
ovphysx_string_t string_value#

For KEY_TYPE_STRING and KEY_TYPE_CARBONITE.

union ovphysx_config_entry_t::[anonymous] value#
struct ovphysx_config_t#
#include <include/ovphysx/ovphysx_types.h>

Config array container (convenience wrapper).

Public Members

const ovphysx_config_entry_t *entries#
uint32_t entry_count#
struct ovphysx_create_args#
#include <include/ovphysx/ovphysx_types.h>

Configuration for creating a ovphysx instance.

Initialize with OVPHYSX_CREATE_ARGS_DEFAULT macro for defaults. Keep OVPHYSX_CREATE_ARGS_DEFAULT in sync with this struct; add new fields only to the end to avoid uninitialized members when using the macro.

Example: ovphysx_create_args args = OVPHYSX_CREATE_ARGS_DEFAULT; ovphysx_create_instance(&args, &handle);

Log level is configured globally via ovphysx_set_log_level(), not per-instance.

Public Members

ovphysx_string_t bundled_deps_path#

Bundled deps path: empty=use runtime discovery (default: empty)

const ovphysx_config_entry_t *config_entries#

Array of typed config entries (replaces settings_keys/values)

uint32_t config_entry_count#

Number of config entries.

ovphysx_device_t device#

Simulation device (default: OVPHYSX_DEVICE_AUTO)

int32_t gpu_index#

CUDA device ordinal (default: 0).

Used when device selects GPU (OVPHYSX_DEVICE_GPU or OVPHYSX_DEVICE_AUTO and CUDA is available). Special values: -1 = PhysX default CUDA selection (equivalent to /physics/cudaDevice=-1)

Typed Config Entries#

Builder functions for typed config entries.

Provides static inline helpers to construct ovphysx_config_entry_t values for use with ovphysx_create_instance() and ovphysx_set_global_config().

Pattern: generic type builders + named convenience functions per enum value. Matches the ovrtx_config.h builder pattern for API consistency.

Functions

static inline ovphysx_config_entry_t ovphysx_config_entry_bool(
ovphysx_config_bool_t key,
bool value,
)#

Build a config entry for a boolean setting.

static inline ovphysx_config_entry_t ovphysx_config_entry_int32(
ovphysx_config_int32_t key,
int32_t value,
)#

Build a config entry for an int32 setting.

static inline ovphysx_config_entry_t ovphysx_config_entry_float(
ovphysx_config_float_t key,
float value,
)#

Build a config entry for a float setting.

static inline ovphysx_config_entry_t ovphysx_config_entry_string(
ovphysx_config_string_t key,
ovphysx_string_t value,
)#

Build a config entry for a string setting.

value.ptr must remain valid until the API call that consumes the config returns.

static inline ovphysx_config_entry_t ovphysx_config_entry_carbonite(
ovphysx_string_t key,
ovphysx_string_t value,
)#

Build a config entry for an arbitrary Carbonite setting (escape hatch).

The key is a Carbonite settings path (e.g., “/physics/fabricUpdateVelocities”) and the value is a string whose type is auto-detected at runtime: “true”/”false” → bool, integer string → int, float string → float, else string.

Both key.ptr and value.ptr must remain valid until the API call returns.

static inline ovphysx_config_entry_t ovphysx_config_entry_disable_contact_processing(
bool value,
)#

Enable/disable contact processing (/physics/disableContactProcessing).

static inline ovphysx_config_entry_t ovphysx_config_entry_collision_cone_custom_geometry(
bool value,
)#

Enable/disable cone custom geometry for collisions (/physics/collisionConeCustomGeometry).

static inline ovphysx_config_entry_t ovphysx_config_entry_collision_cylinder_custom_geometry(
bool value,
)#

Enable/disable cylinder custom geometry for collisions (/physics/collisionCylinderCustomGeometry).

static inline ovphysx_config_entry_t ovphysx_config_entry_num_threads(
int32_t value,
)#

Set number of worker threads (/physics/numThreads).

0 = auto.

static inline ovphysx_config_entry_t ovphysx_config_entry_scene_multi_gpu_mode(
int32_t value,
)#

Set scene multi-GPU mode (/physics/sceneMultiGPUMode).

0=disabled, 1=all GPUs, 2=skip first GPU.

C++ Wrappers (Experimental)#

C++17 RAII wrappers and helpers in the ovphysx namespace.

namespace ovphysx#
class PhysX#
#include <include/ovphysx/experimental/PhysX.hpp>

RAII wrapper for ovphysx_handle_t.

Automatically calls ovphysx_destroy_instance on destruction. Move-only (non-copyable) to ensure unique ownership.

Provides implicit conversion to ovphysx_handle_t for seamless use with C API.

Example: PhysX physx; PhysX::create(physx); physx.step(0.01f, 0.0f); physx.waitAll();

Notes:

  • Use PhysX::create to obtain a valid instance; methods log and return errors if the handle is null.

  • Use waitOp/waitAll when you need results outside stream order.

Public Types

using ContactEventHeader = ovphysx_contact_event_header_t#
using ContactPoint = ovphysx_contact_point_t#
using FrictionAnchor = ovphysx_friction_anchor_t#
using SceneQueryHit = ovphysx_scene_query_hit_t#

Public Functions

explicit PhysX(ovphysx_handle_t h)#

Construct from existing handle (takes ownership)

PhysX()#

Default constructor - creates null handle.

~PhysX()#

Destructor - destroys instance if valid.

PhysX(PhysX &&other) noexcept#

Move constructor.

PhysX &operator=(PhysX &&other) noexcept#

Move assignment.

PhysX(const PhysX&) = delete#
PhysX &operator=(const PhysX&) = delete#
inline ovphysx_handle_t handle() const#

Get raw handle.

inline operator ovphysx_handle_t() const#

Implicit conversion to handle for use with C API.

inline explicit operator bool() const#

Check if handle is valid.

ovphysx_handle_t release()#

Release ownership of handle (caller must destroy)

void reset(ovphysx_handle_t h = 0)#

Reset to new handle (destroys current if valid)

ovphysx_api_status_t addUsd(
const std::string &path,
const std::string &prefix,
ovphysx_usd_handle_t &out_handle,
)#

Add a USD file to the stage.

ovphysx_api_status_t removeUsd(ovphysx_usd_handle_t usd_handle)#

Remove a previously added USD file.

ovphysx_api_status_t reset()#

Reset the stage to empty.

ovphysx_api_status_t getStageId(int64_t &out_stage_id)#

Get the USD stage ID.

ovphysx_api_status_t clone(
const std::string &sourcePath,
const std::vector<std::string> &targetPaths,
const float *parentTransforms = nullptr,
)#

Clone a USD prim hierarchy to create multiple runtime copies (asynchronous).

Creates physics-optimized clones in the internal representation for high-performance simulation. The source prim must exist in the loaded USD stage and have physics properties. Use waitOp(op_index) or waitAll() to wait for completion before using cloned objects outside stream order.

Clones are created using an optimized internal replication system, providing optimal performance for RL training scenarios with many parallel environments.

Parameters:
  • sourcePath – USD path of the source prim hierarchy (e.g., “/World/env0”)

  • targetPaths – Vector of USD paths for cloned hierarchies (e.g., [“/World/env1”, “/World/env2”])

  • parentTransforms – World-space placement for each cloned environment’s parent Xform prim. Flat array of [targetPaths.size() * 7] floats: (px, py, pz, qx, qy, qz, qw) per target. Pass nullptr for identity.

Returns:

OVPHYSX_API_SUCCESS if cloning was queued successfully, OVPHYSX_API_ERROR on error

ovphysx_api_status_t step(float step_dt, float current_time)#

Enqueue a physics simulation step.

ovphysx_api_status_t addUserTask(
const ovphysx_user_task_desc_t &desc,
ovphysx_op_index_t &out_op_index,
)#

Add a user task to the execution queue.

physx::WaitResult waitOp(
ovphysx_op_index_t op_index,
uint64_t timeout_ns = UINT64_MAX,
)#

Wait for a specific operation to complete.

physx::WaitResult waitAll(uint64_t timeout_ns = UINT64_MAX)#

Wait for all pending operations to complete.

ovphysx_api_status_t createTensorBinding(
TensorBinding &out_binding,
const std::string &pattern,
ovphysx_tensor_type_t tensor_type,
)#

Create a tensor binding for bulk physics data access.

Creates a binding that connects USD prim paths (matched by pattern) to a tensor type, enabling efficient bulk read/write of simulation state.

Parameters:
  • out_binding – Receives the created TensorBinding on success

  • pattern – USD prim path pattern (e.g., “/World/robot*”)

  • tensor_type – The type of tensor data to bind

Returns:

OVPHYSX_API_SUCCESS on success

template<typename T>
inline ovphysx_api_status_t getPhysXPtr(
const std::string &primPath,
T *&out,
) const#

Type-safe accessor: deduces the enum from the PhysX pointer type.

Example: physx::PxScene* s; physx.getPhysXPtr("/World/scene", s); Compile error if T has no PhysXTypeFor<T> specialization.

inline ovphysx_api_status_t getPhysXPtr(
const std::string &primPath,
ovphysx_physx_type_t type,
void *&out,
) const#

Explicit-enum accessor for advanced use or unsupported types.

Prefer the two-argument overload above when T is a known PhysX type.

inline ovphysx_api_status_t getContactReport(
const ContactEventHeader *&headers,
uint32_t &numHeaders,
const ContactPoint *&points,
uint32_t &numPoints,
const FrictionAnchor **anchors = nullptr,
uint32_t *numAnchors = nullptr,
) const#

Get contact report data for the current simulation step.

Returns typed pointers to the internal contact buffers. Data is valid until the next simulation step.

Parameters:
  • headers[out] Pointer to contact event header array.

  • numHeaders[out] Number of headers.

  • points[out] Pointer to contact point data array.

  • numPoints[out] Number of contact point entries.

  • anchors[out] Optional. Pointer to friction anchor array (pass nullptr to skip).

  • numAnchors[out] Optional. Friction anchor count (pass nullptr to skip).

inline ovphysx_api_status_t raycast(
const float origin[3],
const float direction[3],
float distance,
bool both_sides,
ovphysx_scene_query_mode_t mode,
const SceneQueryHit *&hits,
uint32_t &count,
) const#

Cast a ray into the scene.

Parameters:
  • origin – Ray origin (world space).

  • direction – Normalized ray direction.

  • distance – Maximum ray length.

  • both_sides – Test both sides of mesh triangles.

  • mode – CLOSEST, ANY, or ALL.

  • hits[out] Pointer to internal hit array (valid until next scene query call).

  • count[out] Number of hits.

inline ovphysx_api_status_t sweep(
const ovphysx_scene_query_geometry_desc_t &geometry,
const float direction[3],
float distance,
bool both_sides,
ovphysx_scene_query_mode_t mode,
const SceneQueryHit *&hits,
uint32_t &count,
) const#

Sweep a geometry shape through the scene.

Parameters:
  • geometry – Geometry descriptor.

  • direction – Normalized sweep direction.

  • distance – Maximum sweep length.

  • both_sides – Test both sides of mesh triangles.

  • mode – CLOSEST, ANY, or ALL.

  • hits[out] Pointer to internal hit array (valid until next scene query call).

  • count[out] Number of hits.

inline ovphysx_api_status_t overlap(
const ovphysx_scene_query_geometry_desc_t &geometry,
ovphysx_scene_query_mode_t mode,
const SceneQueryHit *&hits,
uint32_t &count,
) const#

Test geometry overlap against objects in the scene.

Parameters:
  • geometry – Geometry descriptor.

  • mode – ANY or ALL. CLOSEST falls back to ALL because overlap tests have no distance ordering.

  • hits[out] Pointer to internal hit array (valid until next scene query call).

  • count[out] Number of overlapping objects.

Public Static Functions

static ovphysx_api_status_t configureS3(
const std::string &host,
const std::string &bucket,
const std::string &region,
const std::string &access_key_id,
const std::string &secret_access_key,
const std::string &session_token = "",
)#

Configure S3 credentials for remote USD loading via HTTPS S3 URLs.

Process-global — affects all instances. Call before addUsd() with an S3 HTTPS URL. An ovphysx instance must exist so the runtime is loaded.

Parameters:
  • host – S3 endpoint (e.g., “my-bucket.s3.us-east-1.amazonaws.com”)

  • bucket – Bucket name

  • region – AWS region (e.g., “us-east-1”)

  • access_key_id – AWS access key ID

  • secret_access_key – AWS secret access key

  • session_token – STS session token (empty string if unused)

Returns:

OVPHYSX_API_SUCCESS on success

static ovphysx_api_status_t configureAzureSas(
const std::string &host,
const std::string &container,
const std::string &sas_token,
)#

Configure an Azure SAS token for remote USD loading via Azure Blob Storage.

Process-global — affects all instances. Call before addUsd() with an Azure Blob URL. An ovphysx instance must exist so the runtime is loaded.

Parameters:
  • host – Azure Blob host (e.g., “myaccount.blob.core.windows.net”)

  • container – Container name

  • sas_token – SAS token string (without leading ‘?’)

Returns:

OVPHYSX_API_SUCCESS on success

static ovphysx_api_status_t create(
PhysX &out_instance,
const ovphysx_config_entry_t *config_entries = nullptr,
uint32_t config_entry_count = 0,
)#

Factory method to create a PhysX instance with typed config entries.

Example:

#include "ovphysx/ovphysx_config.h"

ovphysx_config_entry_t entries[] = {
    ovphysx_config_entry_disable_contact_processing(true),
    ovphysx_config_entry_num_threads(4),
};
PhysX physx;
auto status = PhysX::create(physx, entries, 2);
if (status != OVPHYSX_API_SUCCESS) { ... handle error ... }

Rationale: ovphysx_create_instance can fail; the factory returns status without constructing an invalid object or relying on exceptions. If you prefer a different pattern, wrap this in your own expected/optional logic.

template<typename T>
struct PhysXTypeFor#

Traits mapping a PhysX SDK type to its ovphysx_physx_type_t enum value. Enables type-safe getPhysXPtr() overloads that auto-deduce the enum.

template<>
struct PhysXTypeFor<::physx::PxArticulationJointReducedCoordinate>#
#include <include/ovphysx/experimental/PhysX.hpp>

Public Static Attributes

static constexpr ovphysx_physx_type_t value = OVPHYSX_PHYSX_TYPE_LINK_JOINT#
template<>
struct PhysXTypeFor<::physx::PxArticulationLink>#
#include <include/ovphysx/experimental/PhysX.hpp>

Public Static Attributes

static constexpr ovphysx_physx_type_t value = OVPHYSX_PHYSX_TYPE_LINK#
template<>
struct PhysXTypeFor<::physx::PxArticulationReducedCoordinate>#
#include <include/ovphysx/experimental/PhysX.hpp>

Public Static Attributes

static constexpr ovphysx_physx_type_t value = OVPHYSX_PHYSX_TYPE_ARTICULATION#
template<>
struct PhysXTypeFor<::physx::PxJoint>#
#include <include/ovphysx/experimental/PhysX.hpp>

Public Static Attributes

static constexpr ovphysx_physx_type_t value = OVPHYSX_PHYSX_TYPE_JOINT#
template<>
struct PhysXTypeFor<::physx::PxMaterial>#
#include <include/ovphysx/experimental/PhysX.hpp>

Public Static Attributes

static constexpr ovphysx_physx_type_t value = OVPHYSX_PHYSX_TYPE_MATERIAL#
template<>
struct PhysXTypeFor<::physx::PxRigidActor>#
#include <include/ovphysx/experimental/PhysX.hpp>

Public Static Attributes

static constexpr ovphysx_physx_type_t value = OVPHYSX_PHYSX_TYPE_ACTOR#
template<>
struct PhysXTypeFor<::physx::PxScene>#
#include <include/ovphysx/experimental/PhysX.hpp>

Public Static Attributes

static constexpr ovphysx_physx_type_t value = OVPHYSX_PHYSX_TYPE_SCENE#
template<>
struct PhysXTypeFor<::physx::PxShape>#
#include <include/ovphysx/experimental/PhysX.hpp>

Public Static Attributes

static constexpr ovphysx_physx_type_t value = OVPHYSX_PHYSX_TYPE_SHAPE#
class TensorBinding#
#include <include/ovphysx/experimental/TensorBinding.hpp>

RAII wrapper for ovphysx_tensor_binding_handle_t.

Automatically calls ovphysx_destroy_tensor_binding on destruction. Move-only (non-copyable) to ensure unique ownership.

Created via PhysX::createTensorBinding(). Do not construct directly.

Example: TensorBinding binding; physx.createTensorBinding(binding, “/World/robot”, OVPHYSX_TENSOR_ARTICULATION_DOF_POSITION_F32); binding.read(myTensor);

Public Functions

TensorBinding()#
~TensorBinding()#
TensorBinding(TensorBinding &&other) noexcept#
TensorBinding &operator=(TensorBinding &&other) noexcept#
TensorBinding(const TensorBinding&) = delete#
TensorBinding &operator=(const TensorBinding&) = delete#
inline ovphysx_tensor_binding_handle_t handle() const#

Get the raw binding handle (for use with C API)

inline explicit operator bool() const#

Check if this binding is valid.

ovphysx_api_status_t spec(ovphysx_tensor_spec_t &out_spec) const#

Query the tensor spec (dtype, ndim, shape)

ovphysx_api_status_t metadata(
ovphysx_articulation_metadata_t &out_metadata,
) const#

Query articulation topology metadata (dof_count, body_count, joint_count, fixed_tendon_count, spatial_tendon_count, is_fixed_base). Only valid for articulation bindings; returns OVPHYSX_API_ERROR otherwise.

ovphysx_api_status_t read(DLTensor &dst) const#

Read simulation data into a DLTensor.

ovphysx_api_status_t write(
const DLTensor &src,
const DLTensor *indices = nullptr,
) const#

Write data from a DLTensor, optionally with an index tensor for sparse updates.

ovphysx_api_status_t writeMasked(
const DLTensor &src,
const DLTensor &mask,
) const#

Write data from a DLTensor using a boolean mask for selective updates.

void destroy()#

Explicitly destroy the binding (called automatically by destructor)

namespace physx#
class WaitResult#
#include <include/ovphysx/experimental/Helpers.hpp>

RAII wrapper for ovphysx_op_wait_result_t.

Automatically calls ovphysx_destroy_wait_result when destroyed. Use get() to pass to ovphysx_wait_op.

Example: WaitResult wait; ovphysx_result_t r = ovphysx_wait_op(handle, op_index, timeout, wait.get());

if (wait.hasErrors()) { for (size_t i = 0; i < wait.errorCount(); ++i) { ovphysx_string_t err = ovphysx_get_last_op_error(wait.errorOpIndexAt(i)); std::cerr << “Op “ << wait.errorOpIndexAt(i) << “ failed: “ << std::string(err.ptr, err.length) << std::endl; } } // wait result freed automatically when wait goes out of scope

Public Functions

inline WaitResult()#
inline ~WaitResult()#
inline WaitResult(WaitResult &&other) noexcept#
inline WaitResult &operator=(WaitResult &&other) noexcept#
WaitResult(const WaitResult&) = delete#
WaitResult &operator=(const WaitResult&) = delete#
inline ovphysx_op_wait_result_t *get()#

Get pointer to underlying result (pass to ovphysx_wait_op)

inline const ovphysx_op_wait_result_t *get() const#
inline bool hasErrors() const#

Check if there were any errors.

inline size_t errorCount() const#

Number of errors.

inline ovphysx_op_index_t lowestPendingOpIndex() const#

Get lowest pending operation index (0 if all complete)

inline ovphysx_op_index_t errorOpIndexAt(size_t i) const#

Get the failed operation index at position i.