You’re reading an older version of the Slamcore SDK documenation. The latest one is 23.01.

Namespace slamcore

namespace slamcore

Main namespace for the SLAMcore public API

Internal error_code infrastructure.

static inline std::error_code make_error_code(errc e)
static inline std::error_condition make_error_condition(errc e)

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::TaskType

template<class Archive>
static inline void load_minimal(const Archive&, TaskType &obj, const std::string &value)
template<class Archive>
static inline std::string save_minimal(const Archive&, const TaskType &obj)
static inline std::ostream &operator<<(std::ostream &os, const TaskType obj)

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::MapChannelType

template<class Archive>
static 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::Stream

template<class Archive>
static inline void load_minimal(const Archive&, Stream &obj, const std::string &value)
template<class Archive>
static inline std::string save_minimal(const Archive&, const Stream &obj)
static inline std::ostream &operator<<(std::ostream &os, const Stream &obj)

Helper functions for slamcore::Property

template<class Archive>
static inline void load_minimal(const Archive&, Property &obj, const std::string &value)
template<class Archive>
static inline std::string save_minimal(const Archive&, const Property &obj)
static inline std::ostream &operator<<(std::ostream &os, const Property &obj)

Get information about the client library

std::string getVersion()

Version

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::SubsystemType

template<class Archive>
static inline void load_minimal(const Archive&, SubsystemType &obj, const std::string &value)
template<class Archive>
static inline std::string save_minimal(const Archive&, const SubsystemType &obj)
static inline std::ostream &operator<<(std::ostream &os, const SubsystemType 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)

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\) BytesPerPixel

template<ImageFormat fmt>
static inline std::size_t ImageFormatToBytesPerPixel()
static inline std::size_t ImageFormatToBytesPerPixel(const ImageFormat fmt)

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)

Typedefs

using host_clock = std::chrono::system_clock

Declaring a host clock allows us to replace it with steady_clock if necessary.

Todo:

do we need a strong type rather than alias?

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 imu_duration = imu_clock::duration
using gps_duration = gps_clock::duration
using odometry_duration = odometry_clock::duration
using lidar_duration = lidar_clock::duration
using host_duration = odometry_clock::duration
using LogCallbackT = std::function<void(const LogMessageInterface&)>

Log callback signature.

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 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
enum class LogSeverity : EnumBaseT

SLAMcore log severity levels

Values:

enumerator Info
enumerator Warning
enumerator Error
enumerator Fatal
enumerator Count
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 Count
enum class TaskType : EnumBaseT

Tasks to run.

Values:

enumerator SaveSession
enumerator Count
enum class MapChannelType : EnumBaseT

Map channel types.

Values:

enumerator OccupancyProbability
enumerator Height
enumerator HeightVariance
enumerator Count
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 Count
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 FeatureKinematicsEnabled

bool, read-only, Whether we are running with kinematics enabled

enumerator SaveTrajectories

bool, Whether trajectories are saved

enumerator Count
enum class DataSource : EnumBaseT

Input data source.

Values:

enumerator Dataset
enumerator RealSense
enumerator Count
enum class SubsystemType : EnumBaseT

Subsystem types. For every one of these enum cases there is a corresponding <enum-name>Interface class.

Values:

enumerator CameraSensorsInfo
enumerator MobileRobot
enumerator HeightMapping
enumerator Trajectory
enumerator Count
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
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
enum class MetaDataID : EnumBaseT

Various supported MetaData variables.

Values:

enumerator TrackingStatus
enumerator NumFeatures
enumerator TrackedFeatures
enumerator DistanceTravelled
enumerator ProcessedFrameRate
enumerator TotalDroppedFrames
enumerator Count
enum class TrackingStatus

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 RELOCALISED

System has just relocalised.

enumerator LOOP_CLOSURE

A loop closure event has been triggered.

enumerator Count
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

Functions

bool pointWithinMap(const Map2DInterface &map, const VectorInterface &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 VectorInterface &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 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.

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.

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.

void slamcoreInit(LogSeverity severity = LogSeverity::Count, LogCallbackT callback = nullptr)

Create SLAMSystemPollingInterface 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.

static inline bool strcasecmp(const std::string &str1, const std::string &str2)

Static insensitive comparison of two strings.

static inline std::ostream &operator<<(std::ostream &os, const SensorIDT obj)
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)
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 Version &version)
void setLogCallback(LogSeverity severity, LogCallbackT callback)
const char * __attribute__ ((__used__)) SLAMCORE_SDK_VERSION_GIT

Variables

static bool s_init = false
struct camera_clock
#include <clocks.hpp>
class CameraSensorsInfoInterface : public SubsystemInterface
#include <subsystems.hpp>

Subsystem to access factory camera calibration.

