![見出し画像](https://assets.st-note.com/production/uploads/images/165295150/rectangle_large_type_2_1c79124a3c68aac2c62258e11cc6d7e2.png?width=1200)
ROS2 Jazzy 入門 (8) - Navigation
「SDF」で作ったシンプルな差動二輪ロボットで「SLAM」を実行して「地図生成」と「自己位置推定」し、「nav2」でナビゲーションを行い、「rviz2」で視覚化します。
・Ubuntu 24.04
・ROS2 Jazzy
・Gazebo Harmonic
前回
1. Nav2
「Nav2」(Navigation 2) は、ROS2向けのナビゲーションソフトウェアです。主にモバイルロボットが環境内を自律的に移動できるように設計されています。
2. Gazebo の起動
(1) launchファイルの作成。
「ROS2 Jazzy 入門 (6) - SLAM」の「launchファイル」から「teleop_twist_keyboard」と「rviz2」を削除します。
・run_simple_robot_nav2.py
from launch import LaunchDescription
from launch.actions import ExecuteProcess
def generate_launch_description():
return LaunchDescription([
# Gazeboの起動
ExecuteProcess(
cmd=['gz', 'sim', 'simple_robot_lidar.sdf'],
output='log',
log_cmd=True
),
# rviz2の起動
ExecuteProcess(
cmd=['rviz2'],
output='log',
log_cmd=True
),
# ブリッジの起動
ExecuteProcess(
cmd=[
'ros2', 'run', 'ros_gz_bridge', 'parameter_bridge',
'/cmd_vel@geometry_msgs/msg/Twist@gz.msgs.Twist'
],
output='log',
log_cmd=True
),
ExecuteProcess(
cmd=[
'ros2', 'run', 'ros_gz_bridge', 'parameter_bridge',
'/lidar@sensor_msgs/msg/LaserScan@gz.msgs.LaserScan'
],
output='log',
log_cmd=True
),
ExecuteProcess(
cmd=[
'ros2', 'run', 'ros_gz_bridge', 'parameter_bridge',
'/model/simple_robot/tf@tf2_msgs/msg/TFMessage[gz.msgs.Pose_V',
'--ros-args', '-r', '/model/simple_robot/tf:=/tf'
],
output='log',
log_cmd=True
),
ExecuteProcess(
cmd=[
'ros2', 'run', 'ros_gz_bridge', 'parameter_bridge',
'/model/simple_robot/odometry@nav_msgs/msg/Odometry@gz.msgs.Odometry',
'--ros-args', '-r', '/model/simple_robot/odometry:=/odom'
],
output='log',
log_cmd=True
),
# teleop_twist_keyboardの起動
ExecuteProcess(
cmd=['ros2', 'run', 'teleop_twist_keyboard', 'teleop_twist_keyboard'],
output='screen',
prefix='xterm -e'
),
# static_transform_publisherの起動
ExecuteProcess(
cmd=[
'ros2', 'run', 'tf2_ros', 'static_transform_publisher',
'0.2', '0', '0.15', '0', '0', '0',
'simple_robot/base_link', 'simple_robot/base_link/lidar'
],
output='log',
log_cmd=True
),
# slam_toolboxの起動
ExecuteProcess(
cmd=[
'ros2', 'launch', 'slam_toolbox', 'online_async_launch.py',
'slam_params_file:=/home/ubuntu/slam_toolbox_params.yaml'
],
output='log',
log_cmd=True
),
])
(2) ターミナルを開いて「Gazebo」を起動。
$ gz sim run_simple_robot_nav2.sdf
(3) 「Gazebo」左下の▶をクリック。
物理シミュレーションが開始します。
3. Nav2 の起動
(1) ターミナルを開いて「Nav2」をインストール。
$ sudo apt update
$ sudo apt install ros-jazzy-navigation2 ros-jazzy-nav2-bringup
(2) 設定ファイルを作成。
・nav2_params.yaml
amcl:
ros__parameters:
use_sim_time: true
alpha1: 0.2
alpha2: 0.2
alpha3: 0.2
alpha4: 0.2
alpha5: 0.2
base_frame_id: "simple_robot/base_link"
beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9
beam_skip_threshold: 0.3
do_beamskip: false
global_frame_id: "map"
lambda_short: 0.1
laser_likelihood_max_dist: 2.0
laser_max_range: 100.0
laser_min_range: -1.0
laser_model_type: "likelihood_field"
max_beams: 60
max_particles: 2000
min_particles: 500
odom_frame_id: "simple_robot/odom"
pf_err: 0.05
pf_z: 0.99
recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0
resample_interval: 1
robot_model_type: "nav2_amcl::DifferentialMotionModel"
save_pose_rate: 0.5
sigma_hit: 0.2
tf_broadcast: true
transform_tolerance: 1.0
update_min_a: 0.2
update_min_d: 0.25
z_hit: 0.5
z_max: 0.05
z_rand: 0.5
z_short: 0.05
scan_topic: lidar
bt_navigator:
ros__parameters:
use_sim_time: true
global_frame: map
robot_base_frame: simple_robot/base_link
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
wait_for_service_timeout: 1000
action_server_result_timeout: 900.0
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
navigate_through_poses:
plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
# plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
# Built-in plugins are added automatically
# plugin_lib_names: []
error_code_names:
- compute_path_error_code
- follow_path_error_code
controller_server:
ros__parameters:
use_sim_time: true
controller_frequency: 20.0
costmap_update_timeout: 0.30
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
failure_tolerance: 0.3
progress_checker_plugins: ["progress_checker"]
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
controller_plugins: ["FollowPath"]
use_realtime_priority: false
# Progress checker parameters
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 10.0
# Goal checker parameters
#precise_goal_checker:
# plugin: "nav2_controller::SimpleGoalChecker"
# xy_goal_tolerance: 0.25
# yaw_goal_tolerance: 0.25
# stateful: True
general_goal_checker:
stateful: True
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
FollowPath:
plugin: "nav2_mppi_controller::MPPIController"
time_steps: 56
model_dt: 0.05
batch_size: 2000
ax_max: 3.0
ax_min: -3.0
ay_max: 3.0
az_max: 3.5
vx_std: 0.2
vy_std: 0.2
wz_std: 0.4
vx_max: 0.5
vx_min: -0.35
vy_max: 0.5
wz_max: 1.9
iteration_count: 1
prune_distance: 1.7
transform_tolerance: 0.1
temperature: 0.3
gamma: 0.015
motion_model: "DiffDrive"
visualize: true
regenerate_noises: true
TrajectoryVisualizer:
trajectory_step: 5
time_step: 3
AckermannConstraints:
min_turning_r: 0.2
critics: [
"ConstraintCritic", "CostCritic", "GoalCritic",
"GoalAngleCritic", "PathAlignCritic", "PathFollowCritic",
"PathAngleCritic", "PreferForwardCritic"]
ConstraintCritic:
enabled: true
cost_power: 1
cost_weight: 4.0
GoalCritic:
enabled: true
cost_power: 1
cost_weight: 5.0
threshold_to_consider: 1.4
GoalAngleCritic:
enabled: true
cost_power: 1
cost_weight: 3.0
threshold_to_consider: 0.5
PreferForwardCritic:
enabled: true
cost_power: 1
cost_weight: 5.0
threshold_to_consider: 0.5
CostCritic:
enabled: true
cost_power: 1
cost_weight: 3.81
critical_cost: 300.0
consider_footprint: true
collision_cost: 1000000.0
near_goal_distance: 1.0
trajectory_point_step: 2
PathAlignCritic:
enabled: true
cost_power: 1
cost_weight: 14.0
max_path_occupancy_ratio: 0.05
trajectory_point_step: 4
threshold_to_consider: 0.5
offset_from_furthest: 20
use_path_orientations: false
PathFollowCritic:
enabled: true
cost_power: 1
cost_weight: 5.0
offset_from_furthest: 5
threshold_to_consider: 1.4
PathAngleCritic:
enabled: true
cost_power: 1
cost_weight: 2.0
offset_from_furthest: 4
threshold_to_consider: 0.5
max_angle_to_furthest: 1.0
mode: 0
# TwirlingCritic:
# enabled: true
# twirling_cost_power: 1
# twirling_cost_weight: 10.0
local_costmap:
local_costmap:
ros__parameters:
use_sim_time: true
update_frequency: 5.0
publish_frequency: 2.0
global_frame: simple_robot/odom
robot_base_frame: simple_robot/base_link
rolling_window: true
width: 3
height: 3
resolution: 0.05
robot_radius: 0.22
plugins: ["voxel_layer", "inflation_layer"]
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.70
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: /lidar
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
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
always_send_full_costmap: True
global_costmap:
global_costmap:
ros__parameters:
use_sim_time: true
update_frequency: 1.0
publish_frequency: 1.0
global_frame: map
robot_base_frame: simple_robot/base_link
robot_radius: 0.22
resolution: 0.05
track_unknown_space: true
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
scan:
topic: /lidar
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
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.7
always_send_full_costmap: True
# The yaml_filename does not need to be specified since it going to be set by defaults in launch.
# If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py
# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used.
# map_server:
# ros__parameters:
# yaml_filename: ""
map_server:
ros__parameters:
use_sim_time: true
yaml_filename: "/home/ubuntu/my_map.yaml"
#map_saver:
# ros__parameters:
# save_map_timeout: 5.0
# free_thresh_default: 0.25
# occupied_thresh_default: 0.65
# map_subscribe_transient_local: True
planner_server:
ros__parameters:
use_sim_time: true
expected_planner_frequency: 20.0
planner_plugins: ["GridBased"]
costmap_update_timeout: 1.0
GridBased:
plugin: "nav2_navfn_planner::NavfnPlanner"
tolerance: 0.5
use_astar: false
allow_unknown: true
smoother_server:
ros__parameters:
use_sim_time: true
smoother_plugins: ["simple_smoother"]
simple_smoother:
plugin: "nav2_smoother::SimpleSmoother"
tolerance: 1.0e-10
max_its: 1000
do_refinement: True
behavior_server:
ros__parameters:
use_sim_time: true
local_costmap_topic: local_costmap/costmap_raw
global_costmap_topic: global_costmap/costmap_raw
local_footprint_topic: local_costmap/published_footprint
global_footprint_topic: global_costmap/published_footprint
cycle_frequency: 10.0
behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
spin:
plugin: "nav2_behaviors::Spin"
backup:
plugin: "nav2_behaviors::BackUp"
drive_on_heading:
plugin: "nav2_behaviors::DriveOnHeading"
wait:
plugin: "nav2_behaviors::Wait"
assisted_teleop:
plugin: "nav2_behaviors::AssistedTeleop"
local_frame: simple_robot/odom
global_frame: map
robot_base_frame: simple_robot/base_link
transform_tolerance: 0.1
simulate_ahead_time: 2.0
max_rotational_vel: 1.0
min_rotational_vel: 0.4
rotational_acc_lim: 3.2
waypoint_follower:
ros__parameters:
use_sim_time: true
loop_rate: 20
stop_on_failure: false
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
waypoint_pause_duration: 200
velocity_smoother:
ros__parameters:
use_sim_time: true
smoothing_frequency: 20.0
scale_velocities: False
feedback: "OPEN_LOOP"
max_velocity: [0.5, 0.0, 2.0]
min_velocity: [-0.5, 0.0, -2.0]
max_accel: [2.5, 0.0, 3.2]
max_decel: [-2.5, 0.0, -3.2]
odom_topic: "odom"
odom_duration: 0.1
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0
collision_monitor:
ros__parameters:
use_sim_time: true
base_frame_id: "simple_robot/base_link"
odom_frame_id: "simple_robot/odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.2
source_timeout: 1.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "/local_costmap/published_footprint"
time_before_collision: 1.2
simulation_time_step: 0.1
min_points: 6
visualize: False
enabled: True
observation_sources: ["scan"]
scan:
type: "scan"
topic: "lidar"
min_height: 0.15
max_height: 2.0
enabled: True
docking_server:
ros__parameters:
use_sim_time: true
controller_frequency: 50.0
initial_perception_timeout: 5.0
wait_charge_timeout: 5.0
dock_approach_timeout: 30.0
undock_linear_tolerance: 0.05
undock_angular_tolerance: 0.1
max_retries: 3
base_frame: "simple_robot/base_link"
fixed_frame: "simple_robot/odom"
dock_backwards: false
dock_prestaging_tolerance: 0.5
# Types of docks
dock_plugins: ['simple_charging_dock']
simple_charging_dock:
plugin: 'opennav_docking::SimpleChargingDock'
docking_threshold: 0.05
staging_x_offset: -0.7
use_external_detection_pose: true
use_battery_status: false # true
use_stall_detection: false # true
external_detection_timeout: 1.0
external_detection_translation_x: -0.18
external_detection_translation_y: 0.0
external_detection_rotation_roll: -1.57
external_detection_rotation_pitch: -1.57
external_detection_rotation_yaw: 0.0
filter_coef: 0.1
# Dock instances
# The following example illustrates configuring dock instances.
# docks: ['home_dock'] # Input your docks here
# home_dock:
# type: 'simple_charging_dock'
# frame: map
# pose: [0.0, 0.0, 0.0]
controller:
k_phi: 3.0
k_delta: 2.0
v_linear_min: 0.15
v_linear_max: 0.15
loopback_simulator:
ros__parameters:
use_sim_time: true
base_frame_id: "simple_robot/base_link"
odom_frame_id: "simple_robot/odom"
map_frame_id: "map"
scan_frame_id: "base_scan" # tb4_loopback_simulator.launch.py remaps to 'rplidar_link'
update_duration: 0.02
(3) 「Nav2」の起動。
今回は、「navigation_launch.py」を使います。
$ ros2 launch nav2_bringup navigation_launch.py params_file:=/home/ubuntu/nav2_params.yaml
4. Navigation用の rvis2 の起動
(1) Nav2で提供されているConfigで「rviz2」を起動。
$ ros2 run rviz2 rviz2 -d $(ros2 pkg prefix nav2_bringup)/share/nav2_bringup/rviz/nav2_default_view.rviz
![](https://assets.st-note.com/img/1733878517-9wVOdoX7va81YW3nRgBcCzJb.png?width=1200)
Navigationがactiveであれば動作しています。
Localizationは今回はNav2のLocalizationを使ってないのでinactiveで問題ないです。
5. ナビゲーション の動作確認
(1) 「2D Pose Estimate」でスタートの位置と向きを指定した後、「Nav2 Goal」でゴールの位置と向きを指定。
クリックでなくマウスドラッグで矢印を配置します。ゴールに向かって移動したら成功です。
ROS2 Jazzy + Gazebo Harmonic の Nav2 をおためし中 pic.twitter.com/mHO0yUMhvP
— 布留川英一 / Hidekazu Furukawa (@npaka123) December 11, 2024