8. karto mapping algorithm8.1. Introduction8.2. Use8.2.1. Start8.2.1. Controlling the robot8.2.1. Map saving8.3. Topics and services8.4. Configuration parameters8.5, TF transformation
karto: http://wiki.ros.org/slam_karto
map_server: https://wiki.ros.org/map_server
Karto is a 2D laser SLAM solution based on a sparse graph optimization method with loop closure detection. The graph optimization method uses the mean value of the graph to represent the map. Each node represents a position point of the robot trajectory and a sensor measurement data set. Each new node is added and the calculation is updated. Karto uses spa (karto_slam) or g2o (nav2d) optimization library, and the front-end and back-end use a single thread.
The ROS version of Karto_SLAM, in which the Spare Pose Adjustment (SPA) used is related to scan matching and loop closure detection. The more landmarks there are, the greater the memory requirements. However, compared with other methods, the graph optimization method has greater advantages in mapping in large environments because it only contains point graphs (robot poses), and the map is obtained after the pose is obtained.
overall program framework
Note: When building a map, the slower the speed, the better the effect (note that the rotation speed should be slower). If the speed is too fast, the effect will be poor.
According to different models, you only need to set the purchased model in [.bashrc], X1 (normal four-wheel drive) X3 (Mailun) Take X3 as an example
xxxxxxxxxx
#Raspberry Pi 5 master needs to enter docker first, please perform this step
#If running the script into docker fails, please refer to ROS/07, Docker tutorial
~/run_docker.sh
Open the [.bashrc] file
xxxxxxxxxx
sudo vim .bashrc
Find the [ROBOT_TYPE] parameters and modify the corresponding car model
xxxxxxxxxx
export ROBOT_TYPE=X3 # ROBOT_TYPE: X1 X3 X3plus R2 X7
Note: Due to the difference in radar laser data between 4ROS radar and A1 radar, you need to modify the karto source code part before it can run normally and modify the file.
xxxxxxxxxx
sudo gedit ~/software/library_ws/src/open_karto-melodic/include/open_karto/Karto.h
Locate line 4165, the source code is,
xxxxxxxxxx
void Update()
{
m_NumberOfRangeReadings = static_cast<kt_int32u>(math::Round((GetMaximumAngle() -
GetMinimumAngle())
/ GetAngularResolution())+1);
}
Need to be changed to,
xxxxxxxxxx
void Update()
{
m_NumberOfRangeReadings = static_cast<kt_int32u>(math::Round((GetMaximumAngle() -
GetMinimumAngle())
/GetAngularResolution()));
}
After saving, switch to the ~/software/library_ws directory and use catkin_make to compile.
xxxxxxxxxx
cd ~/software/library_ws
catkin_make
Start the command (robot side). For the convenience of operation, this section takes [mono + laser + yahboomcar] as an example.
xxxxxxxxxx
roslaunch yahboomcar_nav laser_bringup.launch # laser + yahboomcar
roslaunch yahboomcar_nav laser_usb_bringup.launch # mono + laser + yahboomcar
roslaunch yahboomcar_nav laser_astrapro_bringup.launch # Astra + laser + yahboomcar
Mapping command (robot side)
<PI5 needs to open another terminal to enter the same docker container
xxxxxxxxxx
roslaunch yahboomcar_nav yahboomcar_map.launch use_rviz:=false map_type:=karto
[use_rviz] parameter: whether to enable rviz visualization.
[map_type] parameter: Set the mapping algorithm [karto].
Turn on the visual interface (virtual machine side)
xxxxxxxxxx
roslaunch yahboomcar_nav view_map.launch
The gap at the back of the robot is due to the obstruction caused by the installation position of the display screen, so a certain range of radar data is blocked. The shielding range can be adjusted, or it can not be blocked according to the actual situation. For specific operations, see [01. Radar Basic Course].
Keyboard controls robot movement
xxxxxxxxxx
rosrun teleop_twist_keyboard teleop_twist_keyboard.py # System integration
roslaunch yahboomcar_ctrl yahboom_keyboard.launch # Custom
Control the robot movement with the handle
Make the robot cover the area to be mapped and the map should be as closed as possible.
There may be some scattered points during the mapping process. If the mapping environment is well closed, relatively regular, and the movement is slow, the scattering phenomenon will be much smaller.
xxxxxxxxxx
rosrun map_server map_saver -f ~/yahboomcar_ws/src/yahboomcar_nav/maps/my_map # The first way
bash ~/yahboomcar_ws/src/yahboomcar_nav/maps/map.sh # The second way
The map will be saved to the ~/yahboomcar_ws/src/yahboomcar_nav/maps/ folder, a pgm image and a yaml file.
map.yaml
xxxxxxxxxx
image: map.pgm
resolution: 0.05
origin: [-15.4,-12.2,0.0]
Negate: 0
occupied_thresh: 0.65
free_thresh: 0.196
Parameter analysis:
image: The path of the map file, which can be an absolute path or a relative path.
resolution: resolution of the map, meters/pixel
Origin: 2D pose (x, y, yaw) in the lower left corner of the map. The yaw here is rotated counterclockwise (yaw=0 means no rotation). Many parts of the current system ignore the yaw value.
negate: whether to reverse the meaning of white/black and free/occupied (the interpretation of the threshold is not affected)
occupied_thresh: Pixels with an occupation probability greater than this threshold will be considered fully occupied.
free_thresh: Pixels with occupancy probability less than this threshold will be considered completely free.
Topic Subscription | Type | Description |
---|---|---|
scan | sensor_msgs/LaserScan | Depth data of lidar scan |
tf | tf/tfMessage | Used for conversion between lidar coordinate system, base coordinate system, and odometer coordinate system |
Topic Post | Type | Description |
map_metadata | nav_msgs/MapMetaData | Publish map Meta data |
map | nav_msgs/OccupancyGrid | Publish map raster data |
visualization_marker_array | visualization_msgs/MarkerArray | Publish pose diagram |
Service | Type | Description |
dynamic_map | nav_msgs/GetMap | Get map data |
Node view
xxxxxxxxxx
rqt_graph
Common parameters
Parameters | Type | Default value | Description |
---|---|---|---|
~base_frame | string | "base_link" | Robot base coordinate system |
~map_frame | string | "map" | Map coordinate system |
~odom_frame | string | "odom" | Odometer coordinate system |
~throttle_scans | int | 1 | Process 1 per this many scans (set this to a higher number to skip more scans) |
~map_update_interval | float | 5.0 | The time in seconds between map updates. Lowering this number will update the occupancy grid more frequently, but will increase the computational load. |
~resolution | float | 0.05 | Map resolution (meters per occupied grid block) |
~delta | float | 0.05 | Map resolution (meters per occupied grid block). Same as resolution. Defined for compatibility with gmapping parameter names. |
~transform_publish_period | float | 0.05 | The time in seconds between transform publications. |
use_scan_matching | bool | true | Whether to use the scan matching algorithm, generally set to true, the mapper algorithm can correct the noise and errors of the odometer and laser. In some simulation environments with accurate sensor data, the scan matching algorithm will achieve worse results (because the use of Gaussian blur reduces the observation confidence of high-precision sensors), and it is recommended to turn it off (just add noise to the simulation environment). |
use_scan_barycenter | bool | true | Defines the distance between scans using the centroid of the scan endpoints. |
minimum_travel_distance | double | 0.2 | Set the minimum travel between scans. |
minimum_travel_heading | double | deg2rad(10)=0.087266461 | Set the minimum angle between scans. |
scan_buffer_size | int | 70 | Set the length of ScanBuffer, approximately equal to scan_buffer_maximum_scan_distance/minimum_travel_distance |
scan_buffer_maximum_scan_distance | double | 20.0 | Setting the maximum length of ScanBuffer is similar to Size |
link_match_minimum_response_fine | double | 0.8 | Set the minimum response threshold for the minimum scans connection |
link_scan_minimum_distance | double | 10.0 | Set the maximum distance between scans of two connections. If it is greater than this value, the response threshold of the two will not be considered |
loop_search_maximum_distance | double | 4.0 | Maximum distance for loop detection. Scans less than this distance from the current position will be considered matching loop closures. |
do_loop_closing | bool | true | Whether to enable loop closing detection |
loop_match_minimum_chain_size | int | 10 | The lowest chain size for loop detection |
loop_match_maximum_variance_coarse | double | math::Square(0.4)=0.16 | The maximum covariance value of coarse matching during loop matching. If it is less than this value, it is considered a feasible solution |
loop_match_minimum_response_coarse | double | 0.8 | The minimum response for coarse matching during loop matching. A response value greater than this value will start coarse precision loop optimization |
loop_match_minimum_response_fine | double | 0.8 | The minimum response threshold for loop matching. High accuracy will only start when it is greater than this value |
Correction parameters
Parameters | Type | Default value | Description |
---|---|---|---|
correlation_search_space_dimension | double | 0.3 | Set the search range size of Correlation Grid |
correlation_search_space_resolution | double | 0.01 | Set the resolution of the Correlation Grid |
correlation_search_space_smear_deviation | double | 0.03 | Set the Correlation Grid blur level |
Loopback parameters
Parameters | Type | Default value | Description |
---|---|---|---|
loop_search_space_dimension | double | 8.0 | Loop detection space range size |
loop_search_space_resolution | double | 0.05 | Loop detection spatial resolution |
loop_search_space_smear_deviation | double | 0.03 | Loop detection blur level |
Scan Matcher parameters
Parameters | Type | Default value | Description |
---|---|---|---|
distance_variance_penalty | double | sqrt(0.3)=0.09 (less than 1.0) | Compensation coefficient for odometer during scan-matching |
angle_variance_penalty | double | sqrt(deg2rad(20))=0.17453292 | Compensation coefficient for angle during scan-matching |
fine_search_angle_offset | double | deg2rad(0.2)=0.0017453292 | Fine search angle range |
coarse_search_angle_offset | double | deg2rad(20)=0.17453292 | Coarse search angle range |
coarse_angle_resolution | double | deg2rad(2)=0.017453292 | Coarse search angle resolution |
minimum_angle_penalty | double | 0.9 | minimum angle penalty |
minimum_distance_penalty | double | 0.5 | Minimum distance penalty |
use_response_expansion | bool | false | Whether to increase the search scope if no good matches are found |
Required TF transformation | Description |
---|---|
laser-->base_link | Usually a fixed value, the transformation between the lidar coordinate system and the base coordinate system, generally published by robot_state_publisher or static_transform_publisher |
base_link-->odom | Transformation between the map coordinate system and the robot odometer coordinate system, estimating the robot's pose in the map |
Published by TF Transform | Description |
map-->odom | The current estimate of the robot pose within the map frame (only provided if parameter "pub_map_odom_transform" is true). |
View tf tree
xxxxxxxxxx
rosrun rqt_tf_tree rqt_tf_tree