Overview
Introduction
This page provides an overview of the Slamcore C++ API.
All the calls and types mentioned here are under the namespace slamcore
.
Note
In order to build and link against our C++ API, a compiler must support C++11 and link against the default standard library for the distribution that the package was intended for (e.g libstdc++ for Ubuntu). Any compiler that is available from the distribution’s own mirrors is supported. In theory, all recent versions of gcc and clang are supported (e.g gcc >= 7).
Initialisation
Before using the API the library has to be initialised with the
slamcore::slamcoreInit()
call. The user might optionally pass a
callback that will receive the logs from the library (at least at a desired log
level).
Once done with using the library please call
slamcore::slamcoreDeinit()
to free all the resources that might still
be acquired.
Example:
slamcore::slamcoreInit(slamcore::LogSeverity::Info,
[](const slamcore::LogMessageInterface& message)
{
const time_t time = std::chrono::system_clock::to_time_t(message.getTimestamp());
struct tm tm;
localtime_r(&time, &tm);
std::cerr << "[" << message.getSeverity() << " " << std::put_time(&tm, "%FT%T%z") << "] "
<< message.getMessage() << "\n";
});
// ... use the SDK
slamcoreDeinit();
Main SLAM interface
Every interaction with the SLAM systems happens through the
slamcore::SLAMSystemCallbackInterface
, which provides the following
methods:

Creation
To create the slamcore::SLAMSystemCallbackInterface
call the slamcore::createSLAMSystem()
factory function. It takes the
slamcore::v0::SystemConfiguration
struct as an argument. With this
struct the system configuration can be fine-tuned:
if the system is running live (real camera) or from a pre-recorded dataset,
provide a path to a JSON preset file with optional low level config overrides,
set the positioning mode,
provide the path to the session file to pre-load,
disable SLAM altogether, in that scenario the system just passes the camera data (images, IMU samples) to the user, useful for debugging.
Note
Only one instance of a slamcore::SLAMSystemCallbackInterface
is allowed. To
create another instance the previous instance needs to be deleted. See Example reset.cpp example
for more information on running SLAM systems one-by-one.
Example:
slamcore::v0::SystemConfiguration sysCfg;
std::unique_ptr<slamcore::SLAMSystemCallbackInterface> slam = slamcore::createSLAMSystem(sysCfg);
if (!slam)
{
std::cerr << "Error creating SLAM system!" << std::endl;
slamcore::slamcoreDeinit();
return -1;
}
Objects, Streams and Properties
Data returned by the SLAM system is in the form of objects of various types, all inheriting from the
slamcore::ObjectInterface
. These interfaces often are related, e.g.
slamcore::PoseInterface
- representation of a 3D pose - returns
slamcore::DynamicVector
in the getters for the translation and rotation parts.
Many objects additionally inherit from
slamcore::MeasurementPoint
which provides basic
metadata for that particular measurement sample (ID, timestamps, sensor type
etc).

