2024. 11. 6. 16:29ㆍROS2/Nav2
센서 설정이다.
센서는 환경 지도를 작성하고 유지하고, 지도에서 로봇의 위치를 파악하고, 환경의 장애물을 확인하는 데 사용할 수 있는 정보를 얻는다.
일반적으로 사용되는 센서의 예로는 lidar, radar, RGB camera, depth camera, IMU, GPS 등이 있다.
이러한 센서의 메시지 형식을 표준화하고 공급업체 간의 보다 쉬운 상호 운용을 허용하기 위해 ROS는 일반적인 센서 인터페이스를 정의하는 sensor_msgs 패키지를 제공한다.
sensor_msgs를 제외하고 알아야 할 표준 인터페이스가 있다.
radar_msgs는 특정 radar 센서의 메시지를 정의하고 vision_msgs는 객체 탐지, 세분화 및 기타 머신 러닝 모델과 같은
컴퓨터 비전에서 사용되는 메시지를 정의한다. 이 패키지에서 지원하는 메시지를 몇 가지 예를 들면
vision_msgs/Classification2D, vision_msgs/Classification3D, vision_msgs/Detection2D, vision_msgs/Detection3D
등이 있다.
nav2와 같은 일반 소프트웨어 패키지는 이러한 표준화된 메시지를 읽고 센서 하드웨어와 독립적으로 작업을 수행할 수 있다.
Gazebo와 같은 시뮬레이션에도 마찬가지로 sensor_msgs 패키지에 따라 정보를 퍼블리시하는 센서 플러그인이 있다.
sensor_msgs/LaserScan
이 메시지는 평면 레이저 거리 측정기에서 단일 스캔을 나타낸다. 이 메시지는 slam_toolbox, nav2_amcl에서 위치 파악 및 매핑에 사용되거나 nav2_costmap_2d 인식에 사용된다.
sensor_msgs/PointCloud2
이 메시지는 3d 포인트 모음과 각 포인트에 대한 선택적 추가 정보를 포함한다. 이는 3d 라이더, 2d 라이더, 깊이 카메라 등에서 나올 수 있다.
sensor_msgs/Image
이는 RGB 또는 범위 값에 해당하는 RGB 또는 깊이 카메라의 센서 판독값을 나타낸다.
Gazebo를 사용하여 센서 시뮬레이션
이전에 만들었던 로봇에 센서를 부착해보겠다.
gazebo 플러그인을 사용하여 오도메트리 센서를 추가했던 것과 유사하게 gazebo 플러그인을 사용하여 라이더 센서와 깊이 카메라를 시뮬레이션 해보겠다.
실제 로봇으로 작업하는 경우 이러한 단계의 대부분은 URDF 프레임을 설정하는 데 여전히 필요하며 나중에 사용할 수 있도록 Gazebo 플러그인을 추가하는 것도 나쁘지 않다.
먼저 lidar 센서를 추가해보겠다. URDF파일 src/decription/sam_bot_description.urdf를 열고 </robot> 태그 앞에 다음 줄을 붙여넣는다.
<link name="lidar_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.125"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
</inertial>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.0508" length="0.055"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.0508" length="0.055"/>
</geometry>
</visual>
</link>
<joint name="lidar_joint" type="fixed">
<parent link="base_link"/>
<child link="lidar_link"/>
<origin xyz="0 0 0.12" rpy="0 0 0"/>
</joint>
<gazebo reference="lidar_link">
<sensor name="lidar" type="ray">
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1.000000</resolution>
<min_angle>0.000000</min_angle>
<max_angle>6.280000</max_angle>
</horizontal>
</scan>
<range>
<min>0.120000</min>
<max>3.5</max>
<resolution>0.015000</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="scan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>lidar_link</frame_name>
</plugin>
</sensor>
</gazebo>
다음으로 depth 카메라를 추가해보겠다.
<link name="camera_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.015 0.130 0.022"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.015 0.130 0.022"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.035"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
</inertial>
</link>
<joint name="camera_joint" type="fixed">
<parent link="base_link"/>
<child link="camera_link"/>
<origin xyz="0.215 0 0.05" rpy="0 0 0"/>
</joint>
<link name="camera_depth_frame"/>
<joint name="camera_depth_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
<parent link="camera_link"/>
<child link="camera_depth_frame"/>
</joint>
<gazebo reference="camera_link">
<sensor name="depth_camera" type="depth">
<visualize>true</visualize>
<update_rate>30.0</update_rate>
<camera name="camera">
<horizontal_fov>1.047198</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>3</far>
</clip>
</camera>
<plugin name="depth_camera_controller" filename="libgazebo_ros_camera.so">
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<frame_name>camera_depth_frame</frame_name>
<pointCloudCutoff>0.5</pointCloudCutoff>
<pointCloudCutoffMax>3.0</pointCloudCutoffMax>
<distortionK1>0</distortionK1>
<distortionK2>0</distortionK2>
<distortionK3>0</distortionK3>
<distortionT1>0</distortionT1>
<distortionT2>0</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>
실행 및 빌드를 해보겠다.
센서가 제대로 설정되었고 주변 환경에서 물체를 볼 수 있는지 확인하려면 물체가 있는 gazebo월드를 시작한다.
프로젝트 루트에 world라는 폴더를 만들고 내부에 my_world.sdf라는 이름의 파일을 만든다. 그런 다음 아래의 내용을 붙여 넣는다.
<sdf version='1.7'>
<world name='default'>
<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose>0 0 10 0 -0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
<spot>
<inner_angle>0</inner_angle>
<outer_angle>0</outer_angle>
<falloff>0</falloff>
</spot>
</light>
<model name='ground_plane'>
<static>1</static>
<link name='link'>
<collision name='collision'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
<torsional>
<ode/>
</torsional>
</friction>
<contact>
<ode/>
</contact>
<bounce/>
</surface>
<max_contacts>10</max_contacts>
</collision>
<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
</model>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type='adiabatic'/>
<physics type='ode'>
<max_step_size>0.001</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
</physics>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>1</shadows>
</scene>
<wind/>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>0</latitude_deg>
<longitude_deg>0</longitude_deg>
<elevation>0</elevation>
<heading_deg>0</heading_deg>
</spherical_coordinates>
<model name='unit_box'>
<pose>1.51271 -0.181418 0.5 0 -0 0</pose>
<link name='link'>
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
<pose>0 0 0 0 -0 0</pose>
</inertial>
<collision name='collision'>
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
</model>
<model name='unit_sphere'>
<pose>-1.89496 2.36764 0.5 0 -0 0</pose>
<link name='link'>
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
<pose>0 0 0 0 -0 0</pose>
</inertial>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='visual'>
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
</model>
<state world_name='default'>
<sim_time>0 0</sim_time>
<real_time>0 0</real_time>
<wall_time>1626668720 808592627</wall_time>
<iterations>0</iterations>
<model name='ground_plane'>
<pose>0 0 0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>0 0 0 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 0 0 0 -0 0</acceleration>
<wrench>0 0 0 0 -0 0</wrench>
</link>
</model>
<model name='unit_box'>
<pose>1.51272 -0.181418 0.499995 0 1e-05 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>1.51272 -0.181418 0.499995 0 1e-05 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0.010615 -0.006191 -9.78231 0.012424 0.021225 1.8e-05</acceleration>
<wrench>0.010615 -0.006191 -9.78231 0 -0 0</wrench>
</link>
</model>
<model name='unit_sphere'>
<pose>-0.725833 1.36206 0.5 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='link'>
<pose>-0.944955 1.09802 0.5 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 0 0 0 -0 0</acceleration>
<wrench>0 0 0 0 -0 0</wrench>
</link>
</model>
<light name='sun'>
<pose>0 0 10 0 -0 0</pose>
</light>
</state>
<gui fullscreen='0'>
<camera name='user_camera'>
<pose>3.17226 -5.10401 6.58845 0 0.739643 2.19219</pose>
<view_controller>orbit</view_controller>
<projection_type>perspective</projection_type>
</camera>
</gui>
</world>
</sdf>
launch 파일도 마찬가지로 수정한다. generate_launch_description():안에 아래 내용을 추가한다.
world_path=os.path.join(pkg_share, 'world/my_world.sdf')
launch.actions.ExecuteProcess(cmd=['gazebo', ... 에 아래와 같이 world경로를 추가한다.
launch.actions.ExecuteProcess(cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so', world_path], output='screen'),
CMakeLists.txt파일을 열고 install(DIRECTORY...)안에 디렉토리를 추가한다.
install(
DIRECTORY src launch rviz config world
DESTINATION share/${PROJECT_NAME}
)
이제 빌드하고 실행할 수 있다.
colcon build
. install/setup.bash
ros2 launch sam_bot_description display.launch.py
카메라와 라이다 센서가 부착되어있는 것을 볼 수 있다.
센서를 시각화하려면 add를 눌러 LaserScan과 image를 추가해주고 topic을 설정해주면 아래와 같은 결과가 나온다.
이제 센서가 설정된 로봇이 있으므로 얻은 센서 정보를 사용하여 환경 맵을 작성하고 맵에서 로봇의 위치를 파악할 수 있다.
slam_toolbox 패키지는 ros2를 사용하여 잠재적으로 방대한 맵에서 2D 동시 위치 파악 및 매핑을 위한 도구와 기능들이 있다.
또한 nav2에서 공식적으로 지원되는 slam 라이브러리 중 하나이며 로봇 설정에서 slam을 사용해야 하는 상황에서 이 패키지를 사용하는 것이 좋다.
localization은 nav2_amcl패키지를 통해 구현할 수도 있다. 이 패키지는 맵에서 로봇의 위치와 방향을 추정하는 Adaptive Monte Carlo Localization (AMCL) 을 구현한다
slam_toolbox, nav2_amcl 모두 레이저 스캔 센서의 정보를 사용하여 로봇의 환경을 인식할 수 있다. 따라서 레이저 스캔 센서 판독값에 엑세스할 수 있는지 확인하려면 메시지를 게시하는 올바른 토픽에 subscribe하고 있는지 확인해야한다.
costmap2D
costmap2d 패키지는 센서 정보를 사용하여 로봇의 환경을 점유 그리드 형태로 표현한다. 점유 그리드의 셀은 0~254사이의 비용 값을 저장하며, 이는 이러한 구역을 통과하는 데 드는 비용을 나타낸다. 비용 0은 셀이 비어 있음을 의미하고 비용 254는 최대로 점유되었음을 의미한다.
이러한 극단 사이의 값은 탐색 알고리즘에서 로봇을 잠재적 필드인 장애물에서 벗어나도록 조종하는데 사용된다.
nav2의 costmap은 nav2_costmap_2d 패키지를 통해 구현된다.
costmap 구현은 여러 레이어로 구성되고, 각 레이어는 셀의 전체 비용에 기여하는 특정 기능을 한다. 이 레이어들은 플러그인 기반으로 되어 있어서, 커스터마이징이나 새로운 레이어 추가도 가능하다. 주요 레이어와 기능은 아래와 같다:
- Static Layer (정적 레이어)
- 맵의 기본 레이어로, /map 토픽에 게시된 맵 데이터를 사용해 로봇이 참고할 지도를 설정한다. 보통 SLAM으로 생성된 맵 정보 같은 데이터를 포함한다.
- Obstacle Layer (장애물 레이어)
- 장애물을 포함하는 레이어로, LaserScan과 PointCloud2 메시지로부터 장애물 정보를 수집해 맵에 반영한다.
- Voxel Layer (복셀 레이어)
- 장애물 레이어와 비슷하지만, 3D 데이터를 처리할 수 있다. LaserScan과 PointCloud2 메시지를 모두 사용할 수 있고, 입체 장애물 정보 반영에 유리하다.
- Range Layer (범위 레이어)
- **초음파(Sonar)**와 적외선 센서에서 제공되는 정보를 포함해 근거리 탐지 기능을 추가할 수 있다.
- Inflation Layer (팽창 레이어)
- 장애물 주변에 추가 비용을 생성해 로봇이 장애물에 가까이 가지 않도록 한다. 로봇의 기하학적 크기를 고려해 장애물 근처에 유휴 공간을 추가하는 방식으로 경로 설정을 돕는다.
이 레이어들은 nav2_costmap_2d 패키지에서 설정 가능하며, 기본적인 레이어 구성 방법은 이후 설명한다.
아래 코드는 lidar 센서에서 제공하는 정보를 이용한 nav2_costmap_2d의 예제 configuration이다.
정적 레이어, 장애물 레이어, 복셀 레이어, 인플레이션 레이어를 사용하는 예시 구성이다.
우리는 장애물과 복셀레이어를 모두 lidar 센서에서 /scan 토픽에 publish한 LaserScan 메시지를 사용하도록 하였다.또 감지된 장애물이 비용 맵에 반영되는 방식을 정의하기 위한 몇 가지 기본 매개변수도 설정하였다.
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
publish_frequency: 1.0
global_frame: map
robot_base_frame: base_link
use_sim_time: True
robot_radius: 0.22
resolution: 0.05
track_unknown_space: false
rolling_window: false
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
raytrace_max_range: 3.0
raytrace_min_range: 0.0
obstacle_max_range: 2.5
obstacle_min_range: 0.0
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.55
always_send_full_costmap: True
local_costmap:
local_costmap:
ros__parameters:
update_frequency: 5.0
publish_frequency: 2.0
global_frame: odom
robot_base_frame: base_link
use_sim_time: True
rolling_window: true
width: 3
height: 3
resolution: 0.05
robot_radius: 0.22
plugins: ["voxel_layer", "inflation_layer"]
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.05
z_voxels: 16
max_obstacle_height: 2.0
mark_threshold: 0
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.55
always_send_full_costmap: True
자세히 보면 global_costmap과 local_costmap에 따로 매개변수를 설정한 것을 볼 수 있다.
global_costmap은 전체 맵에 대한 장기 계획에 주로 사용되고 local_costmap은 단기 계획 및 충돌 방지에 사용되므로
따로 설정한 것이다.
costmap 설정에서 사용하는 레이어는 plugins 매개변수에 정의되어 있고, 이 값들은 각 레이어에 매칭된 이름으로, 레이어별 파라미터 네임스페이스로도 활용된다. 주요 설정은 다음과 같다:
- global_costmap와 local_costmap에 레이어 목록 정의
- plugins에 레이어 이름을 리스트로 설정하며, 각 레이어는 네임스페이스로 사용된다. 각 네임스페이스에 plugin 파라미터를 포함해야 하고, 이 파라미터는 로드할 플러그인 종류를 지정한다.
- Static Layer (정적 레이어)
- map_subscribe_transient_local: True로 설정해 맵 토픽의 QoS 설정을 정의한다.
- map_topic: 구독할 맵 토픽을 지정하며, 기본값은 /map이다.
- Obstacle Layer (장애물 레이어)
- observation_sources: 감지 센서 소스 지정. 예를 들어, scan으로 설정하고, 이 소스에 대한 세부 파라미터를 설정한다.
- topic: 사용할 센서의 토픽을 지정하고, data_type으로 센서 유형을 정의한다. 설정된 경우, /scan 토픽을 통해 Lidar 센서의 LaserScan 메시지를 사용한다.
- Voxel Layer (복셀 레이어)
- LaserScan 또는 PointCloud2 데이터 유형을 모두 사용할 수 있다. 기본값은 LaserScan이지만, 두 센서를 조합해 사용할 수도 있다. 특히 물리적인 로봇 설정 시 유용하게 활용 가능하다.
이렇게 각 레이어의 세부 설정을 통해 다양한 센서와 QoS, 장애물 감지를 설정할 수 있다.
각 레이어 파라미터들에 대한 설명이다.
- Obstacle Layer Parameters
- max_obstacle_height: 센서의 최대 높이 값을 설정해, 이 높이 이하의 데이터만 점유 그리드에 반영된다.
- min_obstacle_height: 최소 높이를 설정하며, 설정하지 않으면 기본값은 0으로 된다.
- clearing: 장애물을 costmap에서 제거할지 여부를 설정하고, 제거 작업은 raytracing 방식으로 진행된다.
- raytrace_max_range와 raytrace_min_range: costmap에서 장애물을 제거할 최대 및 최소 거리 범위를 설정한다.
- marking: 삽입된 장애물이 costmap에 표시될지 여부를 설정한다.
- obstacle_max_range와 obstacle_min_range: costmap에 장애물을 표시할 최대 및 최소 거리 범위를 설정한다.
- Inflation Layer Parameters
- cost_scaling_factor: exponential decay factor를 설정해, 위험 장애물 주변의 부풀림 효과를 제어한다.
- inflation_radius: 장애물 주변에 부풀려지는 반경을 설정한다.
- Voxel Layer Parameters
- publish_voxel_map: 3D voxel 그리드를 퍼블리시할지 여부를 설정한다.
- z_resolution: 높이에서 voxel의 해상도를 설정한다.
- z_voxels: 각 컬럼에 들어가는 voxel의 수를 설정한다.
- mark_threshold: 점유 상태로 표시할 컬럼 내 최소 voxel 수를 설정한다.
- observation_sources: 센서 데이터 소스로 scan을 설정하며, scan의 세부 설정은 obstacle layer와 유사하게 구성한다.
- Range Layer (Optional)
- topics, input_sensor_type, clear_on_max_reading 등의 파라미터로 설정할 수 있다. input_sensor_type는 ALL, VARIABLE, FIXED 중 하나로 설정할 수 있으며, clear_on_max_reading은 최대 범위일 때 센서 데이터를 제거할지 여부를 설정한다.
빌드 및 실행을 하게 되면 아래 과정을 거치게 된다.
- Launching display.launch.py
- display.launch.py 파일을 실행하면 robot_state_publisher가 함께 실행되며, 이 노드는 URDF에 정의된 base_link => sensors 변환을 제공한다.
- 또한 Gazebo가 실행되어 물리 시뮬레이터로서 동작하고, differential drive plugin을 통해 odom => base_link 변환을 제공한다. 이 플러그인은 이전 가이드에서 sam_bot에 추가되었다.
- 마지막으로, RViz도 실행되어 로봇과 센서 정보를 시각화할 수 있게 된다.
- Launching slam_toolbox
- 이후 slam_toolbox를 실행해 /map 토픽에 지도를 퍼블리시하고, map => odom 변환을 제공한다. 이 map => odom 변환은 Nav2 시스템에서 요구되는 주요 항목 중 하나다.
- /map 토픽에 퍼블리시되는 메시지는 global_costmap의 static layer에 사용된다.
#terminal 1
colcon build
. install/setup.bash
ros2 launch sam_bot_description display.launch.py
sudo apt install ros-<ros2-distro>-slam-toolbox
#terminal 2
ros2 launch slam_toolbox online_async_launch.py
위와 같은 결과가 나옴
nav2 실행
sudo apt install ros-<ros2-distro>-navigation2
sudo apt install ros-<ros2-distro>-nav2-bringup
#Terminal 3
ros2 launch nav2_bringup navigation_launch.py use_sim_time:=True
#공식사이트에는 use_sim_time:=True가 빠져있는데 저게 없으면 global_costmap만 떴다
fixed frame을 map으로 바꿔주고 add를 눌러 map을 불러와서 topic을 global_costmap으로 바꿔주면 아래와 같은 결과가 나온다.
local_costmap을 선택하고 color schme를 costmap으로 설정하면 아래와 같은 결과가 나온다.
'ROS2 > Nav2' 카테고리의 다른 글
ROS2 nav2(6) (0) | 2024.11.07 |
---|---|
ROS2 nav2(4) (0) | 2024.11.06 |
ROS2 nav2(3) (0) | 2024.11.05 |
ROS2 nav2(2) 22.04 + humble (0) | 2024.11.05 |
ROS2 nav2 (0) | 2024.11.04 |