Skip to content

PoseNode

This module contains PoseNode, a ROS node that estimates camera pose in the global (REP 105 earth) frame of reference.

The reference image is an orthoimage raster from the onboard GIS server. Deep learning based keypoint matching provides a global (absolute) but noisy pose estimate that is drift-free.

The pose is estimated by finding matching keypoints between the query and reference images and then solving the resulting PnP problem.

Classes:

PoseNode(*args, **kwargs)Estimates camera pose in global (REP 105 earth) frame of reference by finding matching keypoints and solving the PnP problem.

class gisnav.core.pose_node.PoseNode(*args, **kwargs)

Bases: Node

Estimates camera pose in global (REP 105 earth) frame of reference by finding matching keypoints and solving the PnP problem.

Class initializer

  • Parameters:
    • args – Positional arguments to parent Node constructor
    • kwargs – Keyword arguments to parent Node constructor

Attributes:

CONFIDENCE_THRESHOLDConfidence threshold for filtering out bad keypoint matches
MAX_KEYPOINTSMax number of SIFT keypoints to detect when matching on CPU
MIN_MATCHESMinimum number of keypoint matches before attempting pose estimation
camera_infoCamera info including the intrinsics matrix, or None if unknown
poseCamera pose in REP 105 earth frame
pose_imageAligned and cropped query, reference, DEM rasters from StereoNode

CONFIDENCE_THRESHOLD = 0.5

Confidence threshold for filtering out bad keypoint matches

MAX_KEYPOINTS = 1024

Max number of SIFT keypoints to detect when matching on CPU

See also TwistNode.MAX_KEYPOINTS.

Keep this low to increase matching speed especially on resource constrained systems.

MIN_MATCHES = 15

Minimum number of keypoint matches before attempting pose estimation

property camera_info : CameraInfo | None

Camera info including the intrinsics matrix, or None if unknown

property pose : PoseWithCovarianceStamped | None

Camera pose in REP 105 earth frame

This represents the global 3D position and orientation of the camera_optical frame in the REP 105 earth (ECEF) frame. This is obtained via deep matching and is a discontinuous estimate of pose. It is intended to be fused with and complement the continous or smooth twist estimate obtained via shallow matching or visual odometry (VO).

property pose_image : OrthoStereoImage | None

Aligned and cropped query, reference, DEM rasters from StereoNode

This image couple is used for “deep” matching.

GISNav v0.68.1-2-gf2c72641

Released under the MIT License.