struct CellCoordinates
#include <helpers.hpp>
template<class T>
class ConstImageView
#include <const_image_view.hpp>

Convenience constant pixel accessor wrapper for ImageInterface.

class DummyReferenceFrame : public ReferenceFrameInterface
class EncoderInterface : public ObjectInterface, public virtual MeasurementPointInterface<odometry_clock>
#include <objects.hpp>

Representing a single encoder measurement.

class EncoderListInterface : public ObjectInterface
#include <objects.hpp>

Representing a list of Encoder measurements.

class ErrorCodeInterface : public ObjectInterface
#include <objects.hpp>

Interface to transfer error codes.

class FrameSyncInterface : public ObjectInterface
#include <objects.hpp>

Frame sync token object. Received at the beginning of new frame.

struct gps_clock
#include <clocks.hpp>
class HeightMappingSubsystemInterface : public SubsystemInterface
#include <subsystems.hpp>

Subsystem for accessing height maps.

template<ImageFormat fmt>
struct ImageFormatTraits
#include <types.hpp>

Traits specific to the corresponding slamcore::ImageFormat they are templated for Supports storing information for the following properties:

  • Channels - numbers of associated channels

  • ChannelType - e.g., float / double, …

template<> Mono_16 >
#include <types.hpp>
template<> Mono_32 >
#include <types.hpp>
template<> Mono_64 >
#include <types.hpp>
template<> Mono_8 >
#include <types.hpp>
template<> Mono_F >
#include <types.hpp>
template<> RGB_8 >
#include <types.hpp>
template<> RGB_F >
#include <types.hpp>
template<> RGBA_8 >
#include <types.hpp>
template<> RGBA_F >
#include <types.hpp>
class ImageInterface : public ObjectInterface, public virtual MeasurementPointInterface<camera_clock>
#include <objects.hpp>

Representing a single video frame.

struct imu_clock
#include <clocks.hpp>
class IMUListInterface : public ObjectInterface
#include <objects.hpp>

Representing a list of IMU sensor measurements.

class IMUSensorDataInterface : public ObjectInterface, public virtual MeasurementPointInterface<imu_clock>
#include <objects.hpp>

Representing a single accelerometer/gyroscope/magnetometer measurement.

class IMUTripletInterface : public ObjectInterface
#include <objects.hpp>

Representing an IMU measurement triplet.

class IMUTripletListInterface : public ObjectInterface
#include <objects.hpp>

Representing a list of IMU triplet measurements.

class LandmarkInterface : public ObjectInterface
#include <objects.hpp>

Representing a single landmark.

struct lidar_clock
#include <clocks.hpp>
class LogMessageInterface
#include <logging.hpp>

Interface to a log message

class Map2DInterface : public ObjectInterface, public virtual MeasurementPointInterface<camera_clock>
#include <objects.hpp>

Interface to a 2D map.

class MapChannel2DInterface : public ObjectInterface
#include <objects.hpp>

Interface to a 2D map channel.

class Matrix : public MatrixInterface
#include <objects.hpp>

Simple matrix to adapt std::vector to MatrixInterface.

class MatrixInterface : public ObjectInterface
#include <objects.hpp>

Representing the matrix object.

Subclassed by Matrix

template<typename ClockT>
class MeasurementPointInterface
#include <objects.hpp>

Common interface for measurement data (e.g. images or IMU samples).

Subclassed by PoseInterface< ClockT >, VelocityInterface< ClockT >

class MetaDataInterface : public ObjectInterface
#include <objects.hpp>

Representing metadata.

class MobileRobotSubsystemInterface : public SubsystemInterface
#include <subsystems.hpp>

Subsystem for feeding mobile robots wheel odometry.

class MultiFrameInterface : public ObjectInterface
#include <objects.hpp>

Representing a set of video frames.

struct MultiSessionID
#include <types.hpp>

ID for objects that can come from different sessions.

class ObjectInterface
#include <objects.hpp>

Common interface for all the objects - enables runtime polymorphism.

Subclassed by PoseInterface< odometry_clock >, EncoderInterface, EncoderListInterface, ErrorCodeInterface, FrameSyncInterface, ImageInterface, IMUListInterface, IMUSensorDataInterface, IMUTripletInterface, IMUTripletListInterface, LandmarkInterface, Map2DInterface, MapChannel2DInterface, MatrixInterface, MetaDataInterface, MultiFrameInterface, PointCloudInterface, PoseInterface< ClockT >, PoseListInterface< ClockT >, SparseMapInterface, TaskStatusInterface, TrackingStatusListInterface, VectorInterface, VelocityInterface< ClockT >

struct odometry_clock
#include <clocks.hpp>
class PointCloudInterface : public ObjectInterface, public virtual MeasurementPointInterface<camera_clock>
#include <objects.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 ObjectInterface, public virtual slamcore::MeasurementPointInterface<ClockT>
#include <objects.hpp>

