시뮬레이터 상의 2D LiDAR 시각화를 끄려면 아래 경로의 파일을 수정
→ ~/nav2_ws/src/neuronbot2/neuronbot2_gazebo/models/neuronbot2/model.sdf
...
<!-- 362번째 줄의 **visualize를 false로 변경** -->
<sensor name="rp_lidar_a1" type="ray">
<always_on>true</always_on>
**<visualize>false</visualize>**
<pose>0.0 0 0.02 0 0 0</pose>
<update_rate>5.5</update_rate>
<ray>
...
시뮬레이션 환경(bookstore)에 neuronbot2을 spawn
ros2 launch neuronbot2_gazebo neuronbot2_world.launch.py
사전에 만들어 놓은 지도를 불러오고 localization 활용하기 위해, neuronbot2_nav
패키지의 bringup_launch.py
파일을 수정
Path Planning 수행을 위한 아래 통합 런치 파일 시작
ros2 launch neuronbot2_nav bringup_launch.py use_sim_time:=true
지도에서 로봇의 초기 위치가 올바르지 않을 경우, 2D Pose Estimate
버튼을 클릭한 후 다음 시뮬레이터 상에서 로봇의 실제 위치에 해당하는 위치와 방향을 클릭
Rviz2의 2D Goal Pose
버튼으로 목적에 해당하는 위치와 방향을 클릭해 자율주행 결과 확인
/navigate_to_pose
액션 서버를 활용 (/clicked_point
토픽으로 지도 상 위치 정보 획득 및 활용)ros2 action send_goal /navigate_to_pose nav2_msgs/action/NavigateToPose "pose: {header: {frame_id: map}, pose: {position: {x: 1.52, y: 1.92, z: 0.0}, orientation:{x: 0.0, y: 0.0, z: 0, w: 1.0000000}}}"
/goal_pose
토픽을 활용 (/clicked_point
토픽으로 지도 상 위치 정보 획득 및 활용)ros2 topic pub -1 /goal_pose geometry_msgs/PoseStamped "{header: {stamp: {sec: 0}, frame_id: 'map'}, pose: {position: {x: 2.2, y: 0.0, z: 0.0}, orientation: {w: 1.0}}}"
/navigate_to_pose
액션 서버를 활용한 코드