Mapping API
The Mapping API gives access to fast real-time 3D reconstructions. It can also be used together with Replay API for high-quality post-processed results, which can also be given as inputs to other tools such as Nerfstudio.
- class spectacularAI.mapping.Frame
A single camera frame with a pose and bitmap image
- property cameraPose
CameraPose
for this frame
- property depthScale
float
Scale of depth image, for non-depth images this is -1.0
- property sparseFeatures
List of
FeaturePoint
. 2D-to-3D sparse feature matches in this frame. Empty if not available for this frame type, e.g., depth frames.
- property visualMarkers
List of
VisualMarker
. Visual Markers detected in this frame. Only April Tags are supported currently. Always empty if April Tag detection is not enabled.
- class spectacularAI.mapping.FrameSet
A set of camera frames from multiple cameras at a moment of time.
- getAlignedDepthFrame(self: spectacularAI.mapping.FrameSet, arg0: spectacularAI::mapping::Frame) spectacularAI::mapping::Frame
Compute the depth map at the camera pose of the input frame (for example rgbFrame). If depthFrame is already aligned to the the input camera, returns depthFrame.
- getUndistortedFrame(self: spectacularAI.mapping.FrameSet, arg0: spectacularAI::mapping::Frame) spectacularAI::mapping::Frame
Returns an undistorted version of the input frame (i.e., with camera model = undistorted pinhole). If the input frame is not distorted, returns the input frame.
- class spectacularAI.mapping.KeyFrame
A SLAM KeyFrame
- property id
int
Unique identifier for this key frame
- property pointCloud
PointCloud
Point cloud for this key frame in primary frame coordinates
- class spectacularAI.mapping.Map
A map generated by SLAM
- class spectacularAI.mapping.MapperOutput
Main mapping output structure
- property finalMap
A
bool
that indicates the map is now final and won’t be updated any longer. This is true the when the program exits.
- property updatedKeyFrames
List of
int
. Key frame ids that were updated (created, modified or deleted) since the last callback
- property updatedMapPoints
List of
int
. Map points ids that were updated (created, modified or deleted) since the last callback
- class spectacularAI.mapping.Mesh
A generic 3D mesh with a few optional properties (e.g., normals).
- empty(self: spectacularAI.mapping.Mesh) bool
True when mesh has no vertices
- faceCount(self: spectacularAI.mapping.Mesh) int
Number of faces (L)
- getFaceNormals(self: spectacularAI.mapping.Mesh) numpy.ndarray[numpy.uint32]
A numpy array of size Lx3 that contains all face normals indices if they exist
- getFaceVertices(self: spectacularAI.mapping.Mesh) numpy.ndarray[numpy.uint32]
A numpy array of size Lx3 that contains all face vertex indices.
- getNormalData(self: spectacularAI.mapping.Mesh) numpy.ndarray[numpy.float32]
A numpy array of size Mx3 that contains all vertex normals if they exist
- getPositionData(self: spectacularAI.mapping.Mesh) numpy.ndarray[numpy.float32]
A numpy array of size Nx3 that contains all vertex positions
- hasNormals(self: spectacularAI.mapping.Mesh) bool
True when mesh has normal data
- normalCount(self: spectacularAI.mapping.Mesh) int
Number of normals (M)
- vertexCount(self: spectacularAI.mapping.Mesh) int
Number of vertices (N)
- class spectacularAI.mapping.PointCloud
Point cloud with position, and optional point normal and color data
- empty(self: spectacularAI.mapping.PointCloud) bool
True when point cloud has no points
- getNormal(self: spectacularAI.mapping.PointCloud, arg0: int) spectacularAI.Vector3f
Get normal of a single point. Check first that normal data exists for this point cloud
- getNormalData(self: spectacularAI.mapping.PointCloud) numpy.ndarray[numpy.float32]
A numpy array of size Nx3 that contains all point normals if they exist
- getPosition(self: spectacularAI.mapping.PointCloud, arg0: int) spectacularAI.Vector3f
Get position of a single point
- getPositionData(self: spectacularAI.mapping.PointCloud) numpy.ndarray[numpy.float32]
A numpy array of size Nx3 that contains all point positions
- getRGB24(self: spectacularAI.mapping.PointCloud, arg0: int) List[int[3]]
Get color of a single point. Check first that color data exists for this point cloud
- getRGB24Data(self: spectacularAI.mapping.PointCloud) numpy.ndarray[numpy.uint8]
A numpy array of size Nx3 that contains all point colors if they exist
- hasColors(self: spectacularAI.mapping.PointCloud) bool
True when point cloud has color data
- hasNormals(self: spectacularAI.mapping.PointCloud) bool
True when point cloud has normal data
- size(self: spectacularAI.mapping.PointCloud) int
Number of points
- class spectacularAI.mapping.VisualMarker
A visual marker observation in a frame. Only April Tags are supported currently. To enable April Tag detection in the SDK, see https://github.com/SpectacularAI/docs/blob/main/pdf/april_tag_instructions.pdf
- property center
PixelCoordinates
Center of the visual marker in image pixel coordinates
- property corners
List of
PixelCoordinates
. Corners of the visual marker in image pixel coordinates. In visual marker coordinate frame: index 0=bottom-left, 1=bottom-right, 2=top-right, 3=top-left
- property hasPose
bool
Flag that indicates if marker has pose information. Currently markers with unknown size don’t have pose estimate.
- property id
int
Visual marker ID
- property pose
Pose
Camera to visual marker transformation (note: identity if size is not available). The visual marker’s coordinate frame is centered at the center of the marker, with x-axis to the right, y-axis down, and z-axis into the tag.
- property size
float
Visual marker size in meters (note: 0 if not available)
Defined in #include <spectacularAI/mapping.hpp>
-
namespace spectacularAI
-
namespace mapping
Typedefs
-
using MapperOutputPtr = std::shared_ptr<const MapperOutput>
-
struct Frame
Public Members
-
CameraPose cameraPose
Camera pose information
-
std::shared_ptr<const Bitmap> image
Image data from the camera, might not always exist
-
double depthScale
Set when image type is depth. Depth image values are multiplied by this number to to make their unit meters (e.g., if depth is integer mm, this will be set to 1.0 / 1000)
-
std::vector<FeaturePoint> sparseFeatures
2D-to-3D sparse feature matches in this frame. Empty if not available for this frame type, e.g., depth frames.
-
std::vector<VisualMarker> visualMarkers
Visual Markers detected in this frame.
Only April Tags are supported currently. Always empty if April Tag detection is not enabled.
-
CameraPose cameraPose
-
struct FrameSet
Public Functions
-
virtual std::shared_ptr<Frame> getAlignedDepthFrame(const std::shared_ptr<Frame> target) const = 0
Compute the depth map at the camera pose of the given frame (for example rgbFrame). If depthFrame is already aligned to the the given camera, returns a pointer to depthFrame.
-
virtual std::shared_ptr<Frame> getUndistortedFrame(const std::shared_ptr<Frame> distortedFrame) const = 0
Returns an undistorted version of the given frame (i.e., with camera model = undistorted pinhole). If the given frame is not distorted, returns a pointer to distortedFrame.
-
inline virtual ~FrameSet()
Public Members
-
std::shared_ptr<Frame> primaryFrame
Primary camera frame used for tracking
-
std::shared_ptr<Frame> secondaryFrame
Secondary camera frame used for tracking when using stereo cameras
-
std::shared_ptr<Frame> rgbFrame
RGB color frame if such exists. When using RGB-D this is the same as primaryFrame
-
std::shared_ptr<Frame> depthFrame
Depth frame
-
virtual std::shared_ptr<Frame> getAlignedDepthFrame(const std::shared_ptr<Frame> target) const = 0
-
struct KeyFrame
Public Members
-
int64_t id
Unique ID for this keyframe. Monotonically increasing.
-
std::shared_ptr<FrameSet> frameSet
Set of frames available for this keyframe.
-
std::shared_ptr<PointCloud> pointCloud
(Optional) Dense point cloud for this keyframe in primary frame coordinates.
-
Vector3d angularVelocity
Angular velocity vector in SI units (rad/s)
-
int64_t id
-
struct Map
Public Members
-
std::map<int64_t, std::shared_ptr<const KeyFrame>> keyFrames
ID to KeyFrame map. The shared_ptr objects are always non-empty. May be changed to a similar associative container in the future, do not rely on this being std::map.
-
std::map<int64_t, spectacularAI::Vector3d> mapPoints
List of sparse 3D map points (a.k.a. landmarks). These are observed from one or more KeyFrames, where the corresponding 2D pixel coordinates are stored in the sparseFeatures fields.
-
std::map<int64_t, std::shared_ptr<const KeyFrame>> keyFrames
-
struct MapperOutput
Public Members
-
std::shared_ptr<const Map> map
Up to date map. Always non-empty
-
std::vector<int64_t> updatedKeyFrames
List of keyframes that were modified or deleted. Ordered from oldest to newest
-
std::vector<int64_t> updatedMapPoints
List of sparse map points that were modified, added or deleted.
-
std::shared_ptr<Mesh> mesh
(Optional) dense reconstruction of the map.
-
bool finalMap
True for the last update before program exit
-
std::shared_ptr<const Map> map
-
struct Mesh
A generic 3D mesh with a few optional properties (e.g., normals, colors, textures) Flexible enough to support both vertex-specific and face specific normals / colors.
Public Types
-
using IndexFace = std::array<std::uint32_t, 3>
Public Functions
-
virtual bool empty() const = 0
Returns true if the mesh has 0 vertices (and triangles).
-
virtual bool hasNormals() const = 0
Returns true if the mesh has optional normal data.
-
virtual std::size_t vertexCount() const = 0
Returns the number of vertices in the mesh.
-
virtual std::size_t normalCount() const = 0
Returns the number of normals in the mesh.
-
virtual std::size_t faceCount() const = 0
Returns the number of triangles in the mesh.
-
virtual Triangle getTriangle(std::size_t faceIndex) const = 0
Helper function to get a single triangle, yields an error if index >= size().
-
virtual const Vector3f *getPositionData() = 0
Efficient way to get all vertex positions, returns nullptr if the mesh is empty.
-
virtual const Vector3f *getNormalData() = 0
Efficient way to get all normals, returns nullptr if the mesh is empty or hasNormals() is false.
-
virtual const IndexFace *getFaceVertices() = 0
Efficient way to get all face vertice indices, returns nullptr if the mesh is empty.
-
virtual const IndexFace *getFaceNormals() = 0
Efficient way to get all face normal indices, returns nullptr if the mesh is empty or hasNormals() is false.
-
virtual void serializeToObj(const std::string &filename) const = 0
Save mesh as .obj file to a path specified by filename.
- Parameters:
filename – For instance, path/to/output/mesh.obj.
-
inline virtual ~Mesh()
-
struct Triangle
-
using IndexFace = std::array<std::uint32_t, 3>
-
struct PointCloud
Container for point clouds, where the points may have optional properties such as colors and normals.
Public Functions
-
virtual std::size_t size() const = 0
Returns the number of points in the point cloud.
-
virtual bool empty() const = 0
Returns true if the point cloud has 0 points.
-
virtual bool hasNormals() const = 0
Returns true if the point cloud has optional normal data.
-
virtual bool hasColors() const = 0
Returns true if the the point cloud has optional color data.
-
virtual Vector3f getPosition(std::size_t index) const = 0
Helper function to get a single point position vector, yields an error if index >= size().
-
virtual Vector3f getNormal(std::size_t index) const = 0
Helper function to get a single point normal vector, yields an error if hasNormals() is false or index >= size().
-
virtual std::array<std::uint8_t, 3> getRGB24(std::size_t index) const = 0
Helper function to get a single point color array, yields an error if hasColors() is false or index >= size().
-
virtual const Vector3f *getPositionData() = 0
Efficient way to get all point positions, returns nullptr if the point cloud is empty.
-
virtual const Vector3f *getNormalData() = 0
Efficient way to get all point normals, returns nullptr if the point cloud is empty or hasNormals() is false.
-
virtual const std::uint8_t *getRGB24Data() = 0
Efficient way to get all point colors, returns nullptr if the point cloud is empty or hasColors() is false.
-
inline virtual ~PointCloud()
-
virtual std::size_t size() const = 0
-
struct VisualMarker
A visual marker observation in a frame. Only April Tags are supported currently. To enable April Tag detection in the SDK, see https://github.com/SpectacularAI/docs/blob/main/pdf/april_tag_instructions.pdf
Public Members
-
int id
Visual marker ID
-
float size
Visual marker size in meters (note: 0 if not available).
-
PixelCoordinates center
Center of the visual marker in image pixel coordinates
-
std::array<PixelCoordinates, 4> corners
Corners of the visual marker in image pixel coordinates. In visual marker coordinate frame: index 0=bottom-left, 1=bottom-right, 2=top-right, 3=top-left
-
bool hasPose
Flag that indicates if marker has pose information. Currently markers with unknown size don’t have pose estimate.
-
int id
-
using MapperOutputPtr = std::shared_ptr<const MapperOutput>
-
namespace mapping