How it Works how_it_works

The Intel® Robotics SDK (Robotics SDK) modules are deployed as Deb packages, enhancing the Developer Experience (DX) and supporting Continuous Integration and Continuous Deployment (CI/CD) practices. They offer flexible deployment across various execution environments, including robots, development PCs, servers, and the cloud.

Modules and Services

In the Intel® oneAPI Base Toolkit (oneAPI™) and Intel® Distribution of OpenVINO™ toolkit (OpenVINO™), a middleware layered architecture that abstracts hardware dependencies from algorithm implementation.

The ROS 2 with a data distribution service (DDS) is used as a message bus. This Publisher-Subscriber architecture based on ROS 2 topics decouples data providers from consumers.

Camera and LiDAR sensor data is abstracted through ROS 2 topics.

Video streaming processing pipelines are supported by GStreamer*. GStreamer* is a library for constructing media handling component graphs. It decouples sensor ingestion, video processing and AI object detection via OpenVINO™ toolkit DL Streamer framework. This versatile framework supports applications ranging from simple Ogg Vorbis playback audio and video streaming to complex audio (mixing) and video (non-linear editing) processing.

For more complex computational graphs that decouple Sense-Plan-Act in AMR applications, ROS 2 topic registration can be implemented.

This diagram shows the software components included in the Robotics SDK package.

../../_images/amr_sdk_software_components.png

The Robotics SDK software stack relies on the underlying hardware platform, software supported by and integrated into their respective Unified Extensible Firmware Interface (UEFI) based boot processes, and supported Linux* operating system. For requirement details, see Recommended Hardware .

Robotics SDK Drivers

Intel® Robotics SDK relies on standard Intel® Architecture Linux* drivers that are included and upstreamed in the Linux* kernel from kernel.org and forming part of Ubuntu* distributions. These drivers are not bundled within the Robotics SDK package. Some notable drivers that are specifically important for Robotics SDK include:

  • Video4Linux2 Driver Framework, a collection of device drivers and an API for supporting realtime video capture on Linux* systems (compatible with USB webcams, TV tuners etc.), standardizing the video output, so that programmers can easily add video support to their applications.

  • The Serial Driver, the serial stream as used in Ethernet and USB interfaces.

Tools

ROS 2 Tools

The Intel® Robotics SDK is validated using ROS 2 tools as it is not compatible with ROS 1 components. To facilitate interaction, a ROS 1 bridge is included, enabling Robotics SDK components to interface with ROS 1 components.

  • From the hardware perspective of the supported platforms, there are no known limitations for ROS 1 components.

  • For information on porting ROS 1 applications to ROS 2, refer to the How to Guide.

Intel® Robotics SDK includes:

  • rqt, a software framework of ROS 2 that implements the various GUI tools in the form of plugins.

  • rviz2, a tool used to visualize ROS 2 topics.

  • colcon (collective construction), a command line tool to improve the workflow of building, testing, and using multiple software packages (It automates the process, handles the ordering, and sets up the environment to use the packages.)

Simulation Tools

  • The Gazebo* robot simulator, making it possible to rapidly test algorithms, design robots, perform regression testing, and train AI systems using realistic scenarios. Gazebo offers the ability to simulate populations of robots accurately and efficiently in complex indoor and outdoor environments.

  • An industrial simulation room model for Gazebo*, the Open Source Robotics Foundation (OSRF) Gazebo Environment for Agile Robotics (GEAR) workcell that was used for the ARIAC competition in 2018.

  • A Pick and place simulation demo to showcase the interaction of a conveyor belt, a TurtleBot3 Waffle Autonomous Mobile Robot (AMR), and two UR5 robotic arms (ARM) in a simulated environment.

  • Wandering application in Gazebo simulation to showcase autonomous mapping of a gazebo world using TurtleBot3 Waffle robot.

Other Tools

  • Intel® oneAPI Base Toolkit encompasses essential components such as the DPC++ compiler, compatibility tool and a suite of debugging and profiling tools, like the VTune™ Profiler (formerly known as Intel System Studio).

  • Intel® Distribution of OpenVINO™ toolkit, inclusive of the Model Optimization Tool.

  • Intel® ESDQ, is a self-certification test suite to enable partners to determine their platform’s compatibility with the Robotics SDK.

  • AWS* RoboMaker, a cloud-based simulation service, empowers robotics developers to run, scale, and automate simulation seamlessly without the need to manage any infrastructure.

  • Foxglove Studio, interactive visualizations to analyze live connections and pre-recorded data.

Robotics SDK Applications

  • The Wandering Application, included in the Robotics SDK, demonstrates the combination of the middleware, algorithms, and the ROS 2 navigation stack. It showcases the ability to navigate a robot to explore an unknown environment, avoiding hitting obstacles, updating a local map in real-time exposed as a ROS topic, and publishing AI objects detected in another ROS topic (It uses the robot’s sensors and actuators based on its hardware configuration.)

  • Object Detection AI Application, detects objects in video data using a deep learning neural network model from the OpenVINO™ Model Zoo

  • Semantic Segmentation AI Application, is a computer vision application that assigns labels to each pixel according to the object it belongs to, creating so-called segmentation masks.

  • Ground Floor Segmentation Application, uses pointcloud data for distinguishing between ground floor, elevated surfaces, obstacles, and structures above ground level.

  • Benchmarking Application, is a toolkit that uses the Intel® Robotics SDK ingredients to run various combinations of Robotic application & AI application to estimate robotics and deep learning inference performances respectively on supported devices.

Robotics SDK Algorithms

Robotics SDK includes reference algorithms as well as deep learning models, providing practical examples of automated robot control functions.

Open Model Zoo for OpenVINO™

The Open Model Zoo for OpenVINO™ toolkit delivers optimized deep learning models and a set of demos to expedite development of high-performance deep learning inference applications. You can use these pre-trained models instead of training your own models to speed up the development and production deployment process.

For details, see Model Zoo.

ADBSCAN

Tutorial: ADBSCAN Algorithm

DBSCAN (Density-Based Spatial Clustering of Applications with Noise) is an unsupervised clustering algorithm that clusters high dimensional points based on their distribution density. Adaptive DBSCAN (ADBSCAN) has clustering parameters that are adaptive based on range and are especially suitable for processing LiDAR data. It improves the object detection range by 20-30% on average.

3D Pointcloud Groundfloor Segmentation

Tutorial: 3D Pointcloud Groundfloor Segmentation for Intel® RealSense™ Camera and 3D LiDAR

An algorithm, along with a demo application, that transforms (Intel® RealSense™) depth images to 3D pointclouds. This algorithm further assigns classification labels such as ‘ground floor’ or ‘obstacle’ to each point, delivering both the resulting and filtered pointclouds as output.

Point Cloud Library (PCL)

Tutorial: Point Cloud Library (PCL) Optimized for the Intel® oneAPI Base Toolkit

The Point Cloud Library (PCL), a standalone, large scale, open project for 2D/3D image and point cloud processing (see also https://pointclouds.org/). The Robotics SDK SDK version of PCL adds optimized implementations of several PCL modules which allow you to offload computation to a GPU.

ROS 2 Depth Image to Laser Scan

ROS 2 Depth Image to Laser Scan, converts a depth image to a laser scan for use with navigation and localization.

IMU Tools

IMU Tools - filters and visualizers - from https://github.com/CCNYRoboticsLab/imu_tools:

  • imu_filter_madgwick: A filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation.

  • imu_complementary_filter: A filter which fuses angular velocities, accelerations and (optionally) magnetic readings from a generic IMU device into an orientation quaternion using a novel approach based on a complementary fusion.

  • rviz_imu_plugin: A plugin for rviz which displays sensor_msgs::Imu messages.

FastMapping

Tutorial: FastMapping Algorithm

FastMapping, is an algorithm to create a 3D voxel map of a robot’s surrounding, based on Intel® RealSense™ depth sensor data.

Collaborative Visual SLAM

Tutorial: Collaborative Visual SLAM

Collaborative visual SLAM is a framework for service robots which utilizes simultaneous localization and mapping (SLAM). An edge server maintains a map database and handles global optimization. Each robot can register to an existing map, update it, or build new maps, all through a unified interface with low computation and memory costs. A collaborative visual SLAM system consists of at least two elements:

  • The tracker is a visual SLAM system with support for inertial and odometry input. It estimates the camera pose in real-time, and maintains a local map. It can work without a server, but if it has one configured, it communicates with the server to query and update the map. The tracker represents a robot. There can be multiple trackers running at the same time.

  • The server maintains the maps and communicates with all trackers. For each new keyframe from a tracker, it detects possible loops, both intra-map and inter-map. Once detected, the server performs map optimization or map merging and distributes the updated map to corresponding trackers.

For collaborative visual SLAM details, refer to A Collaborative Visual SLAM Framework for Service Robots paper.

ROS 2 Cartographer

ROS 2 Cartographer is a system that provides real-time simultaneous localization and mapping (SLAM) based on real-time 2D LiDAR sensor data. It is used to generate as-built floor plans in the form of occupancy grids.

RTAB-Map (Real-Time Appearance-Based Mapping) is an RGB-D, Stereo and LiDAR Graph-based SLAM approach, employing an incremental appearance-based loop closure detector. This detector uses a bag-of-words approach to determinate how likely a new image comes from a previous location or a new location. When a loop closure hypothesis is accepted, a new constraint is added to the map’s graph, followed by graph optimization to minimize the errors. A memory management approach is used to restrict the number of locations used for loop closure detection and graph optimization, so that real-time constraints on large-scale environments are consistently met. RTAB-Map can be used alone with a handheld Kinect, a stereo camera or a 3D lidar for 6DoF mapping, or on a robot equipped with a laser rangefinder for 3DoF mapping.

SLAM Toolbox

The SLAM toolbox is a set of tools and capabilities for 2D SLAM that includes the following:

  • Starting, mapping, saving pgm files, and saving maps for 2D SLAM mobile robotics.

  • Refining, remapping, or continue mapping a saved (serialized) pose-graph at any time.

  • Loading a saved pose-graph continue mapping in a space while also removing extraneous information from newly added scans (life-long mapping).

  • An optimization-based localization mode built on the pose-graph. Optionally run localization mode without a prior map for “LIDAR odometry” mode with local loop closures.

  • Synchronous and asynchronous modes of mapping.

  • Kinematic map merging (with an elastic graph manipulation merging technique in the works).

  • Plugin-based optimization solvers with an optimized Google* Ceres-based plugin.

  • rviz2 plugin for interacting with the tools.

  • Graph manipulation tools in rviz2 to manipulate nodes and connections during mapping.

  • Map serialization and lossless data storage.

  • See also https://github.com/SteveMacenski/slam_toolbox.

ITS Global Path Planner

Tutorial: ITS Path Planner ROS 2 Navigation Plugin

The Intelligent Sampling and Two-Way Search (ITS) Global Path Planner is a plugin for the ROS 2 Navigation package. It performs a path planning search on a roadmap from two directions simultaneously. The main inputs are 2D occupancy grid map, robot position, and the goal position. The occupancy is converted into a roadmap and can be saved for future inquiries. The output is a list of waypoints which constructs the global path. All inputs and outputs are in standard ROS 2 formats. This plugin is a global path planner module which is based on the Intelligent Sampling and Two-Way Search (ITS). Currently, the ITS plugin does not support continuous replanning. To use this plugin, a simple behavior tree with compute path to pose and follow path should be used. The inputs for the ITS planner are global 2d_costmap (nav2_costmap_2d::Costmap2D), start and goal pose (geometry_msgs::msg::PoseStamped). The outputs are 2D waypoints of the path. The ITS planner gets the 2d_costmap and it converts it to either Probabilistic Road Map (PRM) or Deterministic Road Map (DRM). The generated roadmap is saved in a txt file which can be reused for multiple inquiries. Once a roadmap is generated, the ITS conducts a two-way search to find a path from the source to destination. Either the smoothing filter or catmull spline interpolation can be used to create a smooth and continuous path. The generated smooth path is in the form of ROS navigation message type (nav_msgs::msg).

Kudan Visual SLAM

Tutorial: Kudan Visual SLAM

Kudan Visual SLAM (KdVisual), Kudan’s proprietary visual SLAM software, has been extensively developed and tested for use in commercial settings. Open source and other commercial algorithms struggle in many common use cases and scenarios. Kudan Visual SLAM achieves much faster processing time, higher accuracy, and a more robust results in dynamic situations.

Robot Localization

robot_localization (from https://github.com/cra-ros-pkg/robot_localization), a collection of state estimation nodes, each of which is an implementation of a nonlinear state estimator for robots moving in 3D space. It contains two state estimation nodes, ekf_localization_node and ukf_localization_node. In addition, robot_localization provides navsat_transform_node, which aids in the integration of GPS data.

Robotics SDK Middleware

  • Intel® Distribution of OpenVINO™ toolkit is a comprehensive toolkit for rapidly developing applications and solutions across a range of tasks. This includes emulation of human vision, automatic speech recognition, natural language processing, recommendation systems, and more. Built on latest generations of artificial neural networks, including Convolutional Neural Networks (CNNs), recurrent and attention-based networks, the toolkit extends computer vision and non-vision workloads across Intel® hardware, optimizing performance. It accelerates applications with high-performance AI and deep learning inference, deployed from edge to the cloud.

  • Intel® oneAPI Base Toolkit, is capable of executing sample applications in the toolkit. This core set of tools and libraries is designed for developing high-performance, data-centric applications across diverse architectures. It features an industry-leading C++ compiler and the Data Parallel C++ (DPC++) language, an evolution of C++ for heterogeneous computing. For Intel® oneAPI Base Toolkit training, refer to:

  • The Intel® RealSense™ ROS 2 Wrapper node is utilized for Intel® RealSense™ cameras within ROS 2.

  • The Intel® RealSense™ SDK is used to implement software for Intel® RealSense™ cameras.

  • The ROS 2 OpenVINO™ Toolkit provides a ROS 2 adapted runtime framework of neural networks, enabling rapid deployment of applications and solutions for vision inference.

  • AAEON* ROS 2 interface, the ROS 2 driver node for AAEON Robotics SDKs.

  • Slamtec* RPLIDAR ROS 2 Wrapper node for using RPLIDAR LIDAR sensors with ROS 2.

  • SICK Safetyscanners ROS 2 Driver reads the raw data from the SICK Safety Scanners and publishes the data as a laser_scan msg.

  • ROS 2 ros1_bridge, facilitates a network bridge for exchanging messages between ROS1 and ROS 2. This allows users to evaluate the Robotics SDK on Robotics SDKs or with sensors for which only ROS1 driver nodes exist.

  • ROS 2, Robot Operating System (ROS) is a collection of open-source software libraries and tools designed for building robot applications. ROS 2 depends on other middleware, like the Object Management Group (OMG) DDS connectivity framework which utilizes a publish-subscribe pattern (The standard ROS 2 distribution includes eProsima Fast DDS implementation.)

  • OpenCV (Open Source Computer Vision Library) is an open-source library that includes several hundred computer vision algorithms.

  • GStreamer* includes support for libv4l2 video sources, GStreamer* “good” plugins for video and audio, and a GStreamer* plugin for display to show a video stream in a window.

  • Teleop Twist Joy is a generic facility for teleoperating twist-based ROS 2 robots with a standard joystick. It converts joy messages to velocity commands. This node does not include rate limiting or auto-repeat functionality. It is recommended to leverage the features integrated into ROS 2 Driver for a Generic Joystick.

  • Teleop Twist Keyboard provides a generic keyboard teleoperation solution for ROS 2.

  • The Twist Multiplexer is essential in scenarios where multiple sources move a robot using a geometry_msgs::Twist message. It plays important role in multiplexing all input sources into a single source that goes to the Robotics SDK control node.

  • The ROS 2 Driver for Generic Joysticks.