AAEON UP Xtreme i11 Robot Kit SLAM-Toolbox Tutorial#
Description
In this tutorial you will learn:
How to use AAEON Robot Kit with laser LIDAR.
How to mount RPLidar A1/A3 on AAEON Robot Kit.
How to use SLAM ToolBox with laser scanner.
How to run Mapping and Localization Modes using SLAM ToolBox.
How to save map in a SLAM Toolbox.
How to use saved map to navigate around using Nav2 stack.
Hardware needed
Batteries 7.4 2S for Motor Driver, and 11.1V 3S for the UP Xtreme i11, or AC/DC power supplies included in a kit.
RPLidar A1/A3 (purchase separately)
Logitech F710 gamepad (purchase separately)
For RPLIDAR A1 only M2.5 x 30mm standoff male-female 8pcs. (purchase separately)
For RPLIDAR A1 only M2.5 x 6mm screws 4pcs. (purchase separately)
For RPLIDAR A1 only M2.5 nuts 4pcs (purchase separately)
For RPLIDAR A3 only M2.5 x 30mm standoff male-female 8pcs. (purchase separately)
For RPLIDAR A3 only M3 x 30mm standoff male-female 4pcs. (purchase separately)
For RPLIDAR A3 only M3 x 6mm screws 4pcs. (purchase separately)
Mounting plate for LIDAR (both versions). Use the laser cutter and 3mm ABS plastic, or 3D print it. Download .stl file here CAD file to download
Robot prerequisites
Assembly your robot, see AAEON* Resources. Make sure that your Robot’s Inertial Measurement Unit (IMU) Sensor is calibrated.
Mount LIDAR following the installation guide for A1 model Steps to mount RPLIDAR A1 on the AAEON Robot Kit (Variant 1) or for A3 model Steps to mount RPLIDAR A3 on the AAEON Robot Kit (Variant 2)
Connect the 7.4V 2S Li-Po battery to the motor driver board and turn it on, see AAEON* Resources.
Power the main computer UP Xtreme i11 using an 11.1V 3S Li-Po battery, see AAEON* Resources. If you map a small space, you can also power the robot’s UP Xtreme board using AC/DC power supply, but it can prevent the robot to move far enough due to the short power cord.
Software prerequisites
Connect a Slamtec* RPLIDAR A3 2D LIDAR to your system.
Follow the Step #2 in 2D LIDAR and ROS 2 Cartographer to create udev rule for RPLidar.
Check if your EI for AMR installation has next Docker* images:
docker images |egrep "amr-aaeon-amr-interface|amr-ros-base|amr-imu-tools|amr-rplidar|amr-slam-toolbox|amr-nav2|" #If you have them installed, the result will be: amr-aaeon-amr-interface amr-ros-base amr-imu-tools amr-rplidar amr-slam-toolbox amr-nav2
Note
If these images are not installed, continuing with these steps triggers a build process that can take a very long time to complete, which also depends on the system resources and the internet connection. To avoid it Intel® recommends installing “the Robot Complete Kit EI for AMR”.
Check that EI for AMR environment is set:
echo $AMR_TUTORIALS # should output the path to EI for AMR tutorials /home/user/edge_insights_for_amr/Edge_Insights_for_Autonomous_Mobile_Robots_2023.1/AMR_containers/01_docker_sdk_env/docker_compose/05_tutorials
If nothing is output, refer to Get Started Guide for Robots Step 5 for information on how to configure the environment.
Steps to mount RPLIDAR A1 on the AAEON Robot Kit (Variant 1)#
Remove the default 5mm standoffs and mount 4pcs. M2.5 standoffs on the UP Xtreme board.
Mount 4pcs. M2.5 standoffs on the mounting plate and fix them using M2.5 screw nuts. Make sure the ventilation hole is oriented on the right side of the mounting plate.
Mount RPLIDAR A1 on the mounting plate using 4pcs. M2.5 x 6mm screws.
Put a mounting plate with the RPLIDAR on the standoffs and fix it with the default 5mm standoffs.
You mounted RPLIDAR A1 on the robot. Don’t connect RPLIDAR to the USB port of the UP Xtreme i11 computer.
Steps to mount RPLIDAR A3 on the AAEON Robot Kit (Variant 2)#
Remove the default 5mm standoffs and mount 4pcs. M2.5 standoffs on the UP Xtreme board.
Screw M3 30mm standoffs into RPLIDAR A3 on the mounting holes.
Fix RPLIDAR A3 on the mounting plate using M3 6mm screws. Make sure the ventilation hole in the plate, and RPLIDAR A3 wire are oriented exactly as in the picture.
Put a mounting plate with RPLIDAR on the standoffs of the main computer and fix it with the default 5mm standoffs.
You mounted RPLIDAR A3 on the robot. Don’t connect RPLIDAR to the USB port of the UP Xtreme i11 computer.
SLAM Toolbox Mapping mode using RPLIDAR and UP Xtreme i11 Robotic Kit#
The goal of the SLAM Toolbox mapping mode application is to manually map an area using a remote controller.
Put the robot on the ground.
Turn on the UP Xtreme i11, and wait till the OS will be initialized.
After that connect RPLIDAR A1 or A3 USB cable to the computer’s USB port.
Go to the installation folder of Edge_Insights_for_Autonomous_Mobile_Robots:
# Setup joystick controls sudo chmod a+rw /dev/input/js0 sudo chmod a+rw /dev/input/event* # Export the correct RPLIDAR device number export RPLIDAR_SERIAL_PORT=/dev/rplidar
Launch the SLAM Toolbox mapping mode application. For the RPLIDAR A1 run:
docker compose -f $AMR_TUTORIALS/aaeon_mapping_rplidar-a1_slam-toolbox_ukf.tutorial.yml up
For the RPLIDAR A3 run:
docker compose -f $AMR_TUTORIALS/aaeon_mapping_rplidar-a3_slam-toolbox_ukf.tutorial.yml up
Expected result: RViz will be opened, and you will see the building map process.
Use the Logitech F710 gamepad to control the robot. Hold on the button “RB”, then press the “Mode” button on the joystick, the green LED near this button will turn on. Then use a “D-pad” on the left side to control the robot around.
You will see that map in RViz will start extending.
When your robot moves, you will see red dots on the trajectory of the robot. They are graphs created by a SLAM Toolbox. You can create graphs depending on your needs. Read more about it in the SLAM Toolbox documentation
When you think that your map is good enough, you can save it. In RViz you can see at the bottom left the SLAM-Toolbox plugin. To save a map, enter your path to the already existing folder and enter a desired map file name, for example, the full path is “/home/amr/all_maps/map_1” where “all_maps” is the existing folder, and “map_1” is the desired future file name without extension. The map will be saved in .pgm format
You can check your folder to see that your map was saved successfully.
Then you will need to save a serialized map for navigation. Again, use the SLAM-Toolbox plugin in RViz. To save a serialized map, enter your path to the already existing folder and enter a desired map file name, for example, full path is “/home/amr/all_maps/map_1_ser” where “all_maps” is the existing folder, and “map_1_ser” is the desired future file name without extension.
You can check your folder again to see that serialized map was saved successfully, two more additional files were added “map_1_ser.data” and “map_1_ser.posegraph”
After saving all the map files, mapping was done successfully. To stop the robot from mapping the area, do the following:
Type
Ctrl-c
in the terminal executing the Docker* containerUse docker compose down to remove stopped containers:
# For RPLIDAR A1 docker compose -f $AMR_TUTORIALS/aaeon_mapping_rplidar-a1_slam-toolbox_ukf.tutorial.yml down --remove-orphans # For RPLIDAR A3 docker compose -f $AMR_TUTORIALS/aaeon_mapping_rplidar-a3_slam-toolbox_ukf.tutorial.yml down --remove-orphans
Troubleshooting#
If the robot does not move, check if the motor driver board is turned on.
If the robot does not move, check if the motor driver board USB device name is “dev/ttyUSB0”. To do so, disconnect LIDAR from the USB, then disconnect the USB cable from the motor driver board. Then connect back the USB cable from the motor driver board, and run the terminal command:
dmesg
Make sure that now motor driver board is recognized as “dev/ttyUSB0”. Connect LIDAR back and check the same way what USB device number it has, should be “dev/rplidar” Try to run the program again.
#. If the robot does not move in the mapping mode, make sure that the Logitech joystick works, and you send commands from it correctly.
If the robot does not move in the localization, send a 2D Pose Estimate command, and then “2D Goal Pose” one more time. Maybe not all software modules were initialized when you sent commands for the first time.
If you don’t see in RViz map visualization in the mapping mode, restart application.
If you don’t see it in the RViz map visualization, check that you imported correctly LIDAR USB device number.
If you don’t see it in the RViz map visualization, restart the application.
For general robot issues, go to Troubleshooting for Robot Tutorials.