Representing the 3D pose.

Note

Covariance information is not supported yet.

Subclassed by PoseWriteInterface< ClockT >

template<typename ClockT>
class PoseListInterface : public ObjectInterface
#include <objects.hpp>

Representing the trajectory (list of poses).

template<typename ClockT>
class PoseWriteInterface : public slamcore::PoseInterface<ClockT>
#include <objects.hpp>

Representing the writable matrix object.

template<typename PT>
class PropertiesInterface
#include <slam.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.

template<typename ContainerT>
class RangeIterator
#include <types.hpp>

Simple indexing iterator. Needs operator()[] in the container.

struct ReferenceFrameInterface
#include <types.hpp>

Interface representing a coordinate system frame of reference

Subclassed by DummyReferenceFrame

class slam_exception : public system_error
#include <errors.hpp>

SLAMcore exception type.

class SLAMAsyncTasksInterface
#include <slam.hpp>

Access to asynchronous tasks.

Subclassed by SLAMSystemInterface

class SLAMCoreInterface
#include <slam.hpp>

Core SLAM system functionality.

Subclassed by SLAMSystemInterface

class SLAMSubsystemAccessInterface
#include <slam.hpp>

Subsystem access interface.

Subclassed by SLAMSystemInterface

class SLAMSystemCallbackInterface : public SLAMSystemInterface
#include <slam.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->spinOnce(std::chrono::seconds(1)));

// cleanup SLAM
slam->stop();
slam->close();

// clean up the library
slamcoreDeinit();

See also

createSLAMSystem

class SLAMSystemInterface : public PropertiesInterface<Property>, public SLAMCoreInterface, public SLAMSubsystemAccessInterface, public SLAMAsyncTasksInterface
#include <slam.hpp>

Subclassed by SLAMSystemCallbackInterface

class SparseMapInterface : public ObjectInterface, public virtual MeasurementPointInterface<camera_clock>
#include <objects.hpp>

Representing the whole sparse map.

template<Stream stream>
struct StreamType
#include <slam.hpp>
template<> ActiveMap >
#include <slam.hpp>
template<> ErrorCode >
#include <slam.hpp>
template<> FrameSync >
#include <slam.hpp>
template<> IMU >
#include <slam.hpp>
template<> LocalPointCloud >
#include <slam.hpp>
template<> MetaData >
#include <slam.hpp>
template<> Pose >
#include <slam.hpp>
template<> Velocity >
#include <slam.hpp>
template<> Video >
#include <slam.hpp>
class SubsystemInterface
#include <subsystems.hpp>

Common interface for all the objects - enables runtime polymorphism.

Subclassed by CameraSensorsInfoInterface, HeightMappingSubsystemInterface, MobileRobotSubsystemInterface, TrajectorySubsystemInterface

class TaskStatusInterface : public ObjectInterface
#include <objects.hpp>

Task status object.

class TrackingStatusListInterface : public ObjectInterface
#include <objects.hpp>

Tracking Status List Interface.

class TrajectorySubsystemInterface : public SubsystemInterface
#include <subsystems.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::TrajectorySubsystemInterface>();

// Fetch most recent trajectories
subsystem->fetch();

// You can retrieve some data
const auto unoptimisedTrajectory = subsystem->getUnoptimisedTrajectory();
const auto optimisedTrajectory = subsystem->getOptimisedTrajectory();
const auto trackingStatus = subsystem->getTrackingStatus();

// Or you can write the trajectories as csv files to an output directory
subsystem->write("trajectories");

Note

There are some positioning modes where the optimised trajectory is not produced. In these cases, getOptimisedTrajectory will return nullptr.

Note

Not thread safe.

class Vector : public VectorInterface
#include <objects.hpp>

Simple vector to adapt std::vector to VectorInterface.

class VectorInterface : public ObjectInterface
#include <objects.hpp>

Representing the vector object.

Subclassed by Vector

template<typename ClockT>
class VelocityInterface : public ObjectInterface, public virtual slamcore::MeasurementPointInterface<ClockT>
#include <objects.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 <objects.hpp>

Simple class for feeding wheel odometry data.

namespace detail

SLAMcore API internal namespace

Internal error_code infrastructure.

const std::error_category &get_error_category()
namespace internal
namespace logging

Functions

void setLogCallback(LogSeverity severity, LogCallbackT callback)
void init(const char*)
void deinit()
namespace system

Functions

std::unique_ptr<SLAMSystemCallbackInterface> createSLAMSystem(const v0::SystemConfiguration&)
namespace v0
struct SystemConfiguration
#include <slam.hpp>

Configuration for the system.

The Mode member sets the positioning mode: