# ROS_Noetic_SLAM
[TOC]
:warning: Remember to source ~/workspace/install(或是install_isolated)/setup.bash
## Four method for scanMatcher

## Gmapping (Only introduction)
https://ithelp.ithome.com.tw/articles/10220338
## Hector slam(Only introduction)
https://ithelp.ithome.com.tw/articles/10220757
## Cartographer(Use this)
在開始前,先提供一個Cartographer提供的debug方式:
先將要launch的node開下去以後,然後新開一個在workspace dir的終端機視窗執行,
:::info
rosbag record -a
:::
然後等它record一下,覺得差不多就ctrl+c中止它,然後在這個workspace執行這個bag,可以ls一下就會知道名字,然後執行:
:::info
cartographer_rosbag_validate -bag_filename your_bag.bag
:::
### Install and Build
For ROS Noetic
Step 1 install wstool wstool rosdep ninja:
:::info
sudo apt-get update
sudo apt-get install -y python3-wstool python3-rosdep ninja-build stow
:::
Step 2 Create new workspace in catkin_ws
:::info
sudo rosdep init
rosdep update
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
:::
如果上面這條有error的話就改成:
:::info
rosdep update --include-eol-distros
rosdep install --from-paths src --ignore-src -r -y
:::
:warning: sudo rosdep init 有可能會有error,通常是因為在下載ros時已經執行過可以不用理會
Step3 pull abseil-cpp:
:::info
src/cartographer/scripts/install_abseil.sh
:::
:warning: 如果有跳conflict version error就執行以下這段把舊的版本刪掉
:::info
sudo apt-get remove ros-${ROS_DISTRO}-abseil-cpp
:::
Step 3 Ceres (求最佳化的函示庫)
:::info
http://ceres-solver.org/installation.html
:::
:warning: 記得用上面連結的Ceres solver2.1.0要不然無法CMake
Step 4 build & install
:::info
catkin_make_isolated --install --use-ninja
:::
### Cartographer compile rplidar
---
#### Step 1: Compile rplidar_ros from github and confirm
Clone rplidar_ros
:::info
git clone https://github.com/Slamtec/rplidar_ros.git
:::
Compile in workspace這邊可以先另外開一個workspace或在原本的catkin_ws cmake都可以,只是在catkin_ws可能要找一下compile特定package的指令
:::info
# compile
catkin_make
# Connect the radar , And give the equipment permission ( According to the actual situation , Select the device name )
sudo chmod 777 /dev/ttyUSB0
# Run demo( Remember source rplidar_ros Installation position of )
roslaunch rplidar_ros test_rplidar.launch
roslaunch rplidar_ros view_rplidar.launch
:::
確認可以使用過後,put both cartographer cartographer_ros rplidar_ros into new wokspace/src/
#### Step2: Build new launch file and lua file in cartographer_ros
##### launch file
:::info
cp demo_revo_lds.launch cartoForRplidar.launch #cope demo_revo_lds.launch form to new launch file
:::
cartoForRplidar.launch should like:
```
<launch>
<--!false Because we need to use real radar data , No simulation time /-->
<param name="/use_sim_time" value="false" />
<--! Be careful configuration_basename The following configuration file name , Be consistent with the actual lua Consistent file names /-->
<node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args=" -configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename rplidar.lua" output="log">
<--! Put the back of scan Modified to the laser released by the robot topic /-->
<remap from="scan" to="scan" />
</node>
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros" type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
<node name="rviz" pkg="rviz" type="rviz" required="true" args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
</launch>
```
:warning: <--! /-->的地方是註解代表下面一行可能有東西需要改
##### lua file
:::info
cp revo_lds.lua rplidar.lua #cope revo_lds.lua form to new lua file
:::
rplidar.lua should like:
:warning: 裡面只有tracking_frame 和 published_frame需要改
```
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map", --cartographer The global coordinate system used , It's best to keep the default , otherwise ROS Of Rviz Don't know other definitions , This makes it impossible to visualize the drawing process
-- Used to publish subgraphs , yes poses The parent frame of , Usually “map”
-- and odom In the beginning, it was an origin , But time accumulation produces cumulative errors to
tracking_frame = "base_link", -- Robot central coordinate system , from SLAM The coordinate system that the algorithm tracks
published_frame = "base_link", -- This frame It's for publishing poses The subframe of , and map_frame Corresponding
-- It is usually set to "base_link", Isn't that what "map->base_link"
odom_frame = "odom", --published_frame and map_frame Between the frames , For publishing ( Non closed loop )local SLAM result
provide_odom_frame = true, --
publish_frame_projected_to_2d = false, -- Whether to limit to pure 2d Postures
publish_tracked_pose = true, -- Release tracked_pose
use_pose_extrapolator = true,
use_odometry = false, -- Subscribe to odometer topics ,nav_msgs/Odometry
use_nav_sat = false, -- Whether to subscribe to sensor_msgs/NavSatFix
use_landmarks = false, -- Whether to subscribe to cartographer_ros_msgs/LandmarkList
num_laser_scans = 1, -- Number of laser scanning topics subscribed ,sensor_msgs/LaserScan
num_multi_echo_laser_scans = 0, -- Subscribe to the number of multi echo laser scanning topics ,sensor_msgs/MultiEchoLaserScan
num_subdivisions_per_laser_scan = 1, -- Each received ( Multiple echoes ) The number of point clouds divided by laser scanning
num_point_clouds = 0, -- Number of subscription point cloud topics ,sensor_msgs/PointCloud2
lookup_transform_timeout_sec = 0.2, -- Use tf2 Find the timeout seconds of the transform
submap_publish_period_sec = 0.3, -- Publish subgraph interval
pose_publish_period_sec = 5e-3, -- Release pose interval ,5e-3 namely 0.005s, namely 200Hz
trajectory_publish_period_sec = 30e-3, -- Publish track marker interval
rangefinder_sampling_ratio = 1., --range Message sampling frequency
odometry_sampling_ratio = 1., --odo Message sampling frequency
fixed_frame_pose_sampling_ratio = 1., --
imu_sampling_ratio = 1., --imu Message sampling frequency
landmarks_sampling_ratio = 1., --
}
MAP_BUILDER.use_trajectory_builder_2d = true -- Use 2D
--local slam To configure
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35 -- The maximum number of point cloud frames in a subgraph
TRAJECTORY_BUILDER_2D.min_range = 0.3 -- Filter point cloud in horizontal range Lower limit
TRAJECTORY_BUILDER_2D.max_range = 30. -- Filter point cloud in horizontal range ceiling
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1. -- The out of range is set to 1 rice
TRAJECTORY_BUILDER_2D.use_imu_data = false --imu Use or not
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true --【 real 】 No, imu, You may need to open this , At the same time, the front end will consume more resources , The reasons are as follows
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1 -- Maximum search range distance
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10. -- Maximum search range angle
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
--global slam To configure
POSE_GRAPH.optimization_problem.huber_scale = 1e2 -- Control the size of the error value Huber The bigger the factor , The greater the impact of the error value on the whole
POSE_GRAPH.optimize_every_n_nodes = 35 --【 real 】 Every time n Insert... Times , Optimize once ,n==0 when , That is, turn off global optimization
POSE_GRAPH.constraint_builder.min_score = 0.65 -- Greater than the minimum matching value be FastCorrelativeScanMatcher Found a good enough match
return options
```
#### Step3: Build new Rplidar_ros launch file
##### Modify test_rplidar file
```
<launch>
<node pkg="tf2_ros" type="static_transform_publisher" name="link1_broadcaster" args="0 0 0 0 0 0 1 base_link laser" />
<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="log">
<param name="serial_port" type="string" value="/dev/ttyUSB0"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
</node>
<node name="rplidarNodeClient" pkg="rplidar_ros" type="rplidarNodeClient" output="log">
</node>
</launch>
```
#### Step4: Run the test
:::info
catkin_make_isolated
# The first run cartographer
roslaunch cartographer_ros cartoForRplidar.launch
# And then run rplidar_ros
roslaunch rplidar_ros test_rplidar.launch
:::
### Cartographer compile mutiple rplidar
#### Successful V.1
---
##### Reminder
以下的版本是我在cartographer裡面直接修改的版本。我在github上有放另一個放在自己創見的[uc_car_v1](https://github.com/leokim0711092/uc_car/tree/master/uc_car_v1)pkg的版本。
:bulb: 記得在git clone之前要先用以下的指令創建一個pkg,再把檔案clone進去,要不然會catkin_make_isolated會找不到這個ros pkg。
:::info
catkin_create_pkg your-pkg-name std_msgs rospy roscpp
:::
##### Idea
這個版本的想法是直接採用,cartographer提供的概念,直接在lua file 將num_laser_scan改成2為出發點。
##### Step1: Lidar launch file
###### car_rpli.launch
這個launch的主要就是把在urdf改(可以到[URDF](/tLSTDADETMOFV4oF7rekGQ)的file-front_left_laser_link,back_right_laser_link放到node link_1broadcaster,link_2broadcaster這個transform_2裡面。
```
<launch>
<node pkg="tf2_ros" type="static_transform_publisher" name="link1_broadcaster" args="0 0 0 0 0 0 1 front_left_laser_link laser" />
<node name="lidar1" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/ttyUSB0"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
<remap from="scan" to="scan_1"/>
</node>
<node name="rplidarNodeClient1" pkg="rplidar_ros" type="rplidarNodeClient" output="log"/>
<node pkg="tf2_ros" type="static_transform_publisher" name="link2_broadcaster" args="0 0 0 0 0 0 back_right_laser_link laser1" />
<node name="lidar2" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/ttyUSB1"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser1"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
<remap from="scan" to="scan_2"/>
</node>
<node name="rplidarNodeClient2" pkg="rplidar_ros" type="rplidarNodeClient" output="log"/>
~
</launch>
```
##### Step2: Cartographer launch ,lua file, rviz
###### car_cart.launch
```
<launch>
<param name="/use_sim_time" value="false" />
<param name="robot_description" textfile="$(find cartographer_ros)/urdf/car.urdf" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args="
-configuration_directory
$(find cartographer_ros)/configuration_files -configuration_basename car.lua" output="log"/>
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros" type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
<node name="rviz" pkg="rviz" type="rviz" required="true" args="-d $(find cartographer_ros)/configuration_files/car.rviz" />
</launch>
```
:warning: 主要這個的重點就是加了urdf,jointstate,robot state這幾行。
###### car.lua
```
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "base_link",
published_frame = "base_link",
odom_frame = "odom",
provide_odom_frame = true,
publish_frame_projected_to_2d = true,
publish_tracked_pose = true,
use_pose_extrapolator = true,
use_odometry = false,
use_nav_sat = false,
use_landmarks = false,
num_laser_scans = 2,
num_multi_echo_laser_scans = 0,
num_subdivisions_per_laser_scan = 2,
num_point_clouds = 0,
lookup_transform_timeout_sec = 0.2,
submap_publish_period_sec = 0.3,
pose_publish_period_sec = 5e-3,
trajectory_publish_period_sec = 30e-3,
rangefinder_sampling_ratio = 1.,
odometry_sampling_ratio = 1.,
fixed_frame_pose_sampling_ratio = 1.,
imu_sampling_ratio = 1.,
landmarks_sampling_ratio = 1.,
}
MAP_BUILDER.use_trajectory_builder_2d = true
MAP_BUILDER.num_background_threads = 4
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 90
TRAJECTORY_BUILDER_2D.min_range = 0
TRAJECTORY_BUILDER_2D.max_range = 100
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 8.5
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 2
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 2
POSE_GRAPH.constraint_builder.min_score = 0.65
```
:warning: 主要的重點就是TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 2在有兩個laser時需要改成2,要不然沒辦法有map。
:bulb: TRAJECTORY_BUILDER_2D.submaps.num_range_data, MAP_BUILDER.num_background_threads可以對地圖生成做優化,可以了解一下。以下有別人做的整理可以參考。
[一些優化參數介紹](https://blog.csdn.net/zhzwang/article/details/107695535)
###### car.rviz
```
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Submaps1
- /PointCloud21
Splitter Ratio: 0.600671
Tree Height: 821
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.588679
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: PointCloud2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.03
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 100
Reference Frame: <Fixed Frame>
Value: true
- Class: rviz/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: true
base_link:
Value: true
horizontal_laser_link:
Value: true
imu_link:
Value: true
map:
Value: true
odom:
Value: true
vertical_laser_link:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
map:
odom:
base_link:
horizontal_laser_link:
{}
imu_link:
{}
vertical_laser_link:
{}
Update Interval: 0
Value: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
horizontal_laser_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
imu_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
vertical_laser_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: Submaps
Enabled: true
Name: Submaps
Submap query service: /submap_query
Topic: /submap_list
Tracking frame: base_link
Unreliable: false
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 0; 255; 0
Color Transformer: FlatColor
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 4096
Min Color: 0; 0; 0
Min Intensity: 0
Name: PointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.05
Style: Flat Squares
Topic: /scan_matched_points2
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /trajectory_node_list
Name: Trajectories
Namespaces:
"": true
Queue Size: 100
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /landmark_poses_list
Name: Landmark Poses
Namespaces:
"": true
Queue Size: 100
Value: true
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /constraint_list
Name: Constraints
Namespaces:
"": true
Queue Size: 100
Value: true
Enabled: true
Global Options:
Background Color: 100; 100; 100
Fixed Frame: map
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Topic: /initialpose
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Angle: 0
Class: rviz/TopDownOrtho
Enable Stereo Rendering:
Stereo Eye Separation: 0.06
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Name: Current View
Near Clip Distance: 0.01
Scale: 10
Target Frame: <Fixed Frame>
Value: TopDownOrtho (rviz)
X: 0
Y: 0
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1123
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd0000000400000000000001c5000003c0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000041000003c0000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003c0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000041000003c0000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000077e0000003efc0100000002fb0000000800540069006d006501000000000000077e000002f600fffffffb0000000800540069006d006501000000000000045000000000000000000000049e000003c000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1918
X: 0
```
:bulb: 主要是針對urdf的改動去做變更,但改動並沒有很多。
##### Step3: Launch rplidar_ros & cartographer pkg的node
###### rplidar_ros node
:::info
sudo chmod 777 /dev/ttyUSB0 /dev/ttyUSB1
roslaunch rplidar_ros car.launch
:::
:warning: 這部份有時候可能會有下面的這兩種error可以先嘗試重新launch幾遍,不行則換個差孔。


###### cartographer_ros node
:::info
roslaunch cartographer_ros car.launch
:::
:warning: 會出現Drop early points的warning這個warning是從cartographer/mapping/internal/range_data_collator.cc裡的CropAndMerge出來的下面這裡可以看到。

```
if (ranges.begin() < overlap_begin && !warned_for_dropped_points) {
LOG(WARNING) << "Dropped " << std::distance(ranges.begin(), overlap_begin)
<< " earlier points.";
warned_for_dropped_points = true;
}
```
這裡主要是把在前面的end還執行前,就開始的point丟掉。但不知道怎解。以下是解釋的示意圖跟對應的連結。
[Drop early point解釋](https://chargerkong.github.io/2021/11/06/1106%E7%82%B9%E4%BA%91%E6%97%B6%E9%97%B4%E5%90%8C%E6%AD%A5/)

###### check rqt_graph rqt_tf_tree
:::info
rosrun rqt_tf_tree rqt_tf_tree
rosrun rqt_graph rqt_graph
:::
> rqt_tf_tree

> rqt_graph

###### Map result

#### Successful V.2
---
##### idea
這個的想法就是用ira_laser_tools把data merge出來後再送進去cartographer mapping,只是後面的結果變得跟version 1很像,因為把num_laser_scan改成2了,所以這個算是跟第一個一樣。
##### Reminder
以下的版本是我在cartographer裡面直接修改的版本。我在github上有放另一個放在自己創見的[uc_car_v2](https://github.com/leokim0711092/uc_car/tree/master/uc_car_v2)pkg的版本。
:bulb: 記得在git clone之前要先用以下的指令創建一個pkg,再把檔案clone進去,要不然會catkin_make_isolated會找不到這個ros pkg。
:::info
catkin_create_pkg your-pkg-name std_msgs rospy roscpp
:::
###### check rqt_graph rqt_tf_tree
:::info
rosrun rqt_tf_tree rqt_tf_tree
rosrun rqt_graph rqt_graph
:::
> rqt_tf_tree

:bulb: 可以看到這裡面好像多了很多的東西不過這個是在urdf檔案裡面改的,第一個版本也一樣可以換成這個urdf,如果換過來應該也會長一樣。
> rqt_graph

###### Map result

:warning: 這個版本一樣會出現Drop early point的warning,這個版本其實跟第一個只有插在一個地方多一點點東西而已可以思考一下。不過實際上應該不會有太大的改變或幫助。
#### Successful V.3
---
##### idea
這個就是ira_laer_tools merge成一個data送進cartographer的方法,只是用起來好像mapping有點慢,感覺可以調一下可以影響mapping速度的參數試試。只是我之前好像都失敗了。
##### Reminder
以下的版本是我在cartographer裡面直接修改的版本。我在github上有放另一個放在自己創見的[uc_car_v3](https://github.com/leokim0711092/uc_car/tree/master/uc_car_v3)pkg的版本。
:bulb: 記得在git clone之前要先用以下的指令創建一個pkg,再把檔案clone進去,要不然會catkin_make_isolated會找不到這個ros pkg。
:::info
catkin_create_pkg your-pkg-name std_msgs rospy roscpp
:::
##### check rqt_graph rqt_tf_tree
:::info
rosrun rqt_tf_tree rqt_tf_tree
rosrun rqt_graph rqt_graph
:::
> rqt_tf_tree

> rqt_graph

#### Failed version
---
這個version的主體想法就是從lua file去改動把num_laser_scan變成兩個,然後去生成在rplidar裡的launch file。這邊launch file 的想法,就是要建立兩個node,把lidar1的scan_1跟lidar2的scan_2傳進cartographer裡。然後這個方法會失敗,我感覺起來是在namespace裡的節點好像無法把topic給cartographer的節點subscribe,我從rqt_graph看到的是這樣,不過可以學一下如何創namespace跟寫名字一樣的節點。
##### Step1: Confirm two lidar can use
:::info
ls /dev/ttyUSB*
:::
result: 
:warning: 有可能遇到下面這種error,這個是代表可能有硬體的東西不能用,像我則是買錯線要買micro USB轉USB

##### Step2: Build rplidar launch file
:bulb: 下面會建立兩個launch file在rplidar_ros裡面分別是- two_lidars.launch跟rplidar_arg.launch,two_lidars.launch是用來定義兩種namespace lidar0 and lidar1,並且把serial port 定義好。rplidar_arg.launch其實就是平常會使用的rplidar.launch的定義,只是多了一個default。
###### Build two_lidars.launch
```
<launch>
<include ns="lidar0" file="$(find rplidar_ros)/launch/rplidar_arg.launch">
<arg name="serial_port" value="/dev/ttyUSB0"/>
</include>
<include ns="lidar1" file="$(find rplidar_ros)/launch/rplidar_arg.launch">
<arg name="serial_port" value="/dev/ttyUSB1"/>
</include>
</launch>
```
:warning: 有遇到error是忘記把$(find your_ros_pkg)改成 $(find rplidar_ros)
###### Build rplidar_arg.launch
```
<launch>
<node pkg="tf2_ros" type="static_transform_publisher" name="link1_broadcaster" args="0 0 0 0 0 0 1 base_link laser" />
<arg name="serial_port" default="/dev/ttyUSB0"/>
<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="log">
<param name="serial_port" type="string" value="$(arg serial_port)"/>
<param name="serial_baudrate" type="int" value="115200"/><!--A1/A2 -->
<!--param name="serial_baudrate" type="int" value="256000"--><!--A3 -->
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
</node>
<node name="rplidarNodeClient" pkg="rplidar_ros" type="rplidarNodeClient" output="log">
</node>
</launch>
```
#### Step3: BUild cartographer_ros lua file and launch file
##### Build lua file
:warning: <arg name="serial_port" default="/dev/ttyUSB0"/>記得要加,default項,要不然會有error。
#### Resource
:::info
[Cartographer ROS](https://google-cartographer-ros.readthedocs.io/en/latest/index.html)
[Cartographer process in Noetic and connect to Foxy](https://chowdera.com/2022/04/202204010216564342.html#3_cartographer_37)
[Mutilple lidar launch file](https://answers.ros.org/question/320377/using-multiple-rplidar-on-a-single-system/)
[Mutilple lidar in one file](https://answers.ros.org/question/207222/how-to-connect-two-rplidars-on-one-computer/)
:::
### Cartographer compile imu
---
可以先看[imu](/QOfCKvgeRxuQIR646iOz_w)的筆記,再開始這個環節。
#### idea
這個是把前面測試過得imu加進去與兩個rplidar結合防止在mapping的時候車子無法定位,如果沒有imu的話很有可能車子會亂飛。在urdf的地方也與之前不一樣新增了imu_link這個link。
:warning: 這個有一個小問題就是在地圖上的車子的方向好像不太對,可以想一下怎摸改,我沒想出來。
#### Reminder
以下的版本是我在cartographer裡面直接修改的版本。我在github上有放另一個放在自己創見的[uc_car_rplis_imu](https://github.com/leokim0711092/uc_car/tree/master/uc_car_rplis_imu)pkg的版本。
:bulb: 記得在git clone之前要先用以下的指令創建一個pkg,再把檔案clone進去,要不然會catkin_make_isolated會找不到這個ros pkg。
:::info
catkin_create_pkg your-pkg-name std_msgs rospy roscpp
:::
#### Detail for slam file
##### Step1: revise urdf
增加imulink的部份,並且把imu_link跟base_link joint起來。
##### Step2: revise imu source python file
因為imu從gitbee下載下來的source code(名字叫做:hfi_a9_ros.py)設定的frame id 為base_link,必須把它改成imu_link(跟在urdf裡的名字一樣)才能在lua file改動。
##### Step3: revise lua file
1. 把traking frame從base_link改成imu_link(在urdf跟source python檔裡的名字要一樣)
2. 把imu有關的參數打開
:::info
TRAJECTORY_BUILDER_2D.use_imu_data = true
TRAJECTORY_BUILDER_2D.imu_gravity_time_constant=10.0
:::
##### Step4: add imu to rplis launch file
這裡必須把imu加到之前驅動光達的file裡,然後修改一下pkg的名字,對應的tf轉換座標,最後要把topic的名字remap成從原本原廠設定的handfree/imu換成imu。
##### Bonus
在這個imu+rpli的pkg裡,我把lua file的兩個參數做調整, 之前常常會發現把num_subdivisions_per_laser_scan設定為2時(調整為2跟1最大的差別是地圖建構的速度),地圖很容易會有發散的問題,也就是地圖上出現很多條一樣的路(常理來說應該只有一條),但當我把POSE_GRAPH.optimize_every_n_nodes 這個參數設定為0時,發散的問題就減少很多,這個參數好像是用在local map使用的就是在當地建地圖時,應該要把這個參數設定為0才是對的,可以深入了解並做補充。
#### check rqt_graph rqt_tf_tree
:::info
rosrun rqt_tf_tree rqt_tf_tree
rosrun rqt_graph rqt_graph
:::
> rqt_tf_tree

> rqt_graph

#### result

### Cartographer idea for further revision
1. Odometry: We can add wheel encoder for odometry input

Here is some info for further revision:
https://google-cartographer-ros.readthedocs.io/en/latest/going_further.html
## SLAMCORE (camera?)
https://docs.slamcore.com/navstack-integration.html
## resource
Some course about slam before 2016
https://github.com/kanster/awesome-slam#contributing
## Reference
1. [[ROS#10]Hector SLAM教學 ](https://ithelp.ithome.com.tw/articles/10220757)