StereoNode
This module contains StereoNode
, a ROS node that generates and publishes a synthetic query and reference stereo image couple.
Synthetic refers to the fact that no stereo camera is actually assumed or required. The reference os an aligned orthoimage and DEM raster from the GIS server.
Alignment and cropping to the same dimension as the query image is done to the reference orthoimage by using information of the onboard camera resolution and the vehicle’s heading. Alignment is required since the deep learning network that is used for matching keypoints is not assumed to be rotation agnostic.
Classes:
StereoNode (*args, **kwargs) | Generates and publishes a synthetic query and reference stereo image couple. |
---|
class gisnav.core.stereo_node.StereoNode(*args, **kwargs)
Bases: Node
Generates and publishes a synthetic query and reference stereo image couple.
Class initializer
- Parameters:
- args – Positional arguments to parent
Node
constructor - kwargs – Keyword arguments to parent
Node
constructor
- args – Positional arguments to parent
Attributes:
camera_info | Subscribed camera info for determining appropriate orthoimage crop resolution, or None if unknown |
---|---|
keypoints | Subscribed query image keypoints, or None if unknown |
orthoimage | Subscribed orthoimage, or None if unknown |
Methods:
pnp_image (keypoint_cloud) | Published aligned and cropped orthoimage consisting of query image, reference image, and optional reference elevation raster (DEM). |
---|
property camera_info : CameraInfo | None
Subscribed camera info for determining appropriate orthoimage
crop resolution, or None if unknown
property keypoints : PointCloud2 | None
Subscribed query image keypoints, or None if unknown
property orthoimage : OrthoImage | None
Subscribed orthoimage, or None if unknown
pnp_image(keypoint_cloud: PointCloud2)
Published aligned and cropped orthoimage consisting of query image, reference image, and optional reference elevation raster (DEM).
GISNav v0.68.1-2-gf2c72641