ros2をいれます
(humble , ubuntu22.04)
```
sudo apt install cmake pkg-config
sudo apt-get install python3 swig
sudo apt-get install python3-pip
mkdir ~/lidar_ws
cd ~/lidar_ws
git clone https://github.com/YDLIDAR/YDLidar-SDK.git
mkdir YDLidar-SDK/build
cd YDLidar-SDK/build
cmake ..
make
sudo make install
cd ../
pip3 install .
cd ~/lidar_ws
mkdir -p ros2_ws/src
cd ros2_ws/src
git clone -b humble https://github.com/YDLIDAR/ydlidar_ros2_driver.git
cd ../
colcon build --symlink-install
source install/setup.bash
echo "source ~/lidar_ws/ros2_ws/install/setup.bash" >> ~/.bashrc
source ~/.bashrc
chmod 0777 src/ydlidar_ros2_driver/startup/*
sudo sh src/ydlidar_ros2_driver/startup/initenv.sh
sudo apt install ros-humble-cartographer
sudo apt install ros-humble-cartographer-rviz
```
これでydlidarとcartographerのインストールが終わります
実際にSLAMする前にセンサーのテストをしてみましょう
ここではX4使う想定で行きます。
ファイルアプリを開いて、lidar_ws/ros2_ws/src/ydlidar_ros2_driver/params へ移動します。
ydlidar.yamlを適当な名前(old.yaml等)に変更します。
X4.yamlをydlidar.yamlへ変更します。
もしportのところがusb担ってなかったら直します

これでX4が使えるようになりました。
ターミナルを2つ開いて、
```
sudo chmod 777 /dev/ttyUSB0
ros2 launch ydlidar_ros2_driver ydlidar_launch.py
```
と
```
rviz2
```
を起動してください。
rviz2の左下にあるaddから by topic で/scanを選択してください


topicの設定をbest effortにして、sizeやcolorをいじれば...


# やったーーーー!!!
# SLAMします。
そしたら細かい設定やパラメータの設定をしていきます。
lidar_ws/ros2_ws/src/ydlidar_ros2_driverへ移動します
launchないにydlidar_cartographer.launch.py
を作り、以下をコピペします。
```py
import launch
import launch.actions
import launch.substitutions
import launch_ros.actions
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration
from ament_index_python.packages import get_package_share_directory
from launch.actions import DeclareLaunchArgument
import os
def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time', default='false')
share_dir = get_package_share_directory('ydlidar_ros2_driver')
rviz_config_file = os.path.join(share_dir, 'config','ydlidar_cartographer.rviz')
cartographer_config_dir = LaunchConfiguration('cartographer_config_dir',
default=os.path.join(share_dir, 'config'))
configuration_basename = LaunchConfiguration('configuration_basename', default='ydlidar_cartographer.lua')
resolution = LaunchConfiguration('resolution', default='0.05')
publish_period_sec = LaunchConfiguration('publish_period_sec', default='1.0')
return LaunchDescription([
# Node(package='rviz2',
# executable='rviz2',
# name='rviz2',
# arguments=['-d', rviz_config_file],
# ),
Node(
## Configure the TF of the robot to the origin of the map coordinates
package='tf2_ros',
executable='static_transform_publisher',
output='screen',
arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'base_link', 'laser_frame']
),
Node(
## Configure the TF of the robot to the origin of the map coordinates
# map TF to odom TF
package='tf2_ros',
executable='static_transform_publisher',
namespace='',
output='screen',
arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'map', 'odom']
),
Node(
## Configure the TF of the robot to the origin of the map coordinates
# odom TF to base_footprint
package='tf2_ros',
executable='static_transform_publisher',
namespace='',
output='screen',
arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'odom', 'base_footprint']
),
Node(
package='cartographer_ros',
executable='cartographer_node',
output='log',
parameters=[{'use_sim_time': use_sim_time}],
arguments=['-configuration_directory', cartographer_config_dir, '-configuration_basename', configuration_basename],
remappings=[('odom','rs_t265/odom'),]
),
DeclareLaunchArgument(
'resolution',
default_value=resolution,
description='Resolution of a grid cell in the published occupancy grid'),
DeclareLaunchArgument(
'publish_period_sec',
default_value=publish_period_sec,
description='OccupancyGrid publishing period'),
Node(
package='cartographer_ros',
executable='cartographer_occupancy_grid_node',
name='cartographer_occupancy_grid_node',
parameters=[{'use_sim_time': use_sim_time}],
arguments=['-resolution', resolution, '-publish_period_sec', publish_period_sec])
])
```
次にconfig内にydlidar_cartographer.luaを...以下略
```lua
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "laser_frame",
published_frame = "laser_frame",
odom_frame = "odom",
provide_odom_frame = false,
publish_frame_projected_to_2d = false,
use_odometry = false,
use_nav_sat = false,
use_landmarks = false,
num_laser_scans = 1,
num_multi_echo_laser_scans = 0,
num_subdivisions_per_laser_scan = 1,
num_point_clouds = 0,
lookup_transform_timeout_sec = 0.2,
submap_publish_period_sec = 0.05,
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
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 12.0
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 5.
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
POSE_GRAPH.constraint_builder.min_score = 0.65
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7
POSE_GRAPH.optimization_problem.local_slam_pose_translation_weight = 1e5
POSE_GRAPH.optimization_problem.local_slam_pose_rotation_weight = 1e5
POSE_GRAPH.optimization_problem.odometry_translation_weight = 1e5
POSE_GRAPH.optimization_problem.odometry_rotation_weight = 1e5
POSE_GRAPH.optimization_problem.huber_scale = 1e3
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 10
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 40
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 120
TRAJECTORY_BUILDER_2D.motion_filter.max_distance_meters = 0.1
TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.2)
return options
```
これで設定完了です。
lidar_ws/ros2_wsをターミナルでひらいで
bs(colcon build;source install/setup.bash)
します
できたらterm3つ開いて、
```
ros2 launch ydlidar_ros2_driver ydlidar_launch.py
```
```
ros2 launch ydlidar_ros2_driver ydlidar_cartographer.launch.py
```
```
rviz2
```
rviz2で mapと