You’re reading an older version of the Slamcore SDK documenation. The latest one is 23.04.
SLAMcore ROS2 Wrapper
Introduction
The SLAMcore ROS2 Wrapper allows interaction with SLAMcore algorithms via ROS2 Foxy. You may use the ROS2 wrapper with one of the following systems:
Supported Host Systems |
Installation Type |
---|---|
Ubuntu 20.04 |
ROS2 Wrapper on Native Ubuntu 20.04 |
Ubuntu 18.04, 20.04, NVIDIA Jetson |
ROS2 Wrapper via SLAMcore’s Docker Image |
The installation instructions are as follows:
A working ROS2 installation is required before installing the SLAMcore ROS2
Wrapper. More specifically ros-foxy-ros-base
should be installed while
the ros-foxy-desktop
package is optional.
#. To get started with ROS2, follow the instructions provided here: https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html.
#. Obtain SLAMcore’s ROS2 Foxy Wrapper package from the Download SLAMcore Software
link at the SLAMcore Portal.
Install the packages using
apt
or anapt
-based tool to automatically resolve dependencies.
# Update the list of available packages
$ sudo apt update
# To understand what will be installed, use a command like:
$ apt install --dry-run /path/to/ros-foxy-slamcore-ros*.deb
# ^~~~~ Specify the .deb file.
# To Install the slamcore_ros Debian package, use a command like:
$ sudo apt install /path/to/ros-foxy-slamcore-ros*.b
# ^~~~~~~~~~ Specify the .deb file.
In this case, no ROS2 installation is required before installing the SLAMcore ROS2 wrapper. Follow these instructions to set up our ROS2 wrapper in a docker container. This is the preferred method if you are on platforms such as NVIDIA’s Xavier NX which do not yet support the installation of Ubuntu 20.04.
- Download the SLAMcore ROS2 Wrapper for your host system from the ``Download
SLAMcore Software`` link on the SLAMcore Portal.
- Clone the slamcore-ros2-docker
repository and follow the instructions on GitHub to build SLAMcore’s ROS2 Docker image.
$ git clone https://github.com/slamcore/slamcore-ros2-docker.git
Below we describe how to use SLAMcore’s ROS2 wrapper on Ubuntu 20.04 with natively installed ROS2 Foxy. Details for running with the Docker image are provided at slamcore-ros2-docker.
Usage
Our ROS2 node streams poses only when the tracking status is OK.
Note
Make sure you have sourced the setup.bash
(adjust suffix according to your shell) before
running any of the RO2 nodes or launchfiles provided.
SLAM Mode
Here we provide an example use case of running SLAM. Before running it, make sure you have connected a registered, supported camera.
$ source /opt/ros/foxy/setup.bash
# connect to the camera and run SLAM
$ ros2 launch slamcore_slam slam_publisher.launch.py
# Verify that it's streaming data
$ ros2 topic echo /slamcore/pose
Expect output in the form:
# header:
# stamp:
# sec: 1627314066
# nanosec: 961842688
# frame_id: world
# pose:
# position:
# x: -0.00044667969888344613
# y: -0.00023092165271676365
# z: 0.0003275341432887679
# orientation:
# x: 0.059299501965805336
# y: 0.003310471496864338
# z: -0.0005325452114257774
# w: 0.998234604810249
To save a SLAM session in ROS2, call the /slamcore/save_session
service:
$ ros2 service call /slamcore/save_session std_srvs/srv/Trigger
The session file is saved by default in the working directory from which you
called ros2 launch slam_publisher.launch.py
.
SLAM using a recorded dataset
To run SLAM using a prerecorded dataset instead of a live camera you have to set the
path to the dataset using either the dataset_path
roslaunch argument or
using the /slamcore/dataset_path
ROS2 parameter:
# set parameter and run
$ ros2 launch slamcore_slam slam_publisher.launch.py dataset_path:=</path/to/dataset>
Localisation Mode
In localisation mode, our system uses a previously created session map. To load a session map, provide the full path to the session file when launching the SLAM wrapper ROS2 node, e.g.:
$ ros2 launch slamcore_slam slam_publisher.launch.py session_file:=<path/to/session/file>
Height Mapping Mode
In mapping mode, our system runs in SLAM mode but also generates a height map and an occupancy map which can be used in autonomous navigation.
To generate a height map, set the generate_map2d
parameter to true and
ensure the depth stream is enabled (true by default):
$ ros2 launch slamcore_slam slam_publisher.launch.py generate_map2d:=true
Dataset Recorder
To record a dataset in our ROS2 wrapper run:
$ ros2 launch slamcore_slam dataset_recorder.launch.py output_dir:=/home/<user>/<output-directory>
By default, the dataset will be saved in the current working directory, unless
the output_dir
argument is specified. When recording a dataset, you can also
provide a config file, for example to adjust the camera/depth settings
config_file:=$HOME/depth_preset.json
.
See the Troubleshooting page to help diagnose common errors.
ROS2 API
This section outlines the topics, services, and parameters that the SLAMcore ROS2 Wrapper uses as either inputs or outputs.
Lifecycles Nodes
Note
See the official ROS2 documentation for more information about lifecycle nodes.
The SLAMcore ROS2 nodes can be launched as managed nodes and therefore you can
change their state using the lifecycle
package:
# execute a state change
$ ros2 lifecycle set /slamcore/slam_node <lifecycle-state>
Run the following to query about the current state of the node:
$ ros2 service call /slamcore/slam_node/get_state lifecycle_msgs/GetState
Run the following to view the full list of available transitions at the current state of the node:
$ ros2 service call /slamcore/slam_node/get_available_transitions lifecycle_msgs/srv/GetAvailableTransitions
Run the following to reset SLAM similarly to the /slamcore/reset_signal
service advertised in ROS1:
$ ros2 lifecycle set /slamcore/slam_node deactivate
$ ros2 lifecycle set /slamcore/slam_node cleanup
$ ros2 lifecycle set /slamcore/slam_node configure
$ ros2 lifecycle set /slamcore/slam_node activate
Note
The list of available transitions will be different depending on what the current state of the node is.
- /slamcore/slam_node/configure
Description: Allow the node to load its configuration and conduct any required setup.
- /slamcore/slam_node/cleanup
Description: Clear all state and return the node to a functionally equivalent state as when first created. If the cleanup cannot be successfully achieved it will transition to
ErrorProcessing
.
- /slamcore/slam_node/activate
Description: This method is expected to do any final preparations to start executing.
- /slamcore/slam_node/deactivate
Description: This method is expected to do any cleanup to start executing, and should reverse the
onActivate
changes.
Advertised Topics
List of topics advertised by slam_publisher
:
- /diagnostics
Description: SLAMcore system diagnostic information
- /slamcore/accel
Type: sensor_msgs/Imu
Description: Accelerometer data, interpolated to align with the gyroscope measurements
- /slamcore/gyro
Type: sensor_msgs/Imu
Description: Gyroscope data
- /slamcore/{infrared, visual, depth}{, _0, _1, …}/camera_info
Type: sensor_msgs/CameraInfo
Description: Corresponding camera intrinsic parameters
- /slamcore/{infrared, visual}{_0, _1, …}/image_raw
Type: sensor_msgs/Image
Description: Raw image data
- /slamcore/depth/image_raw
Type: sensor_msgs/Image
Description: Depth data. Data is provided with float encoding, where each pixel value is the depth in metres
- /slamcore/local_point_cloud
Type: sensor_msgs/PointCloud2
Description: Unstructured point cloud generated from the depth image
- /slamcore/metadata/{num_features, tracked_features, tracking_status}
Type: std_msgs/Int64
Description: Metadata published periodically by the SLAM algorithm. See Tracking Status for more information on what the numbers refer to.
- /slamcore/metadata/{distance_travelled}
Type: std_msgs/Float64
Description: Distance travelled (metres) published periodically by the SLAM algorithm.
- /slamcore/pose
Description: Sensor pose
- /slamcore/odom
Type: nav_msgs/Odometry
Description: Smooth Pose, and Twist of the sensor. The pose is in the odometry frame of reference (see the /slamcore/odom_frame ROS Parameter) and the twist is in the instantaneous body frame of the sensor (see the /slamcore/base_frame ROS Parameter).
- /slamcore/sparse_map
Type: sensor_msgs/PointCloud2
Description: Computed sparse map
- /slamcore/map
Type: nav_msgs/OccupancyGrid
Description: Computed occupancy grid map
- /tf
Type: tf2_msgs/TFMessage
Description: Transform tree
- /tf_static
Type: tf2_msgs/TFMessage
Description: Static transform tree
Run the following to view the full list of topics:
$ ros2 topic list
Advertised Services
Below is the list of services advertised by slam_publisher
. These are used
mainly for interaction of the client/user with the SLAM machine. Run the following
to call the service:
$ ros2 service call /slamcore/<service-name> <service_type>
List of advertised services:
- /slamcore/save_session
Type: std_srvs/Trigger
Description: Save session map file (saved in the current working directory by default).
- /slamcore/static_map
Type: nav_msgs/GetMap
Description: Retrieve the static map (only advertised if loading from a session file).
Run the following to view the full list of services:
$ ros2 service list -t
Advertised Parameters
Below is the list of parameters that slam_publisher
fetches during
initialisation. To set the parameters:
# set the parameter via the corresponding roslaunch argument
$ ros2 launch slamcore_slam slam_publisher.launch.py <param-name>:=<desired-value> # for slam_publisher.launch.py OR
$ ros2 launch slamcore_slam dataset_recorder.launch.py <param-name>:=<desired-value> # dataset_recorder.launch.py
Run the following to view the full list of advertised parameters:
$ ros2 launch slamcore_slam slam_publisher.launch.py --show-args
$ ros2 launch slamcore_slam dataset_recorder.launch.py --show-args
Note
The full path(s) must be provided for the relevant parameter values e.g. /home/<user>/<path/to/file>
.
- /slamcore/slam_node/advertise_images
Type: Boolean
Default: True
Description: Advertise (publish) images
- /slamcore/slam_node/config_file
Type: String or a List of strings
Description: Path to the configuration/preset file(s). One can provide a single config file, e.g.
config_file:=/usr/share/slamcore/presets/outdoor.json
, or multiple config files as a listconfig_file:=[/usr/share/slamcore/presets/outdoor.json,$HOME/depth_preset.json]
- /slamcore/slam_node/dataset_path
Type: String
Description: Path to the recorded dataset to run SLAM with (details).
- /slamcore/slam_node/dataset_timescale
Type: Float
Default: -1 (runs as fast as possible).
Description: Control the playback speed by selecting a playback timescale. Setting it to values greater than zero sets a corresponding playback speed, and setting the timescale to
1.0
will play back in emulated real time. If no timescale is specified the playback will run as fast as possible to process every frame.
- /slamcore/slam_node/override_realsense_depth
Type: Boolean
Default: False
Description: Overwrite the depth stream, and therefore the depth topic for a RealSense, with the value provided with
/slamcore/realsense_depth_override_value
camera. See FAQs for more information.
- /slamcore/slam_node/realsense_depth_override_value
Type: Boolean
Default: False
Description: Overwrite the depth stream, and therefore the depth topic for a RealSense camera. See FAQs for more information.
- /slamcore/slam_node/enable_color
Type: Boolean
Default: False
Description: Publish RGB image. Please contact support@slamcore.com to enable this feature on your SLAMcore account.
- /slamcore/slam_node/session_file
Type: String
Description: Path to the session map to load to run in localisation mode (details).
- /slamcore/slam_node/session_save_dir
Type: String
Default: current working directory
Description: Specify directory to save session map at. If none is provided, maps will be saved to the current working directory from which you called
ros2 launch slam_publisher.launch.py
.
- /slamcore/slam_node/generate_map2d
Type: Boolean
Default: False
Description: Generate a new 2D map.
- /slamcore/slam_node/odom_reading_topic
Type: String
Description: Topic to read input wheel odometry from.
- /slamcore/slam_node/world_frame
Type: String
Default:
world
Description: Name given to the frame_id the pose is published relative to.
- /slamcore/slam_node/odom_frame
Type: String
Default: None
Description: Name given to the frame_id of the smooth world frame published on /tf (see REP-105).
- /slamcore/slam_node/base_frame
Type: String
Description: Name given to the frame_id the pose refers to.
- /dataset_recorder/output_dir
Type: String
Default:
$PWD/output
Description: Specify directory to save the recorded dataset at. If none is provided, it will be saved under the current working directory with the name
output
.
- /dataset_recorder/odom_reading_topic
Type: String
Default:
/odom
Description: Odometry input topic to subscribe to. The
slam_publisher
anddataset_recorder
will listen on this topic for nav_msgs/Odometry messages.