Receiving a particular object type can be controlled by enabling and disabling a particular stream of data. Below are listed, for example, which data types are coming on which stream:
-
slamcore::PoseInterface
- output pose estimated by the SLAM system, -
slamcore::SLAMStatusInterface
- information about the state of SLAM, such as tracking status and SLAM events. -
slamcore::MultiFrameInterface
- image data from the camera, -
slamcore::IMUListInterface
- IMU samples from the camera, -
slamcore::SparseMapInterface
- landmarks in the current active map, -
slamcore::VelocityInterface
- output velocity estimated by the SLAM system, -
slamcore::MetaDataInterface
- additional information such as distance travelled, number of features detected, etc. -
slamcore::FrameSyncInterface
- object used for synchronisation of other objects, sent at the end of a frame, -
slamcore::ErrorCodeInterface
- sent if an error happened in the SLAM system.
Additionally, the SLAM system interface provides a number of properties that can
be queried and set via the getProperty
and setProperty
calls. These are
often variables with basic data types and related to the current running
configuration, not the SLAM/per-frame data itself.
For a list of properties see here: slamcore::Property
.
Basic operations
The main SLAM API (i.e. slamcore::SLAMSystemCallbackInterface
)
intends to mimic a typical video camera driver that the user might be familiar
with. Slamcore’s system ultimately estimates and provides much more
than just the raw sensor data that a normal video camera does, but the paradigm
still fits.
To start interacting with the SLAM system the user has to open it, with
either slamcore::SLAMCoreInterface::open()
or
slamcore::SLAMCoreInterface::openWithSession()
calls. Once
the system is open the properties can be queried, streams of interest can be enabled
and callbacks registered to handle data coming on those streams.
To start processing, call the
slamcore::SLAMCoreInterface::start()
method.
From that moment the SLAM system starts processing sensor readings, estimating
the camera pose, the map and calling the user provided callbacks with the most
recent data.
To keep receiving data call the
slamcore::SLAMSystemCallbackInterface::spin()
method which is
responsible for receiving and dispatching the incoming data to the callbacks.
The slamcore::SLAMCoreInterface::stop()
method can be called when
an slamcore::ErrorCodeInterface
object signalling the
end of a dataset is received or to stop (live camera). The
slamcore::SLAMCoreInterface::close()
method can be
called to shutdown the SLAM system if processing will not be resumed.
Example:
1// Initialise the library
2slamcoreInit()
3
4// Create a system configuration
5slamcore::v0::SystemConfiguration cfg;
6
7// create a SLAM System
8std::unique_ptr<slamcore::SLAMSystemCallbackInterface> slam = slamcore::createSLAMSystem(cfg);
9
10// register any callbacks
11slam->registerCallback<slamcore::Stream::Pose>(
12[](const slamcore::PoseInterface<slamcore::camera_clock>::CPtr& pose)
13{
14 // do something with the pose!
15});
16// ...
17
18slam->open();
19
20// enable the streams you need
21slam->setStreamEnabled(slamcore::Stream::Pose, true);
22// ...
23
24slam->start();
25
26// poll for data
27while(slam->spin(std::chrono::seconds(1)));
28
29// cleanup SLAM
30slam->stop();
31slam->close();
32
33// clean up the library
34slamcoreDeinit();
See Example hello_world_all_streams.cpp example for more information.
Saving & loading sessions
The Slamcore system can save the state of a session into a portable file and then use that file later to preload the map. The saving process is more than just saving a file, map clean-up and optimisation is carried out to produce higher quality localisation and faster map loading. Session saving is launched by launching an appropriate async task, e.g.:
const std::string ses_path = "/tmp/test.session"; // where to save the session
const slamcore::IDT tid = slam->launchAsyncTask(slamcore::TaskType::SaveSession,
{{"filename", ses_path}});
The code above launches the slamcore::TaskType::SaveSession
task, with appropriate parameters (path to the output file) and returns the
TaskID of that task. With that ID the task can be cancelled or its status can
be queried with the slamcore::SLAMAsyncTasksInterface::getTaskStatus()
method.
Warning
Please make sure SLAM is stopped before launching the save session task. Make sure to check the task status before launching a new task.
Loading the session file can be done either by providing the filename in the
slamcore::v0::SystemConfiguration
struct that is passed to
createSLAMSystem
or SLAM system can be open with
slamcore::SLAMCoreInterface::openWithSession()
method instead of
slamcore::SLAMCoreInterface::open()
.
See Example save_load_session.cpp or Example multisession.cpp examples for more information.
Subsystems
To keep the main SLAM system interface stable and simple, extension points are
provided for advanced users. This mechanism is called subsystems and they are
separate interfaces that can be obtained by calling the
getSubsystem
method.
SensorsInfo
This subsystem allows querying of the sensors in the system, their type and both real and factory calibration for each sensor.
Example:
auto cam_info = slam->getSubsystem<SensorsInfoInterface>();
const std::vector<SensorIDT> sensors = cam_info->getCameraList();
for(const auto& sensor : sensors)
{
const Vector dims = cam_info->getCameraSensorSize(sensor);
std::cout << "Sensor " << sensor << ", width: " << dims.x()
<< ", height: " << dims.y() << std::endl;
}
External Sensor Support
Note
This is an optional feature that might not be enabled for every customer. Please contact Slamcore for more information.
Our API supports feeding data from external (user-managed) sensors. This scenario is mostly used for wheel odometry data.
User side implementation
User has to implement a class that derives from slamcore::SensorSourceInterface
and one or more of sensor
interfaces, e.g.: slamcore::WheelOdometrySensorInterface
.
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 slamcore::SensorSourceInterface::open()
,
slamcore::SensorSourceInterface::close()
, slamcore::SensorSourceInterface::start()
,
slamcore::SensorSourceInterface::stop()
, and slamcore::<sensor interface at hand>::registerCallback
from a single thread.
Callback provided by Slamcore takes an abstract interface as an argument (std::shared_ptr
of it to be precise),
so the user will have to implement it to have a concrete type to create, populate with data and pass to the callback.
One has to pay attention when setting things like timestamps, reference frame, SensorID
of the sample etc.
If these are not set correctly (e.g. SensorID
not the one returned in slamcore::SensorSourceInterface::listSensors()
,
timestamps from a different timeline) the system might not have acceptable performance or even work at all.
Some sensor source interfaces have additional methods to be implemented, e.g. slamcore::CameraSensorInterface::getFrameRate()
.
Registration
The object of the class mentioned above (in a std::shared_ptr
) has to be registered with slamcore::registerExternalSensor()
, e.g.:
std::shared_ptr<WheelOdometryProvider> odom(new WheelOdometryProvider());
slamcore::registerExternalSensor("wheel_odometry", odom);
Currently, the first argument (name) is not important and left for future expansion.
Example
See Example wheel_odometry.cpp for more information on how to implement the sensor data providing class.
General remarks
When using the Slamcore C++ API with Intel RealSense camera avoid forking the process, as RealSense does not support it.
The Slamcore C++ API is not thread-safe.