ラズパイでSLAMによる地図作成(YDLidar X2, cartographer, ROS2, ラズパイ1台で完結)

このサイトでは, ラズパイ5を使って, SLAMによる地図作成を行います. ただし, WSL上のUbuntu OSからsshにて, 操作を行っています. 最後に, GPIOの操作方法も示しています.
※ Ubuntu OSの入ったPCを別途用意する必要はありません.
本サイトの全体的な流れを以下に示します.
- ROS2のインストール
- ROS2とlidarセンサーの接続
- cartographerによる地図作成
- ROS2を使ったGPIO操作(モーター)
使用機器
- ラズパイ5 8GB(Ubuntu 24.04.2 LTS)
- YDLidar X2(秋月電子)
ssh方法
普通にsshしても, ラズパイ上で表示されるウィンドウが, WSL側で表示されないために, -Xを使います. ただし, user_name, ip_addrは, ラズパイのものを使用してください($ip a).
sudo ssh -X user_name@ip_addr
ROS2(Jazzy)のインストール
ROS2のインストールにはcolconを使用します.
Colconのインストール
以下のコマンドでcolconをインストールできます.
sudo apt update
sudo apt install curl gnupg lsb-release
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo tee /etc/apt/trusted.gpg.d/ros.asc
sudo sh -c 'echo "deb [arch=$(dpkg --print-architecture)] http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" > /etc/apt/sources.list.d/ros2.list'
sudo apt update
sudo apt install python3-colcon-common-extensions
参考サイト
https://qiita.com/NeK/items/4ce04a2aa2b5eae3488b
ROS2のインストール
ROS2をインストールするために, 以下のコマンドを実行してください.
# ros2のインストール
sudo apt install ~nros-jazzy-rqt* # 10分程かかります
sudo apt install python3-pip
sudo apt update
sudo add-apt-repository universe
sudo apt update && sudo apt install curl -y
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
sudo apt update
sudo apt install ros-jazzy-desktop # 5分以上かかります
sudo apt update && sudo apt install ros-dev-tools
echo "source /opt/ros/jazzy/setup.bash" >> ~/.bashrc
source ~/.bashrc
sudo rosdep init
rosdep update
# 作業フォルダの作成
cd ~
mkdir -p catkin_ws/src
cd catkin_ws
colcon build
echo "source ~/catkin_ws/install/setup.bash" >> ~/.bashrc
参考サイト
https://wwwms.meijo-u.ac.jp/kohara/technicalreport/ubuntu24-04-ros2-jazzy
YDLidarとROS2の接続
YDLidarの接続を確認するために, 以下のコマンドを実行してください.
sudo apt install cmake pkg-config
sudo apt-get install swig
cd ~
git clone https://github.com/YDLIDAR/YDLidar-SDK.git
mkdir YDLidar-SDK/build
cd YDLidar-SDK/build
cmake ..
make
sudo make install
cd ~/YDLidar-SDK
sudo apt install python3-venv
python3 -m venv venv
source venv/bin/activate
pip install .
deactivate
sudo chmod 777 /dev/ttyUSB0
cd ~/YDLidar-SDK/build
./tri_test # lidarの接続テスト実行
Baudrate: 0, yesを選択.
以下のように, ログが出力できればOK.
Scan received [259] points scanFreq [11.50]
Scan received [259] points scanFreq [11.50]
Scan received [259] points scanFreq [11.50]
Scan received [259] points scanFreq [11.50]
...
次は, /catkin_wsで作業を行っていきます.
以下のコマンドでパッケージをインストールしてください.
cd ~/catkin_ws/src
git clone https://github.com/YDLIDAR/ydlidar_ros2_driver.git
以下のファイルの, 変数を宣言している全ての箇所で,
~/catkin_ws/src/ydlidar_ros2_driver/src/ydlidar_ros2_driver_node.cpp
以下のように, 変数の型を加えてください.
※ 後々, 変数の型でエラーが出たらこのファイルを疑いましょう
node->declare_parameter("ignore_array");
→ node->declare_parameter<std::string>("ignore_array");
変更方法
文字型: <std::string>
整数型: <std::int16_t>
小数型: <std::float_t>
論理型: <bool>
以下のコマンドを実行してください.
cd ~/catkin_ws
colcon build --symlink-install
警告はたくさん出ますが, 以下のように出力されていればOK!
Finished <<< ydlidar_ros2_driver [8.85s]
Summary: 1 package finished [9.06s]
1 package had stderr output: ydlidar_ros2_driver
以下のファイルをYDLidar X2用に変更.
~/catkin_ws/src/ydlidar_ros2_driver/params/ydlidar.yaml
ファイル内容
ydlidar_ros2_driver_node:
ros__parameters:
port: /dev/ttyUSB0
frame_id: laser_frame
ignore_array: ""
baudrate: 115200
lidar_type: 1
device_type: 0
sample_rate: 3
intensity_bit: 0
abnormal_check_count: 4
fixed_resolution: true
reversion: false
inverted: true
auto_reconnect: true
isSingleChannel: true
intensity: false
support_motor_dtr: true
angle_max: 180.0
angle_min: -180.0
range_max: 12.0
range_min: 0.01
frequency: 10.0
invalid_range_is_inf: false
m1_mode: 1
m2_mode: 1
m3_mode: 1
以下のファイルを追加.
~/catkin_ws/src/ydlidar_ros2_driver/launch/ydlidar_launch_view.py
ydlidar_launch_view.pyファイル内容
# !/usr/bin/python3
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import LifecycleNode
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch.actions import LogInfo
import lifecycle_msgs.msg
import os
def generate_launch_description():
share_dir = get_package_share_directory('ydlidar_ros2_driver')
rviz_config_file = os.path.join(share_dir, 'config','ydlidar.rviz')
parameter_file = LaunchConfiguration('params_file')
node_name = 'ydlidar_ros2_driver_node'
params_declare = DeclareLaunchArgument('params_file',
default_value=os.path.join(
share_dir, 'params', 'ydlidar.yaml'),
description='FPath to the ROS2 parameters file to use.')
driver_node = Node(package='ydlidar_ros2_driver',
executable='ydlidar_ros2_driver_node',
name='ydlidar_ros2_driver_node',
output='screen',
emulate_tty=True,
parameters=[parameter_file],
#node_namespace='/',
)
tf2_node = Node(package='tf2_ros',
executable='static_transform_publisher',
name='static_tf_pub_laser',
arguments=['0', '0', '0.02','0', '0', '0', '1','base_link','laser_frame'],
)
rviz2_node = Node(package='rviz2',
executable='rviz2',
name='rviz2',
arguments=['-d', rviz_config_file],
)
return LaunchDescription([
params_declare,
driver_node,
tf2_node,
rviz2_node,
])
以下のコマンドを実行
sudo chmod 777 /dev/ttyUSB0
source ~/catkin_ws/install/setup.bash
ros2 launch ydlidar_ros2_driver ydlidar_launch_view.py
ここで以下のように赤い点々がたくさん表示されていればOK!(少し時間がかかります)

ちなみに成功した場合のログは以下のように表示されています.
変数の型でエラーが出る場合は, ~/catkin_ws/src/ydlidar_ros2_driver/src/ydlidar_ros2_driver_node.cppが怪しいです!
修正したら, colcon build –symlink-install, source ~/catkin_ws/install/setup.bashも実行してください.
参考サイト
https://qiita.com/Yuya-Shimizu/items/c516b076ecc15864c0c5
https://qiita.com/porizou1/items/57edeeda15bbec76a462
cartographerの操作(SLAM)
以下のコマンドでcartographerをインストールしてください.
cd ~/catkin_ws
source ./install/setup.bash
echo "source ~/catkin_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-$ROS_DISTRO-cartographer-ros
次に, 以下のファイルを
~/catkin_ws/src/ydlidar_ros2_driver/launch/ydlidar_cartographer.launch.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='occupancy_grid_node',
parameters=[{'use_sim_time': use_sim_time}],
arguments=['-resolution', resolution, '-publish_period_sec', publish_period_sec])
])
以下のファイルを
~/catkin_ws/src/ydlidar_ros2_driver/config/ydlidar_cartographer.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.
TRAJECTORY_BUILDER_2D.max_range = 10.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 5.
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = false
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
以下のファイルのファイル名を
~/catkin_ws/src/ydlidar_ros2_driver/config/ydlidar.rviz
以下に変更し, (変更コマンド: mv ~/catkin_ws/src/ydlidar_ros2_driver/config/ydlidar.rviz ~/catkin_ws/src/ydlidar_ros2_driver/config/ydlidar_cartographer.rviz)
~/catkin_ws/src/ydlidar_ros2_driver/config/ydlidar_cartographer.rviz
ydlidar_cartographer.rvizファイル内で, Class: rviz_default_plugins/TFの次(Value: trueとEnabled: trueの間)に以下を追加
- Class: rviz_default_plugins/Odometry
Covariance:
Orientation:
Alpha: 0.5
Color: 255; 255; 127
Color Style: Unique
Frame: Local
Offset: 1
Scale: 1
Value: true
Position:
Alpha: 0.300
Color: 204; 51; 204
Scale: 1
Value: true
Value: False
Enabled: true
Keep: 1
Name: Odometry
Position Tolerance: 0.100
Angle Tolerance: 0.100
Shape:
Color: 255; 25; 0
Alpha: 1
Axes Length: 0.4
Axes Radius: 0.10
Shaft Length: 0.4
Shaft Radius: 0.05
Head Length: 0.300
Head Radius: 0.100
Value: Arrow
Topic: /odom_rf2o
Unreliable: true
Value: true
- Class: rviz_default_plugins/Map
Color Scheme: map
Draw Behind: false
Enabled: true
Name: Map
Topic: /map
Unreliable: true
Use Timestamp: false
Value: true
以下のファイルを,
~/catkin_ws/src/ydlidar_ros2_driver/launch/ydlidar_launch.py
以下に変更,
#!/usr/bin/python3
# Copyright 2020, EAIBOT
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import LifecycleNode
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch.actions import LogInfo
import lifecycle_msgs.msg
import os
def generate_launch_description():
share_dir = get_package_share_directory('ydlidar_ros2_driver')
parameter_file = LaunchConfiguration('params_file')
node_name = 'ydlidar_ros2_driver_node'
params_declare = DeclareLaunchArgument('params_file',
default_value=os.path.join(
share_dir, 'params', 'ydlidar.yaml'),
description='FPath to the ROS2 parameters file to use.')
driver_node = LifecycleNode(package='ydlidar_ros2_driver',
executable='ydlidar_ros2_driver_node',
name='ydlidar_ros2_driver_node',
output='screen',
emulate_tty=True,
parameters=[parameter_file],
namespace='/',
)
tf2_node = Node(package='tf2_ros',
executable='static_transform_publisher',
name='static_tf_pub_laser',
arguments=['0', '0', '0.02','0', '0', '0', '1','base_link','laser_frame'],
)
return LaunchDescription([
params_declare,
driver_node,
tf2_node,
])
以下のコマンドを2つのウィンドウに分けて, 実行してください.
※新たにウィンドウを作成する場合, ~/catkin_wsで, colcon buildを実行してください.
ros2 launch ydlidar_ros2_driver ydlidar_launch.py
ros2 launch ydlidar_ros2_driver ydlidar_cartographer.launch.py
以下のように地図が作成できればOK

参考サイト
https://zenn.dev/tasada038/articles/c4fff08deae9dd
以上までは, 実行可能かどうかチェックしていますが, ここから先はチェックしていないことを覚悟してください.
コントローラを使用したGPIO操作
ラズパイ5で, GPIOを操作するには, gpiozeroまたは, gpiochipを使用する必要がありますが, ここでは, gpiozeroを使用します.
まずパッケージを作成していきます.
ここでは, パッケージ名をgpioとしていますが任意で変更可能です.
cd ~/catkin_ws/src
ros2 pkg create gpio
次に, 実行するプログラムを配置していきます. フォルダ名およびファイル名をここでは, /code, program.pyとしていますが任意で変更可能です.
cd gpio
mkdir code
cd code
touch __init__.py
vim program.py
program.pyの中身を以下に示します.
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Joy
from gpiozero import Motor
class JoySubRaspiMove(Node):
def __init__(self):
super().__init__('joy_sub_raspi_move')
self.get_logger().info("joy_sub_raspi_move node started")
# モータ1の設定 (GPIO23: 前進, GPIO18: 後退)
self.motor1 = Motor(forward=23, backward=18)
# モータ2の設定 (GPIO24: 前進, GPIO13: 後退)
self.motor2 = Motor(forward=24, backward=13)
# 初期状態で停止
self.motor1.stop()
self.motor2.stop()
# ジョイスティックの購読
self.create_subscription(Joy, 'joy', self.callback, 20)
# 前進中のフラグ
self.is_moving_forward = False
self.speed_left = 1.0
self.speed_right = 0.9
def callback(self, joy_msg):
axes = [round(joy_msg.axes[0]), round(joy_msg.axes[1])]
buttonsA = int(joy_msg.buttons[0])
buttonsB = int(joy_msg.buttons[1])
self.get_logger().info(f"Axes: {axes}, Button A: {buttonsA}, Button B: {buttonsB}")
# 前進
if axes == [0, 1]: # 前進ボタンが押された
self.get_logger().info("Moving forward")
self.motor1.forward(self.speed_left)
self.motor2.forward(self.speed_right)
self.is_moving_forward = True # 前進中フラグを立てる
# 後退
elif axes == [0, -1]:
self.get_logger().info("Moving backward")
self.motor1.backward(self.speed_left)
self.motor2.backward(self.speed_right)
self.is_moving_forward = False # 後退の場合は前進フラグを解除
elif axes == [-1, 1]:
self.get_logger().info("Moving backward")
self.motor1.backward(self.speed_left)
self.motor2.backward(self.speed_right - 0.2)
self.is_moving_forward = False # 後退の場合は前進フラグを解除
elif axes == [1, 1]:
self.get_logger().info("Moving backward")
self.motor1.backward(self.speed_left - 0.2)
self.motor2.backward(self.speed_right)
self.is_moving_forward = False # 後退の場合は前進フラグを解除
elif axes == [-1, -1]:
self.get_logger().info("Moving backward")
self.motor1.backward(self.speed_left)
self.motor2.backward(self.speed_right - 0.2)
self.is_moving_forward = False # 後退の場合は前進フラグを解除
elif axes == [1, -1]:
self.get_logger().info("Moving backward")
self.motor1.backward(self.speed_left - 0.2)
self.motor2.backward(self.speed_right)
self.is_moving_forward = False # 後退の場合は前進フラグを解除
# 停止
elif axes == [0, 0]:
self.get_logger().info("Stopping")
self.motor1.stop()
self.motor2.stop()
self.is_moving_forward = False # 停止時は前進フラグを解除
def main(args=None):
rclpy.init(args=args)
node = JoySubRaspiMove()
try:
rclpy.spin(node)
except KeyboardInterrupt:
node.get_logger().info("Shutting down gracefully...")
finally:
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
以下のコマンドを実行.
cd ..
vim package.xml # (~/ydlidar_ros2_ws/src/gpio/package.xml)
package.xmlをpythonで実行するために以下のように変更を加えてください.
name=>gpioに変更
export=>build_type=>ament_pythonに変更
test_dependの2つ =>rclpy, std_msgsに変更
変更結果を以下に示す.
<package format="3">
<name>gpio</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="root@todo.todo">root</maintainer>
<license>TODO: License declaration</license>
<test_depend>rclpy</test_depend>
<test_depend>std_msgs</test_depend>
<export>
<build_type>ament_python</build_type>
</export>
</package>
以下のコマンドを実行してください.
rm CMakeLists.txt # (~/ydlidar_ros2_ws/src/gpio/CMakeLists.txt)
vim setup.py # (~/ydlidar_ros2_ws/src/gpio/setup.py)
setup.pyに以下の内容を書き込んでください.
from setuptools import setup
package_name = 'gpio' # 注意(パッケージ名)
setup(
name=package_name,
version='0.0.0',
packages=[],
py_modules=[
'code.gpio', # 注意(実行するプログラムディレクトリ.実行するファイル名)
],
install_requires=['setuptools'],
zip_safe=True,
author='root',
author_email="root@todo.todo",
maintainer='root',
maintainer_email="root@todo.todo",
keywords=['ROS', 'ROS2'],
classifiers=[
'Intended Audience :: Developers',
'License :: OSI Approved :: Apache Software License',
'Programming Language :: Python',
'Topic :: Software Development',
],
description='TODO: Package description.',
license='Apache License, Version 2.0',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'my_gpio= code.gpio:main', # 注意(実行するプログラムディレクトリ.実行するファイル名:実行する関数名)my_gpioはプログラムを実行する際に使用
],
},
)
setup.cfg(~/ydlidar_ros2_ws/src/gpio/setup.cfg)に以下の内容を加えてください.ここで, gpioにはパッケージ名を記入してください
[develop]
script-dir=$base/lib/gpio
[install]
install-scripts=$base/lib/gpio
ファイルの変更は終了!
以下のコマンドを実行してください.
sudo apt update
sudo apt install ros-noetic-joy #コントローラを使用するパッケージをインストール
sudo chmod 777 /dev/ttyUSB0 # lidarセンサーに権限を付与
sudo chmod 666 /dev/gpiochip0 # /dev/gpiochipをプログラムで使用する場合
以下の4つのコマンドをそれぞれ別のウィンドウで実行してください.
ros2 run joy joy_node
ros2 run gpio my_gpio
ros2 launch ydlidar_ros2_driver ydlidar_launch.py
ros2 launch ydlidar_ros2_driver ydlidar_cartographer.launch.py
コントローラを動かしてみて, 反応すればOK!
参考サイト
https://qiita.com/inomu/items/5bd47b4d223434d57615
まとめ
筆者はここに行きつくまでに, 以下の苦労がありました.
- ROSをインストールするために, ラズパイ5へのUbuntu 20.04, 18.04のインストールを試みる
- 1.が不可能だと悟り, ラズパイ上のdockerでUbuntu 20.04をインストールしてROSのダウンロードを行う
- ROSをインストールすることは出来たが, ydlidarの結果をrvizで表示することができなかったため, ROS2の使用を決意
ROS2を使用するとすぐに実行でき, もう誰にもこんな経験をしてほしくないとこのサイトを書いてみました. 事細かに詳細を書いているつもりです.
皆さんの役に立てることを願います.
参考文献
https://qiita.com/NeK/items/4ce04a2aa2b5eae3488b
https://wwwms.meijo-u.ac.jp/kohara/technicalreport/ubuntu24-04-ros2-jazzy
https://qiita.com/Yuya-Shimizu/items/c516b076ecc15864c0c5
https://qiita.com/porizou1/items/57edeeda15bbec76a462