Release Notes¶
Click each tab to learn about the new and updated features in each release of Intel® Robotics SDK.
New Features
ADBSCAN updates
Ground floor segmentation for AMR using Intel® RealSense™ 3D points
Showcasing an Intel® algorithm designed for the segmentation of depth sensor data
FLANN and PCL optimization support for oneAPI™ 2024.0
FLANN and PCL optimization components are rebuilt using oneAPI™ version 2024.0
Kudan Visual SLAM (Simultaneous Localization and Mapping) Updates
Updated core algorithm of the Kudan Visual SLAM system to Release 2.6.0.0
Added Kudan’s documentation, can be accessed at
/opt/ros/humble/share/kdvisual_ros2/docs/html/
after the package has been installedExtended license validity until end of November 2024
New OpenVINO™ tutorials
Tutorial with semantic segmentation using Intel® RealSense™ camera topic as input image on CPU
Tutorial with object detection with input image on GPU
Multi-camera Object detection Tutorial using Intel® RealSense™ Depth Camera D457 (GMSL/FAKRA high-bandwidth stereo camera)
A Multi-camera use case tutorial using an Axiomtek Robox500 ROS2 AMR Controller and four Intel® RealSense™ Depth Camera D457 (GMSL/FAKRA Stereo Camera).
Four instances of AI-based applications for object detection and semantic segmentation are run in parallel using four Intel® RealSense™ camera streams.
Ultralytics YOLOv8 model and OpenVINO™ mobilenet-ssd model are downloaded and used for object detection and semantic segmentation.
The Axiomtek Robox500 ROS2 AMR Controller consists of a 12th Gen Intel® Core™ i7-1270PE, 28W processor and an Intel® Iris® Xe Integrated Graphics Processing Unit
Added support for the Clearpath Robotics Jackal™ Robot
Known Issues and Limitations
Kudan Visual SLAM warning “publish old TF data, trackingState is Lost”
Deb Packages for the SDK 2.1 Release
Component |
Deb packages |
---|---|
|
|
ROS bag files |
|
Common Libraries |
|
AAEON AMR Interface |
|
ADBSCAN |
|
Collaborative SLAM |
|
Fast Mapping |
|
Follow-me |
|
ITS Planner |
|
Kudan SLAM |
|
RealSense |
|
Object Detection |
|
Simulations |
|
Wandering |
|
ESDQ |
|
Benchmarking |
|
License |
|
New Features
Provide Intel® Robotics SDK as Deb packages
Improve the UX and to fix software libraries compatibility issues.
Reduced downloads size from >120GB to <5GB (or <20GB including bag files)
Reduced download time from >1hr to <10min
All open-source components can be pulled directly from the Internet
Debian package dependencies are handled using the standard Linux method
Software library have been standardized to use the same version across all components and are validated to interoperate
The most recent LTS version of all software libraries are used unless a specific exception is made
Kudan Visual SLAM (Simultaneous Localization and Mapping)
Updated core algorithm of the Kudan Visual SLAM system to Release 2.2.3.0
Optimized for Intel® GPUs
Updated the default launch file (
kdvisual_ros2_rgbd_realsense.launch.xml
->kdvisual_ros2.launch.xml
)Added
setup
parameter to set camera mode (rgbd
/stereo
/erasmo
)Added support for multi-camera mode
Updated tutorials for Kudan Visual SLAM using pre-recorded video streams from RGBD cameras and stereo cameras
New tutorial with Kudan Visual SLAM, an AAEON robotic kit, and an Intel® RealSense™ camera
Extended license validity until end of August 2024
Added support for Alder Lake N and Raptor Lake P
Intel® Robotics SDK v2.0 is tested on ADL-N and RPL-P systems.
ADBSCAN support on the AAEON Robot Kit
The new feature consists of ADBSCAN algorithm that runs together with FastMapping to create a 3D spatial scan of the environment around. To support developers we have created a tutorial that runs on the AAEON Robot Kit, so the users can test and modify it if necessary for their own applications.
ORB Feature Extractor 2023.2
The orb-extractor feature library enables users to generate multiple orb-extractor objects tailored to their applications. Additionally, a single orb-extractor feature object exhibits the capability to process input from one or multiple camera sources. Orb-extractor provides versatile support for various configurations in the realm of Visual SLAM front-ends.
Basic Follow Me Application tutorial
This tutorial demonstrates how to run the ADBScan-based Follow-me algorithm using Intel® RealSense™ camera input with AAEON Robot. After running this tutorial you can expect AAEON robot is following you based on the realsense camera input.
Aaeon robot configuration for wandering tutorial
This tutorial creates a map with Wandering application running using Realsense Camera as input.
Robot Re-localization package for ROS 2 Navigation
The robot re-localization package is a package which enables re-localization in ROS 2 navigation.
ITS global path planner for ROS 2 Navigation
Intelligent Sampling and Two-Way Search (ITS) global path planner is a plugin for ROS 2 navigation package which conducts a path planning search on a roadmap from two directions simultaneously.
Follow-me with gesture is an AMR algorithm where the robot automatically follows a target person
The movement of the robot is controlled by two components:
ADBSCAN-based target detection
Hand gesture category of the target
ADBSCAN algorithm takes inputs from a point cloud sensor (LIDAR or depth camera) mounted on the robot whereas gesture recognition pipeline takes RGB camera inputs.
Updated all CSLAM dependencies
All libraries that are required to run CLSAM have been updated.
Intel® Edge Software Device Qualification (Intel® ESDQ) Update
Updated the test module to be compatible with the new Command Line Interface (CLI) 11.0.0 version.
Known Issues and Limitations
In some rare cases, while running the “Wandering Application with Intel® RealSense™ camera and Rtabmap Application in Aaeon Robot”, the robot collides with walls and other obstacles.
On some processing platforms the Kudan Visual SLAM system occasionally reports that the keypoint tracking has failed and that the tracker has relocalized. Section Tracking is occasionally lost describes the issue and provides a work-around.
Debian Packages for the SDK 2.0 Release
Component |
Deb packages |
---|---|
Robotics SDK |
|
ROS bag files |
|
Common Libraries |
|
AAEON AMR Interface |
|
ADBSCAN |
|
Collaborative SLAM |
|
Fast Mapping |
|
ITS Planner |
|
Kudan SLAM |
|
Simulations |
|
Wandering |
|
ESDQ |
|
Revision History
Date |
Software Version |
Description |
June, 2023 |
2023.1.0 |
Updated several features and libraries, ADL-P support |
January 20, 2023 |
2022.3.1 |
Update of the Kudan Visual SLAM license file inside the amr-kudan-slam Docker* image |
December 16, 2022 |
2022.3.0 |
Document-only update: added ADL-P with Ubuntu* 22.04 support for evaluation |
September 26, 2022 |
2022.3.0 |
Update release |
AMR 2023.1.0 Release
New Features
Added support for 12th Generation Intel® Core™ processors
Added support for multi-camera, region-wise remapping and 2D Lidar in Collab-SLAM
Added new modules, improvements, and bug fixes to PCL Optimization libraries
Added stereo camera support for GPU ORB (Oriented FAST and Rotated BRIEF)
Added Intel® RealSense™ depth image input support in ADBSCAN
Follow-me application based on ADBSCAN
Support Ackermann drive in ITS planner
Enabled Lidar SLAM based on SLAM toolbox
Updates to Fleet Management
Updated OpenVINO™ to 2022.3 LTS
Kudan SLAM with updated core algorithm, new tutorials, and extended license validity
Platform configuration
Robot: Ubuntu* 22.04 Intel® IOT, ROS 2 foxy, kernel v5.15+
Collab-SLAM Updates
Added support for tracker frame-level pose fusion using Kalman Filter (part of loosely coupled solution for multi-camera feature)
Added support for region-wise remapping feature that updates pre-constructed keyframe/landmark map and octree map with manual region input from user in remapping mode
Added support of 2D Lidar based frame-to-frame tracking for RGBD input
Added support for multi-camera SLAM using RTABMAP
Enabled multi-camera support up to four Intel® RealSense™ depth cameras for VSLAM
PCL Optimization Libraries Updates
Added oneAPI version of Sample Consensus Initial Alignment
Added oneAPI version of Normal Estimation
Added oneAPI version of Statistical Outlier Removal
Added OpenMP version of Greedy Projection Triangulation
Added OpenMP version of Statistical Outlier Removal
Added GPU memory manager to support all oneAPI PCL modules
Follow-me Application
This is an object tracking application for autonomous mobile robots based on Intel® patented ADBSCAN clustering algorithm.
Supported for Pengo robot, that will follow a moving object or person, keeping a safe distance and is not impacted by surrounding clutter or temporary occlusion.
Ready-to-use launch and parameter configuration files for 2D, 3D LIDAR and Intel® RealSense™ depth camera.
ITS Global Path Planner
In this release we added support for Ackermann steering, which is used by car-like robots with limited turning radius. This version of the planner is based on the concept of Dubins paths. The default version of the ITS is based on differential drive.
Enabled Lidar SLAM based on SLAM toolbox
Enabled “Lidar only” based SLAM on Aaeon robot and pengo robot using SLAM Toolbox algorithm
Supported Lidar: RP Lidar A1, A3 and Sick nanoScan
Added a sample application, which uses one Lidar sensor, runs synchronous mapping, and uses that map to navigate in localization mode
Fleet Management
SOTA update supported with Ubuntu* 22.04 on Robot
Improvements on Error handling for Robot onboarding
Updated OpenVINO™ to 2022.3 LTS
Update to ROS 2 based OpenVINO™ Toolkit
Update to Open Model Zoo examples and models
Kudan Visual SLAM (Simultaneous Localization and Mapping)
Updated core algorithm of the Kudan Visual SLAM system to Release 2.2.1.0
Works with the latest ORB Feature Extractor (Version 2023.1), which is optimized for Intel® GPUs
Updated launch file format (python -> xml)
Updated tutorials for Kudan Visual SLAM using a video stream from an Intel® RealSense™ camera, including new launch files and configuration data
New tutorials for Kudan Visual SLAM using a video stream from a stereo camera
New tutorial for Wandering App based on Kudan SLAM using AAEON robot kits
Extended license validity until end of 2023
Resolved Issues
Kudan Visual SLAM
Fixed issue that Kudan Visual SLAM with the ORB Feature Extractor on the GPU stops mapping using the
robot_moving_15fps
ROS 2 bag.
Known Issues and Limitations
It currently takes up to 100 minutes to install the AMR bundle. The time varies depending on the speed of your internet connection and system’s capabilities.
The POTA implementation in the onboarding flow requires manual input for Product Name and Manufacturer for each type of robot added to the flow.
The Inertial Measurement Unit (IMU) cannot be started on Intel® RealSense™.
Due to the camera’s discontinuation, the Intel® RealSense™ Lidar L515 camera is no longer supported by AMR.
In the Wandering App, the robot radius is hard-coded to 0.177 m. Depending on the actual robot diameters, this may affect the quality of pathfinding and mapping.
RTAB_MAP is not best suited for indoor navigation. Therefore, some obstacles may not be detected with the highest accuracy, due to reflections, etc.
The oneAPI implementation of the convex hull algorithm might provide incorrect outputs. This will be fixed in a future version of the AMR software.
The Server Solution does not cover SEO telemetry and Metric Scrapping.
In case of very high frequency of MQTT message transfers between Thingsboard and Turtle Creek, some performance issues might be caused due to packet loss.
Fleet Management SOTA/FOTA might throw permission denied error. Refer to Developer Guide for workaround.
Due to a compatibility issue of the TensorFlow library the object-detection container of the fleet management is not starting when running on AAEON EHL robot target.
The
barometer-collectd
is not Starting in Cluster of Fleet Management
Intel® Atom® CPU
The server setup deploys collaborative visual SLAM on Cogniteam’s Pengo robot without checking the type of CPU it has. (The Intel® Atom® CPU in Cogniteam’s Pengo robot is not supported by default.)
The installed TensorFlow* version in AMR contains Intel® Advanced Vector Extensions (Intel® AVX) instructions. These Intel® AVX instructions are not supported by Intel® Atom® CPUs like the CPU in Elkhart Lake platform. Any action, including the OpenVINO™ sample application, fails on a platform with an Intel® Atom® CPU. To be able to run TensorFlow* on an Intel® Atom® CPU, it must be re-compiled without the Intel® AVX instructions using the steps from: How to Build and Install the Latest TensorFlow* Without CUDA GPU.
Gazebo* simulation does not work on the Intel® Atom® 3000 processor family like the Apollo Lake-based UP2 (UP Squared). Intel® recommends creating the Gazebo* simulation environment on more powerful systems that have, for example, 12th or 11th generation Intel® Core™ or Intel® Xeon® Scalable processors.
AAEON’s UP Xtreme i11 Robotic Kit
It has been observed that, after 20 minutes of run time, an AAEON* robot gets too close to obstacles and, because Intel® RealSense™ depth does not give information under 20 cm, the robot collides with obstacles.
The AAEON’s UP Xtreme i11 Robotic Kit loses its orientation and redraws the walls in the test area multiple times. Due to this improper mapping, the robot cannot correctly identify the position of the obstacles and might collide with them.
Collaborative Visual SLAM
For long runs, where the edge server accumulates more than 80,000 key frames, the shutdown process takes more time to exit cleanly.
For visual odometry fusion with monocular input, after the visual tracking is lost, the system relies on odometry input (if enabled) to sustain tracking and is never able to switch back to visual tracking.
The visual-inertial fusion is not supported in localization mode.
Fusion of visual, inertial, and odometry data at the same time is not supported.
Map merge does not happen if robots are moving in opposite directions through a common area.
When both the server and tracker are launched, the robot loses tracking while rotating in place.
The collaborative visual SLAM tracker crashes when running in localization mode with 30 FPS.
The current implementation for multi-camera feature only functions when the trackers never get lost. Additionally, multi camera features on the server side are not supported at this time.
Local Bundle Adjustment and Global Bundle Adjustment are not considered in the 2D Lidar support.
Intel® ESDQ for AMR
The Intel® RealSense™ camera test fails if there is no Intel® RealSense™ camera attached to the target System, reporting this error message:
[ERROR]: No RealSense devices were found
.If the internet connection is not stable or GitHub is blocked by a firewall, some Intel® ESDQ tests fail.
On an Intel® Atom® CPU, some of the tests in Intel® ESDQ will not work due to missing support in AVX.
Release Content
Subproject (component) |
Revision |
---|---|
amr-aaeon-amr-interface |
2023.1 |
amr-adbscan |
2023.1 |
amr-battery-bridge |
2023.1 |
amr-cartographer |
2023.1 |
amr-collab-slam |
2023.1 |
amr-collab-slam-gpu |
2023.1 |
amr-fastmapping |
2023.1 |
amr-fdo-client |
2023.1 |
amr-fleet-management |
2023.1 |
amr-gazebo |
2023.1 |
amr-gstreamer |
2023.1 |
amr-imu-tools |
2023.1 |
amr-kobuki |
2023.1 |
amr-kudan-slam |
2023.1 |
amr-nav2 |
2023.1 |
amr-object-detection |
2023.1 |
amr-realsense |
2023.1 |
amr-ros2-openvino |
2023.1 |
amr-ros-arduino |
2023.1 |
amr-ros-base |
2023.1 |
amr-ros1-bridge |
2023.1 |
amr-robot-localization |
2023.1 |
amr-rplidar |
2023.1 |
amr-rtabmap |
2023.1 |
amr-sick-nanoscan |
2023.1 |
amr-slam-toolbox |
2023.1 |
amr-turtlebot3 |
2023.1 |
amr-turtlesim |
2023.1 |
amr-vda-navigator |
2023.1 |
amr-vda5050-ros2-bridge |
2023.1 |
amr-wandering |
2023.1 |
eiforamr-base-sdk |
2023.1 |
eiforamr-full-flavour-sdk |
2023.1 |
eiforamr-openvino-sdk |
2023.1 |
edge-server-base |
2023.1 |
edge-server-fdo-manufacturer |
2023.1 |
edge-server-fdo-owner |
2023.1 |
edge-server-fdo-rendezvous |
2023.1 |
edge-server-fleet-management |
2023.1 |
edge-server-ovms-tls |
2023.1 |
Robotics SDK containers |
2023.1 |
Robotics SDK Edge Server containers |
2023.1 |
Robotics SDK Test Module |
2023.1 |
Robotics SDK Bag Files |
2023.1 |
Intel® Edge Software Device Qualification (Intel® ESDQ) |
2023.1(11.0) |
Docker Compose* |
2.18.1 |
Docker* Community Edition CE |
24.0.2 |
Source Code Distribution under GPL |
2023.1 |