C API Reference#

This page renders the full public API from include/ovphysx/ovphysx.h.

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 requested 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. Subsequent calls with a different device value 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.

ovphysx_destroy_instance(handle);
Side Effects

Releases internal resources, plugins, and cached data for this instance.

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.

ovphysx_result_t ovphysx_set_global_setting(
ovphysx_string_t key,
ovphysx_string_t value,
)#

Set a global configuration setting at runtime.

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

The value type is auto-detected from the string:

  • ”true”/”false” -> bool

  • Integer string (e.g., “42”) -> int

  • Float string (e.g., “0.5”) -> float

  • Other strings -> string

Common settings: “/physics/cudaDevice” = “0” - CUDA device ordinal

See docs/developer_guide.md for integration guidance and common settings usage.

ovphysx_set_global_setting(OVPHYSX_LITERAL("/physics/cudaDevice"), OVPHYSX_LITERAL("0"));
Side Effects

May affect behavior of all existing and future instances.

Threading

Safe to call from any thread; ensure consistent configuration before creating instances.

Ownership

key/value strings are read during the call; caller retains ownership.

Errors

  • OVPHYSX_API_INVALID_ARGUMENT for invalid key/value

  • OVPHYSX_API_ERROR for internal failures

Parameters:
  • key – Setting path (e.g., “/physics/cudaDevice”)

  • value – Setting value as string

Returns:

ovphysx_result_t with status and error info

Pre:

key.ptr != NULL, value.ptr != NULL.

Post:

The process-global setting is updated for all instances.

ovphysx_result_t ovphysx_get_global_setting(
ovphysx_string_t key,
ovphysx_string_t *value_out,
size_t *out_required_size,
)#

Get a global setting value into a user-provided buffer.

Retrieves the current value of a process-global setting as a string. The user must pre-allocate value_out->ptr with sufficient space and set value_out->length to the buffer capacity on input. On success, value_out->length is updated with the actual string length (excluding null terminator).

Example: char buffer[256]; ovphysx_string_t value = {buffer, 256}; size_t required; auto result = ovphysx_get_global_setting(key, &value, &required); if (result.status == OVPHYSX_API_SUCCESS) { // value.ptr contains the string, value.length is actual length }

char buffer[256];
ovphysx_string_t out = {buffer, sizeof(buffer)};
size_t required = 0;
ovphysx_get_global_setting(OVPHYSX_LITERAL("/physics/cudaDevice"), &out, &required);
Side Effects

None.

Ownership

Caller owns the output buffer.

Errors

  • OVPHYSX_API_INVALID_ARGUMENT for invalid inputs

  • OVPHYSX_API_ERROR for internal failures

Parameters:
  • key – Setting path (e.g., “/physics/cudaDevice”)

  • value_out – [in/out] String with pre-allocated buffer

  • out_required_size – [out] If buffer too small, contains required buffer capacity

Returns:

ovphysx_result_t with status and error info

Pre:

value_out != NULL, out_required_size != NULL.

Pre:

value_out->ptr points to valid writable memory with capacity in value_out->length.

Post:

On success, value_out contains the setting value and value_out->length is updated.

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,
)#

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);
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

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.

Post:

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

ovphysx_enqueue_result_t ovphysx_step(
ovphysx_handle_t handle,
float elapsed_time,
float current_time,
)#
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 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,
)#

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 is performed to initialize PhysX DirectGPU buffers.

IMPORTANT: The warmup step is a real physics step that advances simulation state by a minimal timestep (~1ns). While the effect is negligible, it means:

  • Simulation time advances slightly

  • Physics state may change infinitesimally

  • If you need exact initial state, call ovphysx_warmup_gpu() before reading initial positions, or call ovphysx_step() explicitly with your desired dt

For explicit control over warmup timing (recommended for deterministic behavior):

  1. Load USD, wait for completion

  2. Call ovphysx_warmup_gpu() to perform warmup at a controlled time

  3. Now tensor reads will return valid data without triggering auto-warmup

Note: The DirectGPU warmup requirement means you cannot observe a true “pre-warmup” GPU tensor state. Warmup is a real simulation step; calling it explicitly simply makes the timing of that step predictable.

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).

All tensor types are writable. Force/wrench types (OVPHYSX_TENSOR_*_FORCE_F32, OVPHYSX_TENSOR_*_WRENCH_F32) are WRITE-ONLY control inputs applied each step. See ovphysx_tensor_type_t documentation for shapes and layouts.

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.

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.

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_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,
)#
void ovphysx_destroy_error(ovphysx_string_t error)#
void ovphysx_destroy_errors(
const ovphysx_op_error_t *errors,
size_t num_errors,
)#
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_NONE and OVPHYSX_LOG_VERBOSE 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 — 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.

ovphysx_result_t ovphysx_set_setting(
ovphysx_handle_t handle,
ovphysx_string_t key,
ovphysx_string_t value,
)#

Deprecated:

Use ovphysx_set_global_setting() instead. Settings are now process-global; handle parameter is ignored.

Parameters:
  • handle – Ignored.

  • key – Setting path.

  • value – Setting value.

Returns:

ovphysx_result_t with status and error info.

Pre:

key.ptr != NULL, value.ptr != NULL.

Post:

Global setting updated on success.

ovphysx_result_t ovphysx_get_setting(
ovphysx_handle_t handle,
ovphysx_string_t key,
ovphysx_string_t *value_out,
size_t *out_required_size,
)#

Deprecated:

Use ovphysx_get_global_setting() instead. Settings are now process-global; handle parameter is ignored.

Parameters:
  • handle – Ignored.

  • key – Setting path.

  • value_out – Output string buffer.

  • out_required_size – Required buffer size if too small.

Returns:

ovphysx_result_t with status and error info.

Pre:

value_out and out_required_size must be valid.

Post:

value_out contains setting value on success.

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=GPU, 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 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_NONE#

No logging.

enumerator OVPHYSX_LOG_ERROR#

Error messages only.

enumerator OVPHYSX_LOG_WARNING#

Warnings and errors (default)

enumerator OVPHYSX_LOG_INFO#

Info, warnings, and errors.

enumerator OVPHYSX_LOG_VERBOSE#

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

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_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.

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_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

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_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

enum ovphysx_device_t#

Simulation device/backend selection.

Controls whether physics simulation runs on CPU or GPU.

GPU mode (default):

  • 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:

  • 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_GPU#

GPU simulation with DirectGPU API (default)

enumerator OVPHYSX_DEVICE_CPU#

CPU-only simulation.

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_result_t#
#include <include/ovphysx/ovphysx_types.h>

Result returned by synchronous API functions.

Public Members

ovphysx_api_status_t status#

Operation status code.

ovphysx_string_t error#

Error message (empty if success, destroy with ovphysx_destroy_error)

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

Result returned by asynchronous API functions.

Public Members

ovphysx_api_status_t status#

Operation status code.

ovphysx_string_t error#

Error message (empty if success, destroy with ovphysx_destroy_error)

ovphysx_op_index_t op_index#

Operation index for async tracking.

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

Error associated with a specific operation.

Public Members

ovphysx_op_index_t op_index#

Operation that failed.

ovphysx_string_t error#

Error message (destroy via ovphysx_destroy_errors)

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

Result from ovphysx_wait_op() containing errors and pending operation status.

Public Members

ovphysx_op_error_t *errors#

Array of errors (destroy via ovphysx_destroy_errors)

size_t num_errors#

Number of errors in array.

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_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_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_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_string_t *settings_keys#

Array of setting key strings.

const ovphysx_string_t *settings_values#

Array of setting value strings.

uint32_t settings_count#

Number of settings.

ovphysx_device_t device#

Simulation device (default: OVPHYSX_DEVICE_GPU)

int32_t gpu_index#

GPU device index for CUDA, sets /physics/cudaDevice (default: 0).

Only used when device=OVPHYSX_DEVICE_GPU. User settings (settings_keys/values) can override this if needed.