Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion .airstack/modules/config.sh
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,9 @@ function cmd_config_nucleus {
local escaped_api_token="${API_TOKEN//\\/\\\\}"
escaped_api_token="${escaped_api_token//&/\\&}"
escaped_api_token="${escaped_api_token//\//\\/}"
sed "s/PASTE-YOUR-API-TOKEN/$escaped_api_token/g" "$OMNI_PASS_SOURCE" > "$OMNI_PASS_DESTINATION"
sed -e "s/^OMNI_USER=.*$/OMNI_USER='\$omni-api-token'/" \
-e "s/^OMNI_PASS=.*$/OMNI_PASS=$escaped_api_token/" \
"$OMNI_PASS_SOURCE" > "$OMNI_PASS_DESTINATION"
log_info "Nucleus login configuration complete"
else
cp "$OMNI_PASS_SOURCE" "$OMNI_PASS_DESTINATION"
Expand Down
2 changes: 1 addition & 1 deletion .env
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ PROJECT_NAME="airstack"
# If you've run ./airstack.sh setup, then this will auto-generate from the git commit hash every time a change is made
# to a Dockerfile or docker-compose.yaml file. Otherwise this can also be set explicitly to make a release version.
# auto-generated from git commit hash
VERSION="0.18.0-alpha.10"
VERSION="0.18.0-alpha.11"
# Choose "dev" or "prebuilt". "dev" is for mounted code that must be built live. "prebuilt" is for built ros_ws baked into the image
DOCKER_IMAGE_BUILD_MODE="dev"
# Where to push and pull images from. Can replace with your docker hub username if using docker hub.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ def __init__(self):

self._navsat_sub = self.create_subscription(
NavSatFix,
f"/{self._robot_name}/interface/mavros/global_position/global",
f"/{self._robot_name}/interface/mavros/global_position/raw/fix",
self._on_navsat,
SENSOR_QOS,
)
Expand Down Expand Up @@ -148,7 +148,7 @@ def _setup_payload_subscriptions(self, config_path: str) -> None:
self.get_logger().warn(f"Could not load payload config '{config_path}': {e}")
return

for entry in cfg.get("payload_topics", []):
for entry in cfg.get("payload_topics") or []:
topic_template = entry.get("topic", "")
type_str = entry.get("type", "")
if not topic_template or not type_str:
Expand Down
41 changes: 26 additions & 15 deletions docs/simulation/isaac_sim/overhead_camera.md
Original file line number Diff line number Diff line change
Expand Up @@ -70,25 +70,38 @@ The three constants (`OVERHEAD_ALTITUDE_M`, `OVERHEAD_COVERAGE_M`, `OVERHEAD_PX_
| `OVERHEAD_COVERAGE_M` | `200.0` | Side length of the captured square (m). |
| `OVERHEAD_PX_PER_METER` | `4.0` | Texture density. Increase for sharper text/markings; capped at `max_resolution=2048`. |

The camera is positioned at world origin `(0, 0)`. If your scene's points of interest are off-origin, shift the camera's `prim_path` xform after `add_orthographic_camera` returns:
### Re-centering or transforming the camera

By default the camera sits over world origin `(0, 0)`. For an off-origin area of interest, pass `center_x_m` / `center_y_m` to both helpers — they take care of the camera xform and the spec topics the GCS reads:

```python
from pxr import Gf, UsdGeom
CENTER_X_M, CENTER_Y_M = 50.0, -25.0

cam_path = add_orthographic_camera(stage, prim_path="/World/MapCamera", ...)
cam_path = add_orthographic_camera(
stage, prim_path="/World/MapCamera",
altitude_m=OVERHEAD_ALTITUDE_M,
coverage_m=OVERHEAD_COVERAGE_M,
scene_scale_factor=scene_scale_factor,
center_x_m=CENTER_X_M,
center_y_m=CENTER_Y_M,
)

# Re-center the camera over (CENTER_X_M, CENTER_Y_M) instead of world origin.
CENTER_X_M, CENTER_Y_M = 50.0, -25.0
xform = UsdGeom.Xformable(stage.GetPrimAtPath(cam_path))
xform.ClearXformOpOrder()
xform.AddTranslateOp().Set(Gf.Vec3d(
CENTER_X_M * scene_scale_factor,
CENTER_Y_M * scene_scale_factor,
OVERHEAD_ALTITUDE_M * scene_scale_factor,
))
add_overhead_camera_publisher(
parent_graph_path="/World/MapCameraGraph",
camera_prim_path=cam_path,
topic="/sim/overhead/image",
spec_topic="/sim/overhead/spec",
center_x_topic="/sim/overhead/center_x",
center_y_topic="/sim/overhead/center_y",
frame_id="map",
coverage_m=OVERHEAD_COVERAGE_M,
center_x_m=CENTER_X_M,
center_y_m=CENTER_Y_M,
pixels_per_meter=OVERHEAD_PX_PER_METER,
domain_id=0,
)
```


## GCS side

The GCS rendering is handled by `_build_sim_ground_marker` in `gcs/ros_ws/src/gcs_visualizer/gcs_visualizer/foxglove_visualizer_node.py`. It:
Expand All @@ -113,8 +126,6 @@ The default downsample (0.8 cells/m, cap 384) is conservative. To raise the rend
<param name="overhead_max_grid_resolution" value="1024" />
```

`1024` over a 200 m scene gives ~5 cells/m. If the 3D panel slows down, drop back toward `768`. Any change here also requires bumping `OVERHEAD_PX_PER_METER` on the sim side (otherwise you're sampling a low-resolution source more densely).

To change other rendering behavior (alpha, lighting), edit `_build_sim_ground_marker` directly. To force a re-render, restart the GCS visualizer.

## See also
Expand Down
92 changes: 92 additions & 0 deletions docs/simulation/isaac_sim/spawning_drones.md
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,98 @@ set_gps_origins(DRONE_CONFIGS, world_origin=(40.4433, -79.9436, 280.0)) # Pitts

The anchor only affects the geographic location reported via GPS; nothing in the scene moves. Pick something close to where you want the drones to "be" — Foxglove's Map panel will center on it, and any GPS-referenced inputs to your stack will be relative to it.

## Scene prep helpers — `scene_prep.py`

`simulation/isaac-sim/utils/scene_prep.py` is the small toolbox of stage preparation helpers `example_multi_drone_scene_import.py` uses inside its post-load callback (after the stage is loaded, before drones spawn). The full file has more — what's documented here is what you'll reach for in 95% of scenes.

```python
from utils.scene_prep import (
get_stage_meters_per_unit, scale_stage_prim, add_colliders,
add_dome_light, save_scene_as_contained_usd,
add_orthographic_camera, add_overhead_camera_publisher,
)
Comment on lines +63 to +67

mpu, scene_scale_factor = get_stage_meters_per_unit(stage)
```

### Scaling — `scale_stage_prim`

USD scenes are authored at all sorts of stage units. To apply a uniform scale to the imported stage root once, before drones spawn:

```python
STAGE_SCALE = 0.01 # cm → m
scale_stage_prim(stage, "/World/stage", STAGE_SCALE)
```

### Colliders — `add_colliders`

Recursively applies `UsdPhysics.CollisionAPI` to every `UsdGeom.Mesh` under the given prim. Imported environment USDs are usually visual-only; without this, drones fall through buildings.

```python
stage_prim = stage.GetPrimAtPath("/World/stage")
add_colliders(stage_prim)
```

Skips prims that already have the API applied. Run it on the stage root after `scale_stage_prim` returns.

### Lighting — `add_dome_light`

In case the scene is missing any lights, this adds a dome light that can act like an overhead 'sun'.

```python
add_dome_light(
stage,
prim_path="/World/DomeLight",
intensity=3500.0,
exposure=-5.0, # negative = darker; tune per scene
)
```

### Overhead camera — `add_orthographic_camera` + `add_overhead_camera_publisher`

Used as a pair: one drops an orthographic camera over the scene, the other wires an OmniGraph to publish its frame plus three Float32 spec topics (`coverage_m`, `center_x_m`, `center_y_m`) the GCS uses to texture a ground plane in Foxglove's 3D panel.

```python
cam_path = add_orthographic_camera(
stage,
prim_path="/World/MapCamera",
altitude_m=165.0,
coverage_m=225.0,
scene_scale_factor=scene_scale_factor,
center_x_m=0.0, # set if your area of interest isn't at world origin
center_y_m=0.0,
)
add_overhead_camera_publisher(
parent_graph_path="/World/MapCameraGraph",
camera_prim_path=cam_path,
topic="/sim/overhead/image",
spec_topic="/sim/overhead/spec",
center_x_topic="/sim/overhead/center_x",
center_y_topic="/sim/overhead/center_y",
frame_id="map",
coverage_m=225.0,
center_x_m=0.0,
center_y_m=0.0,
pixels_per_meter=10.0,
domain_id=0,
)
```

Full setup, GCS-side rendering, and tuning knobs are on the **[Overhead Camera](overhead_camera.md)** page.

### Saving a self-contained copy — `save_scene_as_contained_usd`

For scenes you'd like to keep working with offline (no Nucleus connection), or for sharing a scene with collaborators, collect the root USD plus every referenced asset (textures, MDLs, sublayers) into a local directory:

```python
save_scene_as_contained_usd(
source_usd_url=ENV_URL,
output_dir="/tmp/collected_scene",
)
```

The collected folder contains a standalone root USD with relative references — load it directly via `omniverse://localhost/...` or a local file path. Note that this collects the **source USD as-is**: scale, colliders, dome light, and any other stage edits applied in this post-load callback are *not* baked into the saved copy. To capture the live stage with your modifications, first export the in-memory stage to a USD on disk (e.g. via `stage.GetRootLayer().Export(...)`) and pass that exported path as `source_usd_url`.

## Common issues

| Symptom | Likely cause | Fix |
Expand Down
2 changes: 1 addition & 1 deletion gcs/foxglove_extensions/airstack_default.json
Original file line number Diff line number Diff line change
Expand Up @@ -539,7 +539,7 @@
},
"synchronize": false,
"imageMode": {
"imageTopic": "/robot_1/sensors/front_stereo/right/depth_ground_",
"imageTopic": "/robot_1/sensors/front_stereo/right/depth_ground_truth",
"calibrationTopic": "/robot_1/sensors/front_stereo/right/camera_info",
"colorMode": "gradient",
"minValue": 0,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
ext_manager = omni.kit.app.get_app().get_extension_manager()
for ext in [
# "airlab.airstack",
"omni.physx.forcefields",
"omni.graph.core", # Core runtime for OmniGraph engine
"omni.graph.action", # Action Graph framework
"omni.graph.action_nodes", # Built-in Action Graph node library
Expand All @@ -38,7 +37,6 @@
"omni.graph.window.action", # Action Graph editor window
"omni.graph.window.generic", # Generic graph UI tools
"omni.graph.ui_nodes", # UI node building helpers
"airlab.pegasus", # Airlab extension Pegasus core extension
"pegasus.simulator",
]:
if not ext_manager.is_extension_enabled(ext):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
from pegasus.simulator.logic.interface.pegasus_interface import PegasusInterface
from pegasus.simulator.ogn.api.spawn_multirotor import spawn_px4_multirotor_node
from pegasus.simulator.ogn.api.spawn_zed_camera import add_zed_stereo_camera_subgraph
from pegasus.simulator.ogn.api.spawn_ouster_lidar import add_ouster_lidar_subgraph
from pegasus.simulator.ogn.api.spawn_rtx_lidar import add_rtx_lidar_subgraph

# gps_utils lives in the same directory as this script
_LAUNCH_SCRIPTS_DIR = os.path.dirname(os.path.abspath(__file__))
Expand All @@ -39,7 +39,7 @@
import scene_prep
from scene_prep import (
scale_stage_prim, add_colliders, add_dome_light, get_stage_meters_per_unit,
reference_root_prims_under_world,
reference_root_prims_under_world, dedupe_physics_scenes,
add_orthographic_camera, add_overhead_camera_publisher,
)

Expand All @@ -49,9 +49,7 @@

#env/stage path and scale
ENV_URL = f"omniverse://{NUCLEUS_SERVER}/Projects/AirStack/scenes/urban/allegheny_county_fire_academy/fire_academy.scene.usd"
#f"omniverse://{NUCLEUS_SERVER}/Library/Assets/FireAcademyFaro/fire_academy_faro.usd"
#f"omniverse://{NUCLEUS_SERVER}/Projects/AirStack/RayFronts-Planner/FireAcademy.scene.usd"
#f"omniverse://{NUCLEUS_SERVER}/Library/Assets/Fire_Academy_Digital_Twin/fire_academy.usd"
Comment thread
JohnYanxinLiu marked this conversation as resolved.

STAGE_SCALE = 0.01

DRONE_USD = "~/.local/share/ov/data/documents/Kit/shared/exts/pegasus.simulator/pegasus/simulator/assets/Robots/Iris/iris.usd"
Expand All @@ -74,29 +72,34 @@
# spawn location for /Assets/Fire_Academy_Digital_Twin/fire_academy.usd:
# {"domain_id": 1, "x_m": 20.0, "y_m": -7.0, ...}
# {"domain_id": 2, "x_m": 17.0, "y_m": 1.5, ...}

SPAWN_HEIGHT_ABOVE_FLOOR_M = 0.03
DRONE_CONFIGS = [
{"domain_id": 1, "x_m": 27.0, "y_m": 7.6, "z_m": SPAWN_HEIGHT_ABOVE_FLOOR_M, "orient": [0.0, 0.0, -0.937, 0.35], "lidar_min_range": 4.0},
{"domain_id": 2, "x_m": 23.0, "y_m": 9.8, "z_m": SPAWN_HEIGHT_ABOVE_FLOOR_M, "orient": [0.0, 0.0, -0.937, 0.35], "lidar_min_range": 4.0},
{"domain_id": 3, "x_m": 27.0, "y_m": 12.0, "z_m": SPAWN_HEIGHT_ABOVE_FLOOR_M, "orient": [0.0, 0.0, -0.937, 0.35], "lidar_min_range": 4.0},
{"domain_id": 4, "x_m": 23.0, "y_m": 14.0, "z_m": SPAWN_HEIGHT_ABOVE_FLOOR_M, "orient": [0.0, 0.0, -0.937, 0.35], "lidar_min_range": 4.0}
{"domain_id": 1, "x_m": 32.0, "y_m": 12.6, "z_m": SPAWN_HEIGHT_ABOVE_FLOOR_M, "orient": [0.0, 0.0, -0.937, 0.35], "lidar_min_range": 0.75},
{"domain_id": 2, "x_m": 28.0, "y_m": 14.8, "z_m": SPAWN_HEIGHT_ABOVE_FLOOR_M, "orient": [0.0, 0.0, -0.937, 0.35], "lidar_min_range": 0.75},
{"domain_id": 3, "x_m": 32.0, "y_m": 19.8, "z_m": SPAWN_HEIGHT_ABOVE_FLOOR_M, "orient": [0.0, 0.0, -0.937, 0.35], "lidar_min_range": 0.75}
]

# Top-down "map" camera over (0, 0). Captures one aerial of the static scene
# that the GCS visualizer turns into a textured ground in Foxglove's 3D panel.
OVERHEAD_ALTITUDE_M = 150.0
OVERHEAD_COVERAGE_M = 200.0 # per-map knob: world meters per side.
OVERHEAD_PX_PER_METER = 12.0 # Source-image density. Bump for sharper texture.
# Top-down "map" camera. Captures one aerial of the static scene that the
# GCS visualizer turns into a textured ground in Foxglove's 3D panel. The
# camera centers on (OVERHEAD_CENTER_X_M, OVERHEAD_CENTER_Y_M) in world
# meters — leave both 0.0 for the legacy origin-centered behavior.
OVERHEAD_ALTITUDE_M = 165.0
OVERHEAD_COVERAGE_M = 225 # per-map knob: world meters per side.
OVERHEAD_CENTER_X_M = 0.0 #-152 # world-X of camera center / texture center.
OVERHEAD_CENTER_Y_M = 0.0 #-80 # world-Y of camera center / texture center.
OVERHEAD_PX_PER_METER = 10.0 # Source-image density. Bump for sharper texture.
OVERHEAD_TOPIC = "/sim/overhead/image"
OVERHEAD_SPEC_TOPIC = "/sim/overhead/spec"
OVERHEAD_CENTER_X_TOPIC = "/sim/overhead/center_x"
OVERHEAD_CENTER_Y_TOPIC = "/sim/overhead/center_y"
OVERHEAD_FRAME_ID = "map"
OVERHEAD_DOMAIN_ID = 0
# ---------------------------------------------------------


ext_manager = omni.kit.app.get_app().get_extension_manager()
for ext in [
"omni.physx.forcefields",
"omni.graph.core", # Core runtime for OmniGraph engine
"omni.graph.action", # Action Graph framework
"omni.graph.action_nodes", # Built-in Action Graph node library
Expand All @@ -106,7 +109,6 @@
"omni.graph.window.action", # Action Graph editor window
"omni.graph.window.generic", # Generic graph UI tools
"omni.graph.ui_nodes", # UI node building helpers
"airlab.pegasus", # Airlab extension Pegasus core extension
"pegasus.simulator",
]:
if not ext_manager.is_extension_enabled(ext):
Expand Down Expand Up @@ -165,8 +167,13 @@ def __init__(self):
if not wait_for_stage(stage):
carb.log_warn("Stage load timed out — continuing anyway.")

dedupe_physics_scenes(stage)

# ----- Scene preparation -----
# Bring in sky/sun/environment prims that sit outside /World in the source USD
# Bring in sky/sun/environment prims that sit at root level in the
# source USD next to the defaultPrim that pg.load_environment already
# loaded into /World/stage. reference_root_prims_under_world skips
# the defaultPrim, so this can't duplicate geometry.
reference_root_prims_under_world(stage, ENV_URL)

stage_prim = stage.GetPrimAtPath("/World/stage")
Expand All @@ -193,14 +200,20 @@ def __init__(self):
altitude_m=OVERHEAD_ALTITUDE_M,
coverage_m=OVERHEAD_COVERAGE_M,
scene_scale_factor=s,
center_x_m=OVERHEAD_CENTER_X_M,
center_y_m=OVERHEAD_CENTER_Y_M,
)
add_overhead_camera_publisher(
parent_graph_path="/World/MapCameraGraph",
camera_prim_path=cam_path,
topic=OVERHEAD_TOPIC,
spec_topic=OVERHEAD_SPEC_TOPIC,
center_x_topic=OVERHEAD_CENTER_X_TOPIC,
center_y_topic=OVERHEAD_CENTER_Y_TOPIC,
frame_id=OVERHEAD_FRAME_ID,
coverage_m=OVERHEAD_COVERAGE_M,
center_x_m=OVERHEAD_CENTER_X_M,
center_y_m=OVERHEAD_CENTER_Y_M,
pixels_per_meter=OVERHEAD_PX_PER_METER,
domain_id=OVERHEAD_DOMAIN_ID,
)
Expand Down Expand Up @@ -230,14 +243,15 @@ def __init__(self):
camera_rotation_offset=[0.0, 0.0, 0.0],
)

add_ouster_lidar_subgraph(
add_rtx_lidar_subgraph(
parent_graph_handle=graph_handle,
drone_prim=f"/World/drone{i}/base_link",
robot_name=f"robot_{i}",
lidar_name="OS1_REV6_128_10hz___512_resolution",
lidar_config="ouster_os1",
lidar_topic_name="point_cloud_raw",
lidar_offset=[0.0, 0.0, 0.025],
lidar_rotation_offset=[0.0, 0.0, 0.0],
lidar_min_range=cfg["lidar_min_range"],
min_range=cfg["lidar_min_range"],
)

self.play_on_start = os.environ.get("PLAY_SIM_ON_START", "true").lower() == "true"
Expand Down
Loading
Loading