Integration Guide
Overview
The Vantor Raptor SDK is used for determining absolute positioning of airborne vehicles. This is achieved by performing visual real-time matching between images captured from onboard camera sensors and high-resolution 3D maps (Vantor Vivid Terrain 3DSM and/or Vantor WorldView 3D). Raptor Guide performs separate camera pose estimations for each individual frame and has no knowledge of either previous frames or the camera's rotation relative to the aircraft's orientation. In this way, Raptor Guide can be used to estimate position and attitude of the camera but not heading and velocity for the aircraft. Therefore, Raptor Guide should not be used as a standalone navigation system, but is rather designed to be used as a component to be integrated and fused with other sensors such as IMU, magnetometer, barometric sensors, etc., in a complete navigation system.
Raptor Guide's ability to independently estimate the position using onboard processing of 3D maps makes it an ideal component to create GNSS-independent navigation systems, which can operate effectively even in environments where GNSS signals are denied or jammed. Hence, integrating Raptor Guide with other sensors enables the development of a robust and accurate navigation system even without the use of GNSS.
This guide covers the essential integration steps and best practices for incorporating the SDK into your application.
SDK Distribution and Dependencies
Shared Library Distribution
The Raptor SDK is distributed as a shared library:
- Library file:
lib/libraptor.so(linker name; resolves tolibraptor.so.<MAJOR>at runtime andlibraptor.so.<VERSION>on disk) - Header files: Located in the
include/directory - Resources: Geo resources in
resources/geo/directory (shipped as a separate package but required for SDK functionality) - Dependency reference:
docs/markdown/raptor_dependencies.mdlists the required compiler/linker flags and the runtime shared-library dependencies (DT_NEEDEDentries) of the shippedlibraptor.so.
Python Bindings
Python bindings are available as a wheel package. You can either install the pre-built wheel directly or build from source:
- Pre-built wheel: See
python/in the release package for installation instructions - Build from source: See
python/bindings/in the release package for build instructions - Usage examples: See
python/examples/guide/in the release package for usage examples - CANV integration tool: See
python/tools/in the release package forrefine_canv_poses.py, an adaptable end-to-end driver that runs every frame of a CANV v6 recording throughPoseEstimatorand writes a new CANV with the refined poses, covariances, and confidence values attached
GPU Requirements
The SDK uses Vulkan for GPU acceleration for rendering and computations. See Vulkan for:
- Vulkan version and feature requirements
- How to verify GPU support
- GPU selection on multi-GPU systems
Geo Resources
The Raptor SDK requires geo resources for coordinate transformations (e.g., geoid models for height conversion between ellipsoid and EGM2008). These resources are shipped separately from the SDK library.
Initialization
SDK initialization is tied to the lifetime of a raptor::Context. A Context
must be created before any other Raptor SDK object (e.g. raptor::guide::PoseEstimator)
and must outlive every object that references it. The Context resolves geo
resources, verifies the license, and constructs the SDK's primary engine.
The Context is constructed directly from a raptor::Config. Multiple
Context instances may coexist in a process, but each one independently
holds resources, so most applications will only need one.
The SDK-wide map/image fields cannot change for the lifetime of a Context.
To switch maps or image dimensions at runtime, destroy the existing Context
and construct a new one.
Default Search Paths
If no path is specified, the SDK searches for geo resources in the following locations (in order):
Linux:
data/resources/geo/usr/local/share/raptor/data/resources/geo/usr/share/raptor/data/resources/geo/opt/raptor/share/raptor/data/resources/geo
Environment Variables
You can use environment variables to specify the geo resources path:
Option 1: RAPTOR_GEO_RESOURCE_PATH (highest priority)
export RAPTOR_GEO_RESOURCE_PATH=/custom/path/to/geo/resources
Option 2: RAPTOR_DATA_DIR
export RAPTOR_DATA_DIR=/path/to/raptor/data
# SDK will look for geo resources at: $RAPTOR_DATA_DIR/resources/geo
Environment variables take precedence over the default search paths. RAPTOR_GEO_RESOURCE_PATH takes precedence over RAPTOR_DATA_DIR.
Explicit Path Configuration
To specify a geo resource path programmatically, set
raptor::Config::geoResourcePath and pass the Config to the Context
constructor:
#include <raptor/Config.hpp>
#include <raptor/Context.hpp>
// Initialize with custom path
raptor::Config config{};
config.geoResourcePath = "/path/to/geo/resources";
raptor::Context context{config};
// Or let it use environment variables / default paths
raptor::Context context{};
The Context constructor throws std::runtime_error on initialization
failure.
Licensing Overview
A valid license is required to use the Raptor SDK. The path to the license file must set in the configuration.
For a detailed description of fingerprint generation, license installation, replacement, and error handling, see the License Management Guide.
Quick Start
1. Basic Integration
Below is an example of the most basic integration of the SDK.
#include <raptor/Config.hpp>
#include <raptor/Context.hpp>
#include <raptor/guide/PoseEstimator.hpp>
#include <raptor/image.hpp>
#include <raptor/lens.hpp>
#include <raptor/geo.hpp>
// Step 1: Configure SDK-wide settings on raptor::Config
raptor::Config config{
.imageWidth = 1920, // Image width in pixels (REQUIRED)
.imageHeight = 1080, // Image height in pixels (REQUIRED)
.licensePath = "/path/to/license.license", // Path to license file (REQUIRED)
.mapPaths = {"data/example/map/vricon_3d_surface_model/data/db.r3db"}
};
// Step 2: Create the SDK context (must outlive the PoseEstimator)
raptor::Context context{config};
// Step 3: Initialize the PoseEstimator with the context
raptor::guide::PoseEstimator estimator{context};
// Step 4: Create image view, lens model, and pose
raptor::ImageView image{raptor::ImageType::Gray8, config.imageWidth, config.imageHeight, grayImageData};
auto lens = raptor::LensModel{
raptor::lens::Pinhole::fromFov(hFovRad, vFovRad, config.imageWidth, config.imageHeight)
};
// Create pose with geodetic position and attitude, using default CRS
// (degrees for lat/lon, meters for altitude, ellipsoid height system, ITRF2008)
raptor::pose::Geodetic initialPose{
.coords = {.lat = latDeg, .lon = lonDeg, .alt = altMeters},
.attitude = {.x = qx, .y = qy, .z = qz, .w = qw}
};
// Step 5: Process image (per-call tuning lives on EstimationOptions)
auto result = estimator.updatePose(image, lens, initialPose, timestamp);
// Step 6: Validate results
if (auto* output = std::get_if<raptor::guide::PoseOutput<raptor::pose::Geodetic>>(&result);
output && output->confidence > 0.75) {
// Extract refined pose
auto refinedPose = output->pose;
// Use refinedPose.coords (position) and refinedPose.attitude (quaternion)
}
Alternative: Position-only estimation
auto result = estimator.updatePosition(image, lens, initialPose, timestamp);
// Returns PositionOutput with refined position only (no updated attitude)
2. Complete Examples
Complete C++ examples are available in the documentation package under examples/guide/. These include basic and advanced usage demonstrating covariance, time limits, and geodetic coordinates.
See also Conventions for detailed coordinate system and attitude representation guide.
Input Requirements
Image Data
Images are passed using the raptor::ImageView or raptor::Image type:
- Supported Formats:
raptor::ImageType::Gray8- Grayscale, 8-bit, single channel (1 byte/pixel)raptor::ImageType::Rgb8- RGB, 8-bit per channel, interleaved (3 bytes/pixel)raptor::ImageType::Rgba8- RGBA, 8-bit per channel, interleaved (4 bytes/pixel)
- Layout: Row-major, top-to-bottom, left-to-right, channels interleaved
- Size: Must match
config.imageWidth × config.imageHeightexactly - Memory: Contiguous array of
width × height × bytesPerPixelbytes - Preprocessing: Make sure the image data is undistorted.
Lens Model
Camera parameters are passed using the raptor::LensModel type.
Preferred — explicit pinhole parameters from camera calibration:
auto lens = raptor::LensModel{
raptor::lens::Pinhole{.fx = focalX, .fy = focalY,
.cx = centerX, .cy = centerY}
};
This form uses your camera's calibrated focal lengths and principal point
directly and is the recommended way to construct a LensModel.
Alternative — from field of view:
auto lens = raptor::LensModel{
raptor::lens::Pinhole::fromFov(hFovRad, vFovRad, imageWidth, imageHeight)
};
Pinhole::fromFov(...) is a convenience for cases where only the horizontal
and vertical field of view are known. It assumes the principal point is at
the image center and derives focal lengths from the FOV; if your calibrated
principal point is offset from the center, prefer the explicit form above
for best accuracy.
- Field of View: Must match actual camera calibration. Wide lenses not recommended. Fisheye lenses not supported.
- Units: Radians for FOV, pixels for pinhole parameters
Pose
Poses are passed using the pose types (raptor::pose::Ecef or raptor::pose::Geodetic).
A pose contains the position coordinates and the attitude.
// Geodetic pose (default CRS: ITRF2008, degrees, meters, ellipsoid height)
raptor::pose::Geodetic geodPose{
.coords = {.lat = latDeg, .lon = lonDeg, .alt = altMeters},
.attitude = {.x = qx, .y = qy, .z = qz, .w = qw},
};
// Or ECEF
raptor::pose::Ecef ecefPose{
.coords = {.x = x, .y = y, .z = z},
.attitude = {.x = qx, .y = qy, .z = qz, .w = qw},
};
See Coordinate Reference Systems for how to override the CRS on a pose, and Conventions for the attitude and NED conventions.
Image Timestamp
Each updatePose() / updatePosition() call takes a mandatory
std::chrono::nanoseconds timestamp identifying when the input image was
captured. The value is preserved unchanged in the output timestamp field
to allow correlation with the source frame.
- The timestamp must reflect the image capture time, not the time of the SDK call.
- The epoch is application-defined and must be consistent across calls within your application.
- The timestamp must be strictly positive (
> 0 ns) when Debug Capture is active. Frames with a non-positive timestamp are dropped from the debug archive (an error is logged) while theupdatePose()/updatePosition()call itself still runs and returns normally.
Coordinate Reference Systems
The SDK supports two coordinate systems on inputs and outputs:
raptor::pose::Ecef— Cartesian[X, Y, Z]in meters from Earth's centre.raptor::pose::Geodetic—[lat, lon, alt]with attitude relative to local NED. Recommended when supplying a covariance matrix.
For the underlying geodetic, NED and attitude conventions see Conventions. This section only documents how to configure the CRS on a pose.
Each pose carries its own CRS in a .crs field; the defaults are:
| CRS field | Default | Other values |
|---|---|---|
referenceFrame | Itrf2008 | Wgs84g1674 |
horizontalUnit (Geodetic) | Degrees | Radians |
verticalUnit (Geodetic) | Meter | Foot (= 0.3048 m) |
heightSystem (Geodetic) | Ellipsoid (HAE) | Egm2008 (geoid / HAMSL) |
Example
// Default CRS: ITRF2008, degrees, meters, ellipsoid height
raptor::pose::Geodetic pose{
.coords = {.lat = 39.5, .lon = -77.5, .alt = 1542},
.attitude = {.x = 0, .y = 0, .z = 0, .w = 1},
};
// Override individual CRS fields as needed
raptor::pose::Geodetic poseRadFeetGeoid{
.coords = {.lat = 0.6894, .lon = -1.352, .alt = 5059},
.attitude = {.x = 0, .y = 0, .z = 0, .w = 1},
.crs = {
.horizontalUnit = raptor::crs::HorizontalUnit::Radians,
.verticalUnit = raptor::crs::VerticalUnit::Foot,
.heightSystem = raptor::crs::HeightSystem::Egm2008,
},
};
Configuration Parameters
Configuration is split into two structs:
raptor::Config— SDK-wide settings, consumed byraptor::Contextat construction.raptor::guide::EstimationOptions— per-call tuning knobs, passed to eachupdatePose()/updatePosition()call.
raptor::Config
raptor::Config config{
.imageWidth = 1920,
.imageHeight = 1080,
.licensePath = "/path/to/license.license",
.mapPaths = {"path/to/map.r3db"},
.detailStage1 = 8,
.detailStage2 = 9,
// .coordinateEpoch = 2025.0f, // optional, tectonic-shift correction
};
| Field | Required | Default | Notes |
|---|---|---|---|
imageWidth, imageHeight | yes | — | Must match the input frames exactly |
licensePath | yes | — | See License Management |
mapPaths | yes | — | One or more .r3db / .3tz files |
detailStage1 | no | 8 | Initial search detail (7 = faster, 9 = more accurate) |
detailStage2 | no | 9 | Refinement detail (8 = faster, 10 = more accurate) |
coordinateEpoch | no | unused | Decimal year for tectonic-plate correction |
geoResourcePath | no | auto-discover | See Geo Resources |
logger | no | INFO → stdout | See Logger |
raptor::guide::EstimationOptions
raptor::guide::EstimationOptions options{
.confidenceInterval = 0.95,
.featureDensityCheck = true,
.maxTime = std::chrono::milliseconds(1000),
};
auto result = estimator.updatePose(image, lens, pose, timestamp, covariance, options);
| Field | Default | Notes |
|---|---|---|
confidenceInterval | 0.90 | Search-region coverage (0.68 ≈ 1σ, 0.95 ≈ 2σ); see Search Range |
featureDensityCheck | false | Reject visually ambiguous frames early (see below) |
exhaustiveRangeSearch | false | More thorough search within the same region; see Exhaustive Range Search |
maxTime | unbounded | Wall-clock limit; the best result so far is returned |
Feature Density Pre-check
With featureDensityCheck = true, the estimator computes feature density
before running the range search and returns
PoseEstimationError::PoorFeatureDensity for inputs that look visually
ambiguous (e.g. uniform surfaces). This avoids spending time on frames
that are unlikely to yield a reliable pose.
The same check is exposed as a standalone helper for filtering frames before calling the estimator:
#include <raptor/analyze.hpp>
auto density = raptor::computeFeatureDensity(context, image);
if (auto* v = std::get_if<float>(&density); v && *v < 0.02f) {
continue; // skip frame
}
Logger Configuration
The SDK writes log output through a single logger owned by raptor::Context.
By default, messages at INFO level and above are formatted and written to
stdout. Configure via raptor::Config::logger before constructing the
context.
config.logger = {
.name = "my-app", // surfaced as LogMessage::name
.level = raptor::LogLevel::INFO, // minimum level (default: INFO)
};
raptor::LogLevel is ordered TRACE < DEBUG < INFO < WARNING < ERROR < CRITICAL < OFF. Setting level enables that level and all higher ones;
OFF disables logging entirely.
To route messages elsewhere, set logger.callback. The callback receives a
raptor::LogMessage containing level, timestamps, formatted message and
logger name.
config.logger.callback = [](const raptor::LogMessage& msg) {
std::cerr << "[" << msg.name << "] " << msg.message << '\n';
};
The callback may be invoked from any thread and must be thread-safe. Any
state it captures must outlive the owning raptor::Context. A nullptr
callback disables external log delivery.
Loading Configuration from JSON
raptor::parseConfigFromJson() populates a raptor::Config from a JSON
file, useful for deploying or switching configurations without recompiling.
Per-call tuning knobs (EstimationOptions) are still set programmatically.
Schema
The JSON keys mirror the field names on raptor::Config:
{
"licensePath": "/path/to/license.license",
"mapPaths": ["/path/to/map1.r3db", "/path/to/map2.r3db"],
"imageWidth": 1920,
"imageHeight": 1080,
"detailStage1": 8,
"detailStage2": 9,
"coordinateEpoch": 2025.0
}
licensePath and mapPaths are required on the resulting
raptor::Config before Context construction, but they may be left
empty ("" or []) in the JSON and supplied at runtime. The parser only
fails if these keys are missing altogether. All remaining keys are
optional; see Configuration Parameters for
defaults and meaning.
Usage
auto parsed = raptor::parseConfigFromJson("config.json");
if (auto* failure = std::get_if<raptor::ConfigParseFailure>(&parsed)) {
// failure->error / failure->field / failure->detail describe the issue
return;
}
auto config = std::get<raptor::Config>(parsed);
// Fill in anything left empty in the JSON
if (config.licensePath.empty()) config.licensePath = "/path/to/license.license";
if (config.mapPaths.empty()) config.mapPaths = {"/path/to/map.r3db"};
raptor::Context context{config};
raptor::guide::PoseEstimator estimator{context};
Error Handling
Initialization
raptor::Context and raptor::guide::PoseEstimator construction throws on
failure. Wrap construction in try/catch; std::runtime_error covers
missing resources and other initialisation failures, and
std::invalid_argument covers malformed configuration.
try {
raptor::Context context{config};
raptor::guide::PoseEstimator estimator{context};
} catch (const std::runtime_error& e) {
std::cerr << "SDK initialization failed: " << e.what() << std::endl;
} catch (const std::invalid_argument& e) {
std::cerr << "Invalid configuration: " << e.what() << std::endl;
}
Per-call results
updatePose() and updatePosition() do not throw. Each returns a
std::variant that holds either a PoseOutput / PositionOutput on
success or a PoseEstimationError on failure. Always check both the
variant alternative and the confidence field before using the
refined pose (see Quality Assessment).
auto result = estimator.updatePose(image, lens, pose, timestamp);
auto* output = std::get_if<raptor::guide::PoseOutput<raptor::Pose>>(&result);
if (output == nullptr) {
auto error = std::get<raptor::guide::PoseEstimationError>(result);
// log and skip frame
continue;
}
if (output->confidence < 0.7) {
// unreliable result; skip frame
continue;
}
auto refinedPose = output->pose;
Quality Assessment
Confidence
PoseOutput::confidence / PositionOutput::confidence is the SDK's
quality score, combining reprojection error with the match quality between
the input image and the rendered map texture. See
Uncertainty for the underlying interpretation.
Recommended thresholds:
| Confidence | Interpretation |
|---|---|
| > 0.95 | Excellent — high accuracy |
| 0.85–0.95 | Good — reliable for most applications |
| 0.7–0.85 | Moderate — use with caution, monitor consistency |
| < 0.7 | Poor — reject; no robust match found |
Map coverage
PoseOutput::mapCoverage / PositionOutput::mapCoverage (range [0, 1])
reports the fraction of the rendered view backed by 3D map data. Low
values mean parts of the camera view fall outside the loaded map (sky,
terrain beyond map boundary) and typically correlate with lower
confidence.
To inspect coverage before running pose estimation — for example to
validate that a given prior pose is usable — call
raptor::renderMapCoverage(). It returns an 8-bit mask of the same
dimensions as the rendered map view (0xFF = covered, 0x00 = no map).
auto result = raptor::renderMapCoverage(context, lens, pose);
if (auto* image = std::get_if<raptor::Image>(&result)) {
// pixels: 0xFF where the map covers the view, 0x00 otherwise
} else {
// std::get<raptor::OperationError>(result) describes the failure
}
Covariance Matrix Usage
Supplying a 6×6 prior covariance to updatePose() / updatePosition() lets
the SDK search a region around the prior instead of refining a single
hypothesis. Without covariance, only that single hypothesis is tested — fast,
but only suitable when the prior pose is already close to the true pose.
The covariance is always expressed in the camera frame
(DIN 9300: x forward, y right, z down). The same frame is used for the
output covariance returned on PoseOutput::covariance /
PositionOutput::covariance.
Matrix Layout
The covariance argument is a row-major 6×6 matrix passed as
std::array<double, 36>. Off-diagonal entries are accepted; the diagonal
carries the per-dimension variances.
| Index | Component | Unit | Meaning |
|---|---|---|---|
| [0] | X (forward) | m² | Position variance along the camera's forward axis |
| [7] | Y (right) | m² | Position variance along the camera's right axis |
| [14] | Z (down) | m² | Position variance along the camera's down axis |
| [21] | Yaw | rad² | Rotation variance about the camera's down axis |
| [28] | Pitch | rad² | Rotation variance about the camera's right axis |
| [35] | Roll | rad² | Rotation variance about the camera's forward axis |
Attitude variances
The bottom-right 3×3 block carries the rotation uncertainty about the
camera axes, in the order shown in the index table above. Variances are
applied symmetrically around the input attitude — a yaw variance of
σ² searches roughly ±σ on either side of the input yaw at the
default confidence interval.
Rotating between frames
If your uncertainty is expressed in a different frame (e.g. local NED,
ECEF, aircraft body), rotate it into the camera frame before passing
it in. With a 3×3 rotation R = R_camera_from_source:
Position block (top-left 3×3):
C_pos_camera = R · C_pos_source · Rᵀ
Attitude block (bottom-right 3×3):
C_att_camera = R · C_att_source · Rᵀ
Note: the attitude block is indexed as
(yaw, pitch, roll)— rotations about the camera'sz,y,xaxes, in that order. Make sure your source covariance follows the same ordering before applying the rotation.
R_camera_from_source for common source frames (let Q = pose.attitude.toMatrix(),
which is row-major, same layout as raptor::Quaternion::toMatrix()):
-
Local NED (covariance from a
pose::Geodetic-style nav output).QencodesR_NED_from_camera, soR_camera_from_NED = Qᵀ -
ECEF (covariance from a
pose::Ecef-style nav output).QencodesR_ECEF_from_camera, soR_camera_from_ECEF = Qᵀ -
Aircraft body (covariance from an IMU bolted to the airframe, on a camera mounted at a non-trivial orientation).
Ris the camera mount rotation derived as the example in Conventions § Platform to camera:R_camera_from_aircraft = R_body_to_camFor a camera rigidly aligned with the airframe (forward-looking, no tilt) this is the identity and the covariance can be passed through unchanged.
Search Range
Per pose dimension the search range is
searchRange = ±sqrt(chiSquaredValue × variance)
where chiSquaredValue is determined by EstimationOptions::confidenceInterval
and the 6 degrees of freedom of the pose. confidenceInterval controls
how much of your uncertainty region to search, not how confident you
are in the covariance values themselves.
Common values (Wilson–Hilferty approximation, 6 dof):
confidenceInterval | χ² | |
|---|---|---|
| 0.68 | ~7.01 | 1σ |
| 0.90 | ~10.62 | default |
| 0.95 | ~12.57 | 2σ |
| 0.99 | ~16.83 | high confidence |
Worked example. To search ±100 m along a camera-frame axis at 95% confidence (χ² ≈ 12.57), set the corresponding diagonal variance to
variance = 100² / 12.57 ≈ 795 m² (≈ 28 m std. dev.)
Performance impact
- Larger variances → larger search → more hypotheses → longer runtime.
- Smaller variances → faster, but the algorithm may fail to find the true pose if the prior is outside the searched region.
- No covariance → single hypothesis, fastest; only safe when the prior is known to be accurate.
Exhaustive Range Search
EstimationOptions::exhaustiveRangeSearch = true performs a more thorough
search within the same search region (it does not enlarge it). It can
improve accuracy in difficult scenes at a significant runtime cost; pair
with EstimationOptions::maxTime to bound the call.
raptor::guide::EstimationOptions options{
.exhaustiveRangeSearch = true,
.maxTime = std::chrono::milliseconds(2000),
};
auto result = estimator.updatePose(image, lens, pose, timestamp, covariance, options);
Performance and Threading
Reuse a single Context and PoseEstimator
Construct Context and PoseEstimator once and reuse them across all
frames. Construction loads the maps and initialises GPU resources, so
creating a new instance per frame is significantly more expensive than the
estimation call itself.
raptor::Context context{config};
raptor::guide::PoseEstimator estimator{context};
for (const auto& [image, timestamp] : images) {
auto result = estimator.updatePose(image, lens, pose, timestamp);
// handle result...
}
Multiple Context / PoseEstimator instances in the same process compete
for GPU memory and compute and should be avoided.
Time limits for real-time use
Estimation time varies with the platform and the size of the search region
(driven by the input covariance). For real-time applications, bound the
call with EstimationOptions::maxTime; the algorithm returns the best
result found within the limit.
raptor::guide::EstimationOptions options{
.maxTime = std::chrono::milliseconds(1000)
};
auto result = estimator.updatePose(image, lens, pose, timestamp, covariance, options);
Thread safety
raptor::Context and raptor::guide::PoseEstimator are not
thread-safe. Do not share a single instance across threads or call
updatePose() / updatePosition() concurrently on the same estimator.
Common Issues & Solutions
Initialization Failures
Problem: SDK initialization throws exception
Solutions:
- Ensure map files (.r3db or .3tz) exist and are readable
- Check available RAM/GPU memory (minimum 4GB required, 8GB recommended)
- Verify Vulkan-compatible GPU and drivers
- Use absolute paths for reliability
Poor Quality Results
Problem: Low Confidence (confidence < 0.7) or PoseEstimationError::Failed
Root Causes & Solutions:
-
Initial pose too inaccurate
- If the initial pose is too far off, the algorithm may fail to find a good match
- Provide covariance matrix reflecting actual uncertainty
-
Camera calibration mismatch
- Verify FOV values match actual camera calibration
- Make sure the image has been undistorted — the camera's intrinsic
parameters must be calibrated and compensated for before calling
updatePose()
-
Image quality issues
- Ensure sufficient contrast and texture in image
- Check for motion blur or focus issues
-
Map Coverage problems
- Verify 3D map covers your area of interest
- Check map resolution is sufficient for your altitude
-
Correlation mismatch between image and map
- If the image contains water bodies and/or sky, the correlation with the map will be poor.
- Verify the map covers the area with sufficient detail
- If the terrain has changed since the map was created (e.g. construction, natural disasters), the correlation will also be poor.
Covariance Configuration Issues
Problem: Estimation failures with uncertain initial poses
Solutions:
- Always provide covariance when pose uncertainty is high
- Set variance values to match actual uncertainty (not smaller)
- Monitor success rates and adjust covariance accordingly
Performance Issues
Problem: Processing too slow for real-time applications
Solutions:
- Set
maxTimeparameter for time-limited processing - Reduce
detailStage1anddetailStage2values - Provide appropriate covariance to focus search area
Map Inspection and Queries
In addition to pose estimation, the SDK exposes a handful of top-level
free functions for inspecting the loaded 3D map. They share the same
raptor::Context as the pose estimator and do not require a
PoseEstimator instance.
Rendering the map from a viewpoint
raptor::renderMap() renders the loaded 3D map from a given camera
viewpoint as a grayscale image. It is useful for manually validating that
a prior pose lines up with the map, or for inspecting the input the
estimator would see during refinement.
#include <raptor/render.hpp>
auto result = raptor::renderMap(context, lens, pose);
if (auto* image = std::get_if<raptor::Image>(&result)) {
// image holds the rendered map view at the given pose
} else {
// std::get<raptor::OperationError>(result) describes the failure
}
See Map coverage for the related
raptor::renderMapCoverage(), which renders an 8-bit coverage mask for
the same viewpoint.
Map intersection queries
raptor::queryMapIntersection() returns the 3D point on the map surface
hit by a given input. Three forms are provided in <raptor/query.hpp>:
- From a horizontal location — casts straight down from the supplied
position and returns the surface hit. Useful for looking up the map
surface height at a
(lat, lon)or(x, y, z). - From a
Ray— casts the supplied origin + direction and returns the first surface hit. - Per-pixel — given a
LensModelandPose, casts a ray through each supplied pixel coordinate and returns one hit per pixel.
#include <raptor/query.hpp>
// 1. Lookup the map surface point directly below a geodetic location.
raptor::position::Geodetic above{
.coords = {.lat = 39.5, .lon = -77.5, .alt = 1500.0},
};
auto hit = raptor::queryMapIntersection(context, above);
if (auto* surface = std::get_if<raptor::position::Geodetic>(&hit)) {
// surface->coords.alt is the map-surface height at (lat, lon)
} else {
// std::get<raptor::MapQueryError>(hit) describes the failure
}
// 2. Cast a ray and return the first map-surface hit.
raptor::ray::Geodetic ray{
.origin = {.coords = {.lat = 39.5, .lon = -77.5, .alt = 1500.0}},
.direction = {.north = 0.0, .east = 0.0, .down = 1.0},
};
auto rayHit = raptor::queryMapIntersection(context, ray);
// 3. Per-pixel intersection for an image grid.
std::vector<raptor::PixelCoordinates> pixels{ {320, 240}, {640, 480} };
auto perPixel = raptor::queryMapIntersection(context, lens, pose, pixels);
for (auto& entry : perPixel) {
if (auto* p = std::get_if<raptor::position::Geodetic>(&entry)) {
// p->coords holds the surface hit for this pixel
}
}
PixelCoordinates use fractional pixel coordinates with [0, 0] at the
upper-left corner of the upper-left pixel. Overloads taking
position::Geodetic / position::Ecef (and the equivalent ray::* /
pose::* forms) return the matching concrete type directly; the generic
Position / Ray / Pose overloads return a Position variant.
Note:
queryMapIntersection()returns the map-surface hit, not the bare ground. If the map contains buildings or trees at the query location, the rooftop or canopy is returned.
Debug Capture
For analysis of pose estimation behaviour, the SDK can record every
updatePose() or updatePosition() call into a CanV archive.
Usage
#include <raptor/guide/PoseEstimator.hpp>
raptor::guide::PoseEstimator estimator{context};
// Start capture. Returns DebugResult::Ok on success.
if (estimator.startDebug("/tmp/session.canv", /*overwrite=*/true) !=
raptor::guide::DebugResult::Ok) {
// Handle DebugResult::{InvalidLicense, FileExists, InvalidPath, ...}
}
// All updatePose()/updatePosition() calls between start and stop are
// recorded as frames in the archive.
estimator.updatePose(image, lens, pose, timestamp);
// Finalize the archive. Returns DebugResult::NotActive if no capture was
// running, or DebugResult::Failed on a finalization error.
estimator.stopDebug();
See Image Timestamp for the requirement on captured frames.
Further reference
- Runnable examples:
examples/guide/in the documentation package - Coordinate systems and attitude derivation: Conventions
- API reference: header files in
include/raptor/