Namespace slamcore
-
namespace slamcore
Internal error_code infrastructure.
Helper functions for slamcore::LogSeverity
-
template<class Archive>
static inline void load_minimal(const Archive&, LogSeverity &obj, const std::string &value)
-
template<class Archive>
static inline std::string save_minimal(const Archive&, const LogSeverity &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const LogSeverity obj)
Helper functions for slamcore::ObjectType
-
template<class Archive>
static inline void load_minimal(const Archive&, ObjectType &obj, const std::string &value)
-
template<class Archive>
static inline std::string save_minimal(const Archive&, const ObjectType &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const ObjectType obj)
Helper functions for slamcore::DistortionType
-
template<class Archive>
static inline std::string save_minimal(const Archive&, const DistortionType &obj)
-
template<class Archive>
static inline void load_minimal(const Archive&, DistortionType &obj, const std::string &value)
-
static inline std::ostream &operator<<(std::ostream &os, const DistortionType &obj)
Helper functions for slamcore::GPSQuality
-
template<class Archive>
static inline void load_minimal(const Archive&, GPSQuality &obj, const std::string &value)
-
template<class Archive>
static inline std::string save_minimal(const Archive&, const GPSQuality &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const GPSQuality obj)
Helper functions for slamcore::ImageFormat
-
template<class Archive>
static inline void load_minimal(const Archive&, ImageFormat &obj, const std::string &value)
-
template<class Archive>
static inline std::string save_minimal(const Archive&, const ImageFormat &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const ImageFormat obj)
Helper conversion methods
slamcore::ImageFormat \(\leftrightarrow\) BytesPerChannel
-
template<ImageFormat fmt>
static inline std::size_t ImageFormatToBytesPerPixel()
-
static inline std::size_t ImageFormatToBytesPerPixel(const ImageFormat fmt)
-
template<ImageFormat fmt>
static inline std::size_t ImageFormatToBytesPerChannel()
-
static inline std::size_t ImageFormatToBytesPerChannel(const ImageFormat fmt)
Helper functions for slamcore::MapChannelType
-
template<typename Archive>
inline void load_minimal(const Archive&, MapChannelType &obj, const std::string &value)
-
template<class Archive>
static inline std::string save_minimal(const Archive&, const MapChannelType &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const MapChannelType obj)
Helper functions for slamcore::MetaDataID
-
template<class Archive>
static inline void load_minimal(const Archive&, MetaDataID &obj, const std::string &value)
-
template<class Archive>
static inline std::string save_minimal(const Archive&, const MetaDataID &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const MetaDataID obj)
Helper functions for slamcore::TaskType
Helper functions for slamcore::TaskStatusInterface::
-
template<class Archive>
static inline void load_minimal(const Archive&, TaskStatusInterface::TaskState &obj, const std::string &value)
-
template<class Archive>
static inline std::string save_minimal(const Archive&, const TaskStatusInterface::TaskState &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const TaskStatusInterface::TaskState &obj)
Helper functions for slamcore::Property
Helper functions for slamcore::Stream
Get information about the client library
-
std::string getBuildVersion()
Build version
-
std::string getBuildType()
Build type
Helper functions for slamcore::DataSource
-
template<class Archive>
static inline void load_minimal(const Archive&, DataSource &obj, const std::string &value)
-
template<class Archive>
static inline std::string save_minimal(const Archive&, const DataSource &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const DataSource &obj)
Helper functions for slamcore::SensorType
-
template<class Archive>
static inline void load_minimal(const Archive&, SensorType &obj, const std::string &value)
-
template<class Archive>
static inline std::string save_minimal(const Archive&, const SensorType &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const SensorType obj)
Typedefs
-
using LogCallbackT = std::function<void(const LogMessageInterface&)>
Log callback signature.
-
template<template<typename...> class base, typename derived>
using is_base_of_template = typename detail::is_base_of_template_impl<base, derived>::type
-
template<typename Base, typename Derived>
using enable_if_is_base_of = std::enable_if<std::is_base_of<Base, Derived>::value>
-
using ScalarT = double
Default scalar type.
-
using EnumBaseT = uint16_t
Enum underlying integer type.
-
using IDT = uint64_t
Generic ID type.
-
using SessionIDT = uint64_t
Session ID type.
-
using camera_timestamp = camera_clock::time_point
-
using imu_timestamp = imu_clock::time_point
-
using gps_timestamp = gps_clock::time_point
-
using odometry_timestamp = odometry_clock::time_point
-
using lidar_timestamp = lidar_clock::time_point
-
using host_timestamp = host_clock::time_point
-
using camera_duration = camera_clock::duration
-
using odometry_duration = odometry_clock::duration
-
using lidar_duration = lidar_clock::duration
-
using host_duration = odometry_clock::duration
-
using MultiSessionID = GenericMultiSessionId<detail::MultiSessionIdT::Base>
Generic ID
-
using FrameId = GenericMultiSessionId<detail::MultiSessionIdT::Frame>
ID for a frame
-
using KeyFrameId = GenericMultiSessionId<detail::MultiSessionIdT::KeyFrame>
ID for a keyframe
-
using LandmarkId = GenericMultiSessionId<detail::MultiSessionIdT::Landmark>
Id for a landmark
-
using SensorIndexT = uint16_t
Sensor Index type.
-
using SensorIDT = std::pair<SensorType, SensorIndexT>
Sensor ID type.
SensorType and Sensor Index.
Enums
-
enum class errc
Slamcore specific error codes. For typical system ones look for std::errc enum.
Values:
-
enumerator hardware_problem
-
enumerator device_not_open
-
enumerator device_already_open
-
enumerator device_not_running
-
enumerator device_already_running
-
enumerator not_initialized_yet
-
enumerator initialization_failure
-
enumerator input_data_problem
-
enumerator compression_format_not_supported
-
enumerator stream_not_supported
-
enumerator property_not_supported
-
enumerator property_is_read_only
-
enumerator wrong_type_for_property
-
enumerator unhandled_exception
-
enumerator no_odometry_listener
-
enumerator end_of_dataset
-
enumerator end_of_data
-
enumerator invalid_subsystem
-
enumerator invalid_configuration
-
enumerator hardware_problem
-
enum class LogSeverity : EnumBaseT
Slamcore log severity levels
Values:
-
enumerator Info
-
enumerator Warning
-
enumerator Error
-
enumerator Fatal
-
enumerator Count
-
enumerator Info
-
enum class ObjectType : EnumBaseT
Object types. For every one of these enum cases there is a corresponding <enum-name>Interface class.
Values:
-
enumerator ErrorCode
-
enumerator Vector
-
enumerator Matrix
-
enumerator PoseCam
-
enumerator PoseIMU
-
enumerator PoseOdom
-
enumerator PoseListCam
-
enumerator PoseListIMU
-
enumerator PoseListOdom
-
enumerator VelocityCam
-
enumerator VelocityIMU
-
enumerator VelocityOdom
-
enumerator IMUSensorData
-
enumerator IMUList
-
enumerator IMUTriplet
-
enumerator IMUTripletList
-
enumerator Image
-
enumerator MultiFrame
-
enumerator Encoder
-
enumerator EncoderList
-
enumerator Landmark
-
enumerator SparseMap
-
enumerator FrameSync
-
enumerator MetaData
-
enumerator TaskStatus
-
enumerator MapChannel2D
-
enumerator Map2D
-
enumerator PointCloud
-
enumerator TrackingStatusList
-
enumerator StaticPose
-
enumerator Anchor
-
enumerator LIDARScan
-
enumerator GPSLocation
-
enumerator Frame
-
enumerator SLAMEventList
-
enumerator SLAMStatus
-
enumerator PanopticBoundingBox3DList
-
enumerator PanopticSegmentationResult
-
enumerator Biases
-
enumerator Count
-
enumerator ErrorCode
-
enum class DistortionType : uint16_t
Currently supported camera distortion types
Equidistant: Equidistant model with x4 parameters [k2, k3, k4, k5] This distortion type is equivalent to the Kannala-Brandt type up to ninth-order polynomial with k1 = 1. For more information please check the following reference: J. Kannala and S. S. Brandt, “A generic camera model and calibration method for conventional, wide-angle, and fish-eye lenses,” in IEEE Transactions on Pattern Analysis and Machine Intelligence, vol. 28, no. 8, pp. 1335-1340, Aug. 2006
RadialTangential: Radial tangential model with x4 parameters [k1, k2, p1, p2]. (k1, k2) are the radial distortion parameters, while (p1, p2) are the tangential distortion parameters This distortion type is also known as the Plumb Bob model or Brown-Conrady model. For more information please check the following reference: D. C. Brown. “Lens Distortion for Close-Range Photogrammetry”, Photometric Engineering, pages 855-866, Vol. 37, No. 8, 1971
NoDistortion: Zero distortion, ideal camera lens
RadialTangential8: Radial tangential model with x8 parameters [k1, k2, k3, k4, k5, k6, p1, p2]. (k1..k6) are the radial distortion parameters, while (p1, p2) are the tangential distortion parameters. Similar to the RadialTangential model but with a higher order polynomial for approximating the radial distortion
RadialSpline3: Radial model with 6 parameters defining a B-spline with 4 equidistant knots at theta = [0 pi/6 pi/3 pi/2]
Note
The order of the distortion parameters in the configuration files is (k1, k2, p1, p2, k3, k4, k5, k6)
Values:
-
enumerator Equidistant
-
enumerator RadialTangential
-
enumerator NoDistortion
-
enumerator RadialTangential8
-
enumerator RadialSpline3
-
enumerator Count
-
enum class GPSQuality : EnumBaseT
GPS Quality Indicator.
Values:
-
enumerator NoFix
-
enumerator Uncorrected
-
enumerator DifferentiallyCorrected
-
enumerator Invalid
-
enumerator RTKFixCoordinate
-
enumerator RTKFloat
-
enumerator Count
-
enumerator NoFix
-
enum class ImageFormat : EnumBaseT
Various internal image formats.
Values:
-
enumerator Custom
Undefined.
-
enumerator Mono_8
8 bit per pixel
-
enumerator Mono_16
16 bit per pixel
-
enumerator Mono_F
32 bit float per pixel
-
enumerator RGB_8
8 bit per component, RGB
-
enumerator RGBA_8
8 bit per component, RGBA
-
enumerator RGB_F
32 bit float per component, RGB
-
enumerator RGBA_F
32 bit float per component, RGBA
-
enumerator JPEG
Binary JPEG data.
-
enumerator Mono_32
32 bit per pixel
-
enumerator Mono_64
64 bit per pixel
-
enumerator Count
-
enumerator Custom
-
enum class MapChannelType : EnumBaseT
Map channel types.
Values:
-
enumerator OccupancyProbability
-
enumerator Height
-
enumerator HeightVariance
-
enumerator Coverage
-
enumerator Count
-
enumerator OccupancyProbability
-
enum class MetaDataID : EnumBaseT
Various supported MetaData variables.
Values:
-
enumerator NumFeatures
-
enumerator TrackedFeatures
-
enumerator DistanceTravelled
-
enumerator ProcessedFrameRate
-
enumerator TotalDroppedFrames
-
enumerator Count
-
enumerator NumFeatures
-
enum class TaskType : EnumBaseT
Tasks to run.
Values:
-
enumerator SaveSession
-
enumerator Count
-
enumerator SaveSession
-
enum class PredefinedSemanticLabel : EnumBaseT
Values:
-
enumerator Unknown
-
enumerator Background
-
enumerator Person
-
enumerator Count
-
enumerator Unknown
-
enum class Property : EnumBaseT
Properties to query and set.
Values:
-
enumerator ModelName
std::string
, read-only, device model name
-
enumerator SerialNumber
std::string
, read-only, serial number of the device
-
enumerator SensorInfo
std::string
, read-only, misc sensor info
-
enumerator FirmwareVersion
std::string
, read-only, firmware version
-
enumerator FirmwareBuildTime
std::string
, read-only, firmware build time
-
enumerator FirmwareBuildVersion
std::string
, read-only, contains SLAM build info
-
enumerator FirmwareBuildType
std::string
, read-only, contains SLAM build type info
-
enumerator PositioningMode
PositioningMode
enum, read-only, position mode of the SLAM system
-
enumerator ConfigPresetName
std::string
, read-only, name of config preset
-
enumerator FeatureMap2DEnabled
bool
, read-only, Whether 2D mapping features are enabled
-
enumerator FeatureCoverage2DEnabled
bool
, read-only, Whether 2D mapping features are enabled
-
enumerator FeatureKinematicsEnabled
bool
, read-only, Whether we are running with kinematics enabled
-
enumerator LowLatencyMode
bool
, toggle true to enable low latency mode of operation
-
enumerator SessionID
int64_t
, Current SessionID of the current slam run
-
enumerator HasLoadedSession
bool
, read-only, Whether a recorded session was loaded at start
-
enumerator Count
-
enumerator ModelName
-
enum class Stream : EnumBaseT
Supported data streams
Values:
-
enumerator Pose
Used for PoseInterface.
-
enumerator Video
Used for MultiFrameInterface.
-
enumerator IMU
Used for IMUListInterface.
-
enumerator ActiveMap
Used for SparseMapInterface.
-
enumerator Velocity
Used for VelocityInterface<camera_clock>
-
enumerator MetaData
Used for MetaDataInterface.
-
enumerator FrameSync
Used for FrameSyncInterface.
-
enumerator ErrorCode
used for ErrorCodeInterface
-
enumerator LocalPointCloud
used for PointCloudInterface
-
enumerator SmoothPose
used for PoseInterface
-
enumerator SLAMStatus
used for SLAMStatusInterface
-
enumerator PanopticSegmentationResult
-
enumerator PanopticBoundingBox3D
-
enumerator Biases
-
enumerator Count
-
enumerator Pose
-
enum class DataSource : EnumBaseT
Input data source.
Values:
-
enumerator Dataset
-
enumerator RealSense
-
enumerator External
Use the external sources registered with the
registerExternalXXX
methods below.
-
enumerator OakD
-
enumerator AutoDetect
Try and automatically detect camera sensor.
-
enumerator Android
-
enumerator Count
-
enumerator Dataset
-
enum class PositioningMode : EnumBaseT
Type of positioning mode.
Values:
-
enumerator ODOMETRY_ONLY
Visual-only or visual inertial odometry.
-
enumerator SLAM
SLAM mode enables relocalisation and loop-closure.
-
enumerator MULTISESSION_LOCALISATION
Bootstrap from pure_relocalisation and then VIO and reuse of old landmarks with the Visibility Classifier.
-
enumerator Count
-
enumerator ODOMETRY_ONLY
-
enum class ReferenceFrameCategory : EnumBaseT
Enumeration of predefined reference frames
Values:
-
enumerator Unknown
-
enumerator World
-
enumerator Camera
-
enumerator IMU
-
enumerator Body
-
enumerator Odometry
-
enumerator LIDAR
-
enumerator GPS
-
enumerator Anchor
-
enumerator Unknown
-
enum class SensorType : EnumBaseT
Possible Sensor Types.
Values:
-
enumerator SLAM
Outputs from SLAM.
-
enumerator Visible
Standard Visible (Grey/RGB) Sensor (Camera).
-
enumerator Depth
Standard Depth Sensor (Camera).
-
enumerator Infrared
Standard Infrared Sensor (Camera).
-
enumerator Confidence
For time-of-flight Sensors (Camera).
-
enumerator Phase
For time-of-flight Sensors (Camera).
-
enumerator Accelerometer
Inertial Accelerometer Sensor (IMU).
-
enumerator Gyroscope
Inertial Gyroscope Sensor (IMU).
-
enumerator Magnetometer
Inertial Magnetometer Sensor (IMU).
-
enumerator GPS
GPS Sensor.
-
enumerator Odometry
Odometry Sensor.
-
enumerator Encoder
Encoder, for wheel ticks.
-
enumerator Pose
Pose “Sensor”, e.g. ground truth.
-
enumerator Bumper
Bumper
-
enumerator Proximity
Proximity sensor.
-
enumerator LIDAR
LIDAR (2D).
-
enumerator Count
-
enumerator SLAM
-
enum class SLAMEvent : EnumBaseT
Enumerate for the SLAM transition events.
Values:
-
enumerator Relocalisation
-
enumerator LoopClosure
-
enumerator ImuInitialization
-
enumerator IntersessionLocalisation
-
enumerator Count
-
enumerator Relocalisation
-
enum class TrackingStatus : EnumBaseT
Enumerate for the Tracking status.
Values:
-
enumerator NOT_INITIALISED
System is not initialised (waiting for initialisation)
-
enumerator OK
System is initialised and we are tracking.
-
enumerator LOST
System is lost and we are in relocalisation mode.
-
enumerator Count
-
enumerator NOT_INITIALISED
Functions
-
template<typename ScalarT, int LhsRows, int LhsCols, int RhsRows, int RhsCols>
bool operator==(const Matrix<ScalarT, LhsRows, LhsCols> &lhs, const Matrix<ScalarT, RhsRows, RhsCols> &rhs)
-
template<typename ScalarT, int LhsRows, int LhsCols, int RhsRows, int RhsCols>
bool operator!=(const Matrix<ScalarT, LhsRows, LhsCols> &lhs, const Matrix<ScalarT, RhsRows, RhsCols> &rhs)
-
inline bool operator==(const ConstTaggedObject &a, std::nullptr_t) noexcept
-
inline bool operator==(std::nullptr_t, const ConstTaggedObject &a) noexcept
-
inline bool operator!=(const ConstTaggedObject &a, std::nullptr_t) noexcept
-
inline bool operator!=(std::nullptr_t, const ConstTaggedObject &a) noexcept
-
inline std::string toString(const PredefinedSemanticLabel label)
-
uint8_t mapGetOccupancyProbability(const Map2DInterface &map, const CellCoordinates &cell)
Get occupancy probability from the map for a given cell index.
- Parameters
map – Map to use.
cell – Cell coordinates.
- Returns
Occupancy probability value.
-
float mapGetHeight(const Map2DInterface &map, const CellCoordinates &cell)
Get height from the map for a given cell index.
- Parameters
map – Map to use.
cell – Cell coordinates.
- Returns
Height.
-
float mapGetHeightVariance(const Map2DInterface &map, const CellCoordinates &cell)
Get height variance from the map for a given cell index.
- Parameters
map – Map to use.
cell – Cell coordinates.
- Returns
Height variance.
-
bool pointWithinMap(const Map2DInterface &map, const DynamicVector &pt)
Calculate if a point is within the map bounds.
- Parameters
map – Map to use.
pt – Point in the world coordinate frame.
- Returns
True if point is within the map, false otherwise.
-
CellCoordinates mapPointToCell(const Map2DInterface &map, const DynamicVector &pt)
Calculate the cell index for a point in the world coordinate frame.
- Parameters
map – Map to use.
pt – Point in the world coordinate frame.
- Returns
Cell coordinates.
-
Vector<double, 3> mapCellToPoint(const Map2DInterface &map, const CellCoordinates &cell)
Calculate the point (on the map plane) for a given cell index. Mid-point of a cell.
- Parameters
map – Map to use.
cell – Cell coordinates.
- Returns
Point on the map plane in world coordinate frame.
-
void writeTrajectory(const slamcore::PoseListInterface<slamcore::camera_clock> &trajectory, const slamcore::TrackingStatusListInterface &trackingStatus, const std::string &filepath)
Write given trajectory to a file at filepath.
- Parameters
trajectory – Poses to write.
trackingStatus – Tracking status to write.
filepath – Where to write the trajectory.
-
inline KeyFrameId toKeyFrameId(FrameId id)
Explicit promotion of a FrameId to a KeyFrameId
- Parameters
id – Frame ID to be promoted
- Returns
KeyFrameId Promoted frame ID
-
inline KeyFrameId toKeyFrameId(MultiSessionID id)
Explicit promotion of a MultiSessionID to a KeyFrameId
- Parameters
id – Generic ID to be promoted
- Returns
KeyFrameId Promoted frame ID
-
template<class Archive>
std::string save_minimal(const Archive&, const PositioningMode &obj)
-
template<class Archive>
void load_minimal(const Archive&, PositioningMode &obj, const std::string &value)
-
static inline std::ostream &operator<<(std::ostream &os, const PositioningMode &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const ReferenceFrame &obj)
-
template<class Archive>
void load_minimal(const Archive&, ReferenceFrameCategory &obj, const std::string &value)
-
template<class Archive>
std::string save_minimal(const Archive&, const ReferenceFrameCategory &obj)
-
static inline std::ostream &operator<<(std::ostream &os, const ReferenceFrameCategory obj)
-
inline bool strcasecmp(const std::string &str1, const std::string &str2)
Case insensitive comparison of two strings.
-
template<class Archive>
std::string save_minimal(const Archive&, const TrackingStatus &obj)
-
template<class Archive>
void load_minimal(const Archive&, TrackingStatus &obj, const std::string &value)
-
static inline std::ostream &operator<<(std::ostream &os, const TrackingStatus &obj)
Registers a customer-provided external source of sensor data.
Must be enabled in
SystemConfiguration
by setting theSource
field toDataSource::External
. See slam.hpp.Note
Will throw a slamcore::slam_exception on failure.
Note
Not thread safe.
- Parameters
name – External sensor source name.
src – External sensor source instance.
-
void loadExternalSensor(const char *name, const char *pluginFile, const char *pluginConfig = nullptr)
Loads a customer-provided external sensor plugin.
Must be enabled in
SystemConfiguration
by setting theSource
field toDataSource::External
. See slam.hpp.Note
Will throw a slamcore::slam_exception on failure.
Note
Not thread safe.
- Parameters
name – External sensor source name.
pluginFile – Path to the plugin dynamic library.
pluginConfig – Optional path to a plugin-specific config file.
-
void slamcoreInit(LogSeverity severity = LogSeverity::Count, const LogCallbackT &callback = nullptr)
Create
SLAMSystemCallbackInterface
instance. Initialise Slamcore API.A callback can optionally be specified to be notified of log messages with severity greater or equal than the specified value.
The log callback implementation must guarantee its own thread-safety, i.e. it might be invoked, concurrently, from arbitrary threads.
The lifetime of the callback must be guaranteed until the call to slamcore::slamcoreDeinit().
Note
Not thread safe.
-
void slamcoreDeinit()
Deinitialise Slamcore API.
Note
Not thread safe.
-
std::unique_ptr<SLAMSystemCallbackInterface> createSLAMSystem(const v0::SystemConfiguration &cfg, const Version &v = slamcore::getCurrentSDKVersion())
Create slamcore::SLAMSystemInterface instance.
Note
Not thread safe.
- Parameters
cfg – The configuration for the system.
v – The SDK version, used internally.
Variables
-
constexpr int Dynamic = -1
-
class BadTaggedObjectAccess : public exception
- #include <tagged_object.hpp>
-
class BasePoseInterface
- #include <base_pose.hpp>
Subclassed by PoseInterface< odometry_clock >, PoseInterface< ClockT >, StaticPoseInterface
-
class BiasesInterface : public MeasurementPoint<camera_clock>
- #include <biases.hpp>
Representing the IMU biases.
-
struct BoundingBox3D
- #include <bounding_box_3d.hpp>
A bounding box
-
struct camera_clock
- #include <clocks.hpp>
-
struct CellCoordinates
- #include <map2d_interface.hpp>
-
template<class T>
class ConstImageView - #include <const_image_view.hpp>
Convenience constant pixel accessor wrapper for ImageInterface.
-
struct ConstTaggedObject
- #include <tagged_object.hpp>
Subclassed by TaggedObject
-
class EncoderInterface : public MeasurementPoint<odometry_clock>
- #include <encoder.hpp>
Representing a single encoder measurement.
-
class EncoderListInterface
- #include <encoder_list.hpp>
Representing a list of Encoder measurements.
-
class ErrorCodeInterface
- #include <error_code.hpp>
Interface to transfer error codes.
-
class FixedMeasurementPoint
- #include <fixed_measurement_point.hpp>
Common interface for non-temporal metadata
Subclassed by MeasurementPoint< camera_clock >, MeasurementPoint< gps_clock >, MeasurementPoint< imu_clock >, MeasurementPoint< lidar_clock >, MeasurementPoint< odometry_clock >, MeasurementPoint< ClockT >, StaticPoseInterface
-
class FrameInterface
- #include <frame.hpp>
Interface for a Frame, a composition of an image and a region of interest
-
class FrameSyncInterface
- #include <frame_sync.hpp>
Frame sync token object. Received at the beginning of new frame.
-
template<detail::MultiSessionIdT SessionType>
struct GenericMultiSessionId - #include <multi_session_id.hpp>
ID for objects that can come from different sessions.
- template<> Base >
- #include <multi_session_id.hpp>
- template<> KeyFrame > : public GenericMultiSessionId< detail::MultiSessionIdT::Frame >
- #include <multi_session_id.hpp>
-
struct gps_clock
- #include <clocks.hpp>
-
class GPSLocationInterface : public MeasurementPoint<gps_clock>
- #include <gps_location.hpp>
GPS location sample.
-
class HeightMappingSubsystemInterface : public virtual Map2DAccessInterface, public SubsystemInterface
- #include <height_mapping.hpp>
Subsystem for accessing height maps.
-
struct host_clock
- #include <clocks.hpp>
Defining our own host_clock lets us pretend to have nanosecond resolution everywhere.
-
template<ImageFormat fmt>
struct ImageFormatTraits - #include <image.hpp>
Traits specific to the corresponding slamcore::ImageFormat they are templated for Supports storing information for the following properties:
Channels
- numbers of associated channelsChannelType
- e.g., float / double, …
- template<> Mono_16 >
- #include <image.hpp>
- template<> Mono_32 >
- #include <image.hpp>
- template<> Mono_64 >
- #include <image.hpp>
- template<> Mono_8 >
- #include <image.hpp>
- template<> Mono_F >
- #include <image.hpp>
- template<> RGB_8 >
- #include <image.hpp>
- template<> RGB_F >
- #include <image.hpp>
- template<> RGBA_8 >
- #include <image.hpp>
- template<> RGBA_F >
- #include <image.hpp>
-
class ImageInterface : public MeasurementPoint<camera_clock>
- #include <image.hpp>
Representing a single video frame.
-
struct imu_clock
- #include <clocks.hpp>
-
class IMUListInterface
- #include <imu_list.hpp>
Representing a list of IMU sensor measurements.
-
class IMUSensorDataInterface : public MeasurementPoint<imu_clock>
- #include <imu_sensor_data.hpp>
Representing a single accelerometer/gyroscope/magnetometer measurement.
-
class IMUTripletInterface
- #include <imu_triplet.hpp>
Representing an IMU measurement triplet.
-
class IMUTripletListInterface
- #include <imu_triplet_list.hpp>
Representing a list of IMU triplet measurements.
-
class LandmarkInterface
- #include <landmark.hpp>
Representing a single landmark.
-
struct lidar_clock
- #include <clocks.hpp>
-
class LIDARScanInterface : public MeasurementPoint<lidar_clock>
- #include <lidar_scan.hpp>
Complete LIDAR scan.
-
class LogMessageInterface
- #include <logging.hpp>
Interface to a log message
-
class Map2DAccessInterface
- #include <map2d_interface.hpp>
Fetch interface to access 2D map updates
Subclassed by HeightMappingSubsystemInterface
-
class Map2DInterface : public MeasurementPoint<camera_clock>
- #include <map2d.hpp>
Interface to a 2D map.
-
class MapChannel2DInterface
- #include <map_channel2d.hpp>
Interface to a 2D map channel.
-
template<typename ScalarT = double, int RowsT = Dynamic, int ColsT = Dynamic>
class Matrix : public Dimensions<Dynamic, Dynamic> - #include <matrix.hpp>
A column Major data representation of a matrix.
- Template Parameters
ScalarT –
RowsT –
ColsT –
-
template<typename ClockT>
class MeasurementPoint : public FixedMeasurementPoint - #include <measurement_point.hpp>
Common interface for measurement data (e.g. images or IMU samples).
Subclassed by PoseInterface< ClockT >, VelocityInterface< ClockT >
-
class MetaDataInterface
- #include <meta_data.hpp>
Representing metadata.
-
class MultiFrameInterface
- #include <multi_frame.hpp>
Representing a set of video frames.
-
struct odometry_clock
- #include <clocks.hpp>
-
class OptimisedTrajectorySubsystemInterface : public SubsystemInterface
- #include <optimised_trajectory.hpp>
Subsystem for accessing trajectories.
A common way of using this subsystem would be as follows:
// Get subsystem from the SLAM system const auto subsystem = slam->getSubsystem<slamcore::OptimmisedTrajectorySubsystemInterface>(); // Fetch most recent trajectories subsystem->fetch(); // You can retrieve some data const auto optimisedTrajectory = subsystem->getTrajectory();
Note
There are some positioning modes where the optimised trajectory is not produced. In these cases,
getTrajectory
will returnnullptr
.Note
Not thread safe.
-
class PanopticBoundingBox3D : public MeasurementPoint<camera_clock>
- #include <panoptic_bounding_box_3d.hpp>
A bounding box which represents a single object
-
class PanopticBoundingBox3DList
- #include <panoptic_bounding_box_3d_list.hpp>
-
struct PanopticLabel
- #include <panoptic_class_labels.hpp>
-
class PanopticSegmentationResultInterface
- #include <panoptic_segmentation_result.hpp>
-
class PanopticSegmentationRunnerInterface
- #include <panoptic_segmentation_runner.hpp>
-
class PanopticSegmentationSubsystemInterface : public SubsystemInterface
- #include <panoptic_segmentation.hpp>
-
class PointCloudInterface : public MeasurementPoint<camera_clock>
- #include <point_cloud.hpp>
Interface to point cloud data. A point cloud is a linear list of 3D points. The reference coordinate frame of the point cloud is specified via the measurement point interface
getReferenceFrame()
.
-
template<typename ClockT>
class PoseInterface : public BasePoseInterface, public slamcore::MeasurementPoint<ClockT> - #include <pose.hpp>
Representing the 3D pose.
Note
Covariance information is not supported yet.
Subclassed by PoseWriteInterface< ClockT >
-
template<typename ClockT>
class PoseListInterface - #include <pose_list.hpp>
Representing the trajectory (list of poses).
-
template<typename ClockT>
class PoseWriteInterface : public slamcore::PoseInterface<ClockT> - #include <pose_write.hpp>
Representing the writable matrix object.
-
template<typename PT>
class PropertiesInterface - #include <properties_interface.hpp>
Helper for handling the properties.
Property-getters
Query property value.
- param pt
Property to query.
- param val
Return value.
- param idx
Optional index for array-like properties.
- return
Error code.
Property-setter methods
Set a property.
- param pt
Property to set.
- param val
Value to set.
- param idx
Optional index for array-like properties.
- return
Error code.
-
class Range1D
- #include <range.hpp>
Captures the half-open interval [min, max)
-
class Range2D
- #include <range.hpp>
Captures the half-open 2D interval [(x_min, y_min), (x_max, y_max))
-
template<typename ContainerT>
class RangeIterator - #include <range_iterator.hpp>
Simple indexing iterator. Needs operator()[] in the container.
-
class ReferenceFrame
- #include <reference_frame.hpp>
Represent a coordinate system frame of reference
-
struct SemanticLabel
- #include <panoptic_class_labels.hpp>
-
class SensorsInfoInterface : public SubsystemInterface
- #include <sensors_info.hpp>
Subsystem to access information regarding sensors
-
class SensorSourceInterface
- #include <sensor_source_interface.hpp>
Customers wishing to feed sensor data to Slamcore SLAM must implement the following lifecycle interface together with one or more of the above sensor data interfaces.
Slamcore will call into the interfaces according to this lifecycle flowchart:
+------------> open() | | | v | registerCallback(...) | | | v | +--------> start() | | | | | ... // implementer invokes data callbacks | | | | | v | +--------- stop() | | | v | registerCallback(nullptr) // deregister | | | v +------------- close()
Slamcore will invoke lifecycle methods SensorSourceInterface::open, SensorSourceInterface::close, SensorSourceInterface::start, SensorSourceInterface::stop, and <sensor interface at hand>::registerCallback from a single thread.
-
class slam_exception : public system_error
- #include <errors.hpp>
Slamcore exception type.
-
class SLAMAsyncTasksInterface
- #include <slam_async_tasks.hpp>
Access to asynchronous tasks.
Subclassed by SLAMSystemInterface
-
class SLAMCoreInterface
- #include <slam_core.hpp>
Core SLAM system functionality.
Subclassed by SLAMSystemInterface
-
class SLAMEventListInterface
- #include <slam_event_list.hpp>
SLAM Event List Interface.
-
class SLAMStatusInterface : public MeasurementPoint<camera_clock>
- #include <slam_status.hpp>
Representing the status of SLAM.
-
class SLAMSubsystemAccessInterface
- #include <slam_subsystem_access.hpp>
Subsystem access interface.
Subclassed by SLAMSystemInterface
-
class SLAMSystemCallbackInterface : public SLAMSystemInterface
- #include <slam_system_callback.hpp>
Main object for creating, executing and interacting with the SLAM procedure. Use it as a standard device (open \(\rightarrow\) start streaming \(\rightarrow\) grab data \(\rightarrow\) close).
A standard way of getting SLAM up ‘n running would be the following. To simplify the procedure, error handling is not shown, see hello_world_all_streams.cpp for a minimal working example of this:
// Initialise the library slamcoreInit() // Create a system configuration v0::SystemConfiguration cfg; // create a SLAM System slamcore::SLAMSystemCallbackInterface::Ptr slam = slamcore::createSLAMSystem(cfg); // register any callbacks slam->registerCallback<slamcore::Stream::Pose>( [](const slamcore::PoseInterface<slamcore::camera_clock>::CPtr& pose) { // do something with the pose! }); // ... slam->open(); // enable the streams you need slam->setStreamEnabled(slamcore::Stream::Pose, true); // ... slam->start(); // poll for data while(slam->spin(std::chrono::seconds(1))); // cleanup SLAM slam->stop(); slam->close(); // clean up the library slamcoreDeinit();
See also
-
class SLAMSystemInterface : public PropertiesInterface<Property>, public SLAMCoreInterface, public SLAMSubsystemAccessInterface, public SLAMAsyncTasksInterface
- #include <slam_system.hpp>
Subclassed by SLAMSystemCallbackInterface
-
class SparseMapInterface : public MeasurementPoint<camera_clock>
- #include <sparse_map.hpp>
Representing the whole sparse map.
-
class StaticPoseInterface : public BasePoseInterface, public FixedMeasurementPoint
- #include <static_pose.hpp>
Representing a static 3D pose.
Subclassed by TransformationSample
-
template<Stream stream>
struct StreamType - #include <stream_type.hpp>
- template<> ActiveMap >
- #include <stream_type.hpp>
- template<> Biases >
- #include <stream_type.hpp>
- template<> ErrorCode >
- #include <stream_type.hpp>
- template<> FrameSync >
- #include <stream_type.hpp>
- template<> IMU >
- #include <stream_type.hpp>
- template<> LocalPointCloud >
- #include <stream_type.hpp>
- template<> MetaData >
- #include <stream_type.hpp>
- template<> PanopticBoundingBox3D >
- #include <panoptic_bounding_box_3d_list.hpp>
- template<> PanopticSegmentationResult >
- #include <panoptic_segmentation_result.hpp>
- template<> Pose >
- #include <stream_type.hpp>
- template<> SLAMStatus >
- #include <stream_type.hpp>
- template<> SmoothPose >
- #include <stream_type.hpp>
- template<> Velocity >
- #include <stream_type.hpp>
- template<> Video >
- #include <stream_type.hpp>
-
class SubsystemInterface
- #include <subsystem.hpp>
Common interface for all the subsystems - enables runtime polymorphism.
Subclassed by HeightMappingSubsystemInterface, OptimisedTrajectorySubsystemInterface, PanopticSegmentationSubsystemInterface, SensorsInfoInterface
-
struct TaggedObject : public ConstTaggedObject
- #include <tagged_object.hpp>
-
class TaskStatusInterface
- #include <task_status.hpp>
Task status object.
-
class TrackingStatusListInterface
- #include <tracking_status_list.hpp>
Tracking Status List Interface.
-
class TrajectoryHelper
- #include <optimised_trajectory.hpp>
Client-side helper meant to help aggregate tracking statuses and poses into trajectories
It also helps write out trajectories to disk in a consistent and unified format
Note
The helper is not thread-safe
-
template<typename ScalarT>
struct Transform - #include <transform.hpp>
Simple object representing a SE(3) rigid transformation.
- Template Parameters
ScalarT – The scalar type to represent the transformation coefficients
-
class TransformationSample : public StaticPoseInterface
- #include <transformation_sample.hpp>
Simple class for providing transformations.
-
template<typename Type, class Enable = void>
struct TypeTraits - #include <tagged_object.hpp>
-
template<>
struct TypeTraits<PanopticBoundingBox3DList> - #include <panoptic_bounding_box_3d_list.hpp>
- template<typename T> type >
- #include <biases.hpp>
- template<typename T> type >
- #include <encoder.hpp>
- template<typename T> type >
- #include <encoder_list.hpp>
- template<typename T> type >
- #include <error_code.hpp>
- template<typename T> type >
- #include <frame.hpp>
- template<typename T> type >
- #include <frame_sync.hpp>
- template<typename T> type >
- #include <gps_location.hpp>
- template<typename T> type >
- #include <image.hpp>
- template<typename T> type >
- #include <imu_list.hpp>
- template<typename T> type >
- #include <imu_sensor_data.hpp>
- template<typename T> type >
- #include <imu_triplet.hpp>
- template<typename T> type >
- #include <imu_triplet_list.hpp>
- template<typename T> type >
- #include <landmark.hpp>
- template<typename T> type >
- #include <lidar_scan.hpp>
- template<typename T> type >
- #include <map2d.hpp>
- template<typename T> type >
- #include <map_channel2d.hpp>
- template<typename T> type >
- #include <meta_data.hpp>
- template<typename T> type >
- #include <multi_frame.hpp>
- template<typename T> type >
- #include <point_cloud.hpp>
- template<typename T> type >
- #include <slam_event_list.hpp>
- template<typename T> type >
- #include <slam_status.hpp>
- template<typename T> type >
- #include <sparse_map.hpp>
- template<typename T> type >
- #include <static_pose.hpp>
- template<typename T> type >
- #include <task_status.hpp>
- template<typename T> type >
- #include <tracking_status_list.hpp>
-
template<typename ClockT>
class VelocityInterface : public slamcore::MeasurementPoint<ClockT> - #include <velocity.hpp>
Representing the velocities.
-
class Version
- #include <version.hpp>
Manage / Get information about the version of the client library
-
class WheelOdometrySample : public PoseInterface<odometry_clock>
- #include <wheel_odometry_sample.hpp>
Simple class for feeding wheel odometry data.
-
class WheelOdometrySensorInterface
- #include <wheel_odometry.hpp>
Interface to a customer wheel odometry sensor source
Registers a callback to invoke when wheel odometry data becomes available.
Implementers can invoke the registered callbacks in any thread.
-
namespace detail
Slamcore API internal namespace
Internal error_code infrastructure.
-
const std::error_category &get_error_category()
Enums
-
enum MultiSessionIdT
Values:
-
enumerator Frame
-
enumerator KeyFrame
-
enumerator Landmark
-
enumerator Base
-
enumerator Frame
Functions
-
template<int Rows, int Cols>
static void checkSize(const int rows, const int cols)
-
template<typename Subsystem>
const SubsystemType &getSubsystemType()
-
const std::error_category &get_error_category()
-
namespace internal
-
namespace v0
-
struct SystemConfiguration
- #include <system_configuration.hpp>
Configuration for the system.
The
Mode
member sets the positioning mode:Use
PositioningMode::SLAM
to enable relocalisation and loop-closure.Use
PositioningMode::ODOMETRY_ONLY
for visual-inertial odometry only.
-
struct SystemConfiguration
-
namespace v1
-
struct SystemConfiguration
- #include <system_configuration.hpp>
Configuration for the system.
The
Mode
member sets the positioning mode:Use
PositioningMode::SLAM
to enable relocalisation and loop-closure.Use
PositioningMode::ODOMETRY_ONLY
for visual-inertial odometry only.
-
struct SystemConfiguration
-
template<class Archive>