navigation2의 plugin과 node들의 parameter를 어떻게 수정할 수 있는지를 다룬다.
navigation stack의 목표는 robot이 실제 세계에서 작동하기 위한 safe path를 만드는 것이고,
그를 위해 parameter를 조정하는 작업이 필요하다.
-NavigateToPose action server
이용해 waypoint following
(waypoint: 경로의 지점들)
-일련의 waypoint를 따라 차례대로 navigate
-waypoint마다 task수행 가능
waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false #특정 waypoint에 navigate하지 못했을 경우 true-->stop, false-->다음 waypoint로(bool, Default=true)
waypoint_task_executor_plugin: "wait_at_waypoint" #waypoint에 도달 시 수행할 task를 정의(string, Default='wait_at_waypoint')
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
waypoint_pause_duration: 0
(*plugin
: class 개념)
-nav2_waypoint_follower
namespace안의 plugin들
-Default Plugin:wait_at_waypoint
namespace의 nav2_waypoint_follower::WaitAtWaypoint
plugin
WaitAtWaypoint
-각 waypoint에 도달할 때마다 지정 시간 동안 멈추도록 함
parameter
-nav2_waypoint_follower plugin.enabled
-nav2_waypoint_follower plugin.waypoint_pause_duration
PhotoAtWaypoint
-waypoint에 도달했을 때 사진을 찍음
-사진명은 waypoint index_timestamp형식(ex: 0_1602582820)
parameter
-nav2_waypoint_follower plugin.camera_image_topic_name
-nav2_waypoint_follower plugin.save_images_dir
-nav2_waypoint_follower plugin.image_format
InputAtWaypoint
-waypoint에서 일정 시간 동안 외부 입력을 기다리도록 함
parameter
-nav2_waypoint_follower plugin.timeout
-nav2_waypoint_follower plugin.input_topic
-NavigatorPose
task 인터페이스를 구현
-navigation task에 유연성 부여, 복잡한 로봇 동작을 지정
bt_navigator:
ros__parameters:
use_sim_time: true #simulation에서 제공하는 시간 사용 여부(bool, Default=flase)
global_frame: map #reference name(string, Default=map)
robot_base_frame: base_link #BT xml파일 경로(string, Default=base_link)
transform_tolerance: 0.1 #TF transform tolerance(double, Default=0.1(Sec))
default_nav_to_pose_bt_xml: replace/with/path/to/bt.xml #NavigateToPose의 xml file 경로(string, Default=N/A)
default_nav_through_poses_bt_xml: replace/with/path/to/bt.xml #NavigateThroughPoses의 xml file경로(string, Default=N/A)
goal_blackboard_id: goal #NavigateToPoses의 BT에 goal을 전달하는 변수(string, Default="goal")
goals_blackboard_id: goals #NavigateThroughPoses의 BT에 goal들을 전달하는 변수(string, Default="goals")
path_blackboard_id: path #NavigateThroughPoses 의 BT의 경로(string, Default="path")
plugin_lib_names: #behavior tree node 공유 라이브러리 목록(vector<string>)
- nav2_compute_path_to_pose_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_back_up_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
nav2_behavior_tree
package는 몇 navigation-specific node를 제공한다.
behavior tree
behavior tree는 task의 동작 flow를 제어하는 계층 노드 tree
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<RecoveryNode number_of_retries="6" name="NavigateRecovery"> #2개의 자식 노드를 가지고 있고, 첫번째 자식 노드가 SUCCESS일 때 SUCCESS를 return하는 control flow node: number of retries(int, Default=1)
<PipelineSequence name="NavigateWithReplanning"> #자식 노드가 succeed할 때까지 차례대로 tick
<RateController hz="1.0"> #자식 노드의 tick rate를 조절(double, Default=10.0)
<RecoveryNode number_of_retries="1" name="ComputePathToPose">
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased"/> #ComputePathToPose action server 호출: goal pose, 경로, planner plugin 이름
<ReactiveFallback name="ComputePathToPoseRecoveryFallback">
<GoalUpdated/> #global navigation goal 변경 여부
<ClearEntireCostmap name="ClearGlobalCostmap-Context" service_name="global_costmap/clear_entirely_global_costmap"/> #costmap clearing server 호출: clearing을 할 costmap service name
</ReactiveFallback>
</RecoveryNode>
</RateController>
<RecoveryNode number_of_retries="1" name="FollowPath">
<FollowPath path="{path}" controller_id="FollowPath"/>
<ReactiveFallback name="FollowPathRecoveryFallback">
<GoalUpdated/>
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
</ReactiveFallback>
</RecoveryNode>
</PipelineSequence>
<ReactiveFallback name="RecoveryFallback">
<GoalUpdated/>
<RoundRobin name="RecoveryActions"> #자식 BT node에 round-robbin behavior를 만드는 control flow 노드
<Sequence name="ClearingActions">
<ClearEntireCostmap name="ClearLocalCostmap-Subtree" service_name="local_costmap/clear_entirely_local_costmap"/>
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
</Sequence>
<Spin spin_dist="1.57"/> #주어진 각도만큼 in-place rotation: spin distance(double, Default=1.57)
<Wait wait_duration="5"/> #recovery: wait time(double, Default=1.0)
<BackUp backup_dist="0.15" backup_speed="0.025"/> #주어진 distance만큼 linear translation: backup할 total distance(double, Default=-0.15)
</RoundRobin>
</ReactiveFallback>
</RecoveryNode>
</BehaviorTree>
</root>
global_costmap:
global_costmap:
ros__parameters:
footprint_padding: 0.03 #footprint 할 정도(double, Default=0.01)
update_frequency: 1.0 #costmap을 update할 빈도(double, Default=5.0)
publish_frequency: 1.0 #costmap을 topic으로 publish할 빈도(double, Default=1.0)
global_frame: map #reference frame(string, Default="map")
robot_base_frame: base_link #robot base frame(string, Default="base_link")
use_sim_time: True
robot_radius: 0.22 # robot radius(if used, no footprint points)
resolution: 0.05 #costmap 1 pixel의 해상도(double, Default=0.1)
plugins: ["static_layer", "obstacle_layer", "voxel_layer", "inflation_layer"] #type of plugin to be loaded in the namespace(vector<string>, Default)
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer" #default
enabled: True
observation_sources: scan #data source의 namespace
footprint_clearing_enabled: true #footprint아래의 모든 cell 지울지 여부
max_obstacle_height: 2.0 #점유 grid에 return할 최대 높이
combination_method: 1 #master costmap에 data를 추가할 method 목록
scan: #data source: scan
topic: /scan #data의 topic
obstacle_max_range: 2.5 #costmap에 표시할 obstacle 최대 범위
obstacle_min_range: 0.0
raytrace_max_range: 3.0 #costmap에서 raytrace로 장애물을 제거할 최대 범위
raytrace_min_range: 0.0
max_obstacle_height: 2.0
min_obstacle_height: 0.0
clearing: True #raytrace 제거를 할지 여부
marking: True #mark할지 여부
data_type: "LaserScan" #input의 데이터형(LaserScan or PointCloud2)
inf_is_valid: false #무한 반환이 가능한지 여부
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
footprint_clearing_enabled: true
max_obstacle_height: 2.0
publish_voxel_map: True
origin_z: 0.0 #voxel표시를 시작할 지점
z_resolution: 0.05
z_voxels: 16 #표시할 voxel 수(최대 16)
max_obstacle_height: 2.0
unknown_threshold: 15
mark_threshold: 0
observation_sources: pointcloud #data source의 namespace
combination_method: 1
pointcloud: # no frame set, uses frame from message. data source
topic: /intel_realsense_r200_depth/points
max_obstacle_height: 2.0
min_obstacle_height: 0.0
obstacle_max_range: 2.5
obstacle_min_range: 0.0
raytrace_max_range: 3.0
raytrace_min_range: 0.0
clearing: True
marking: True
data_type: "PointCloud2"
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
enabled: true
subscribe_to_updates: true
transform_tolerance: 0.1
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
enabled: true
inflation_radius: 0.55
cost_scaling_factor: 1.0
inflate_unknown: false
inflate_around_unknown: true
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
footprint
-일련의 foorprint point
global_costmap:
global_costmap:
ros__parameters:
footprint_padding: 0.03
update_frequency: 1.0
publish_frequency: 1.0
global_frame: map
robot_base_frame: base_link
use_sim_time: True
robot_radius: 0.22 # radius set and used, so no footprint points
resolution: 0.05
plugins: ["static_layer", "obstacle_layer", "voxel_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
footprint_clearing_enabled: true
max_obstacle_height: 2.0
combination_method: 1
scan:
topic: /scan
obstacle_max_range: 2.5
obstacle_min_range: 0.0
raytrace_max_range: 3.0
raytrace_min_range: 0.0
max_obstacle_height: 2.0
min_obstacle_height: 0.0
clearing: True
marking: True
data_type: "LaserScan"
inf_is_valid: false
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
footprint_clearing_enabled: true
max_obstacle_height: 2.0
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.05
z_voxels: 16
max_obstacle_height: 2.0
unknown_threshold: 15
mark_threshold: 0
observation_sources: pointcloud
combination_method: 1
pointcloud: # no frame set, uses frame from message
topic: /intel_realsense_r200_depth/points
max_obstacle_height: 2.0
min_obstacle_height: 0.0
obstacle_max_range: 2.5
obstacle_min_range: 0.0
raytrace_max_range: 3.0
raytrace_min_range: 0.0
clearing: True
marking: True
data_type: "PointCloud2"
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
enabled: true
subscribe_to_updates: true
transform_tolerance: 0.1
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
enabled: true
inflation_radius: 0.55 #장애물 주변을 부풀릴 때 radius(double, Default=0.55)
cost_scaling_factor: 1.0 #cost_scaling_factor: inflation radius의 Exponential decay factor(double, Default=10.0)
inflate_unknown: false
inflate_around_unknown: true
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
일련의 node를 하나씩 stack을 실행하기 위한 configurating, activate state로 전환한다.
server와 연결하여 server가 계속 작동 중인지 확인하고, 충돌한 노드가 있을 시 모든 node를 down전환한다.
lifecycle_manager:
ros__parameters:
autostart: true
node_names: ['controller_server', 'planner_server', 'behavior_server', 'bt_navigator', 'waypoint_follower']
bond_timeout: 4.0
attempt_respawn_reconnection: true
bond_respawn_max_duration: 10.0
stack의 planner요청을 처리하기 위한 서버 구현, plugin 구현 맵을 hosting하는 역할.
goal로의 path를 계산하기 위한 적절한 plugin을 불러온다.
planner_server:
ros__parameters:
expected_planner_frequency: 20.0
planner_plugins: ['GridBased'] #mapped plugin의 list
GridBased:
plugin: 'nav2_navfn_planner/NavfnPlanner'
wavefront Dijkstra나 A* planner를 구현한다.
planner_server:
ros__parameters:
planner_plugins: ['GridBased']
GridBased:
plugin: 'nav2_navfn_planner/NavfnPlanner'
use_astar: True #true: A* planner사용/false: wavefront Dijkstra planner 사용
allow_unknown: True
tolerance: 1.0
2D A*
-SmacPlanner2D planner
-원형 differential-drive robot, omni-directional drive robot
Hybrid-A*
-SmacPlannerHybrid plugin
-ackermann robot, legged robot
-kinematically feasible
-reversing 가능
State Lattice
-SmacPlannerLattice plugin
-비원형 및 모든 shape의 robot
-kinematically feasible
-reversing 가능
https://news.movel.ai/theta-star?x-host=news.movel.ai
어떤 각도의 경로든 plan할 수 있는 Theta path planner(A 기반)사용
planner_server:
ros__parameters:
expected_planner_frequency: 20.0
use_sim_time: True
planner_plugins: ["GridBased"]
GridBased:
plugin: "nav2_theta_star_planner/ThetaStarPlanner"
how_many_corners: 8
w_euc_cost: 1.0
w_traversal_cost: 2.0
w_heuristic_cost: 1.0
stack의 controller요청을 처리하기 위한 서버 구현, plugin 구현 맵을 hosting하는 역할.
goal로의 path를 계산하기 위한 적절한 plugin을 불러온다.
(planner server와 비슷)
controller_server:
ros__parameters:
use_sim_time: True
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
failure_tolerance: 0.3
odom_topic: "odom"
progress_checker_plugin: "progress_checker"
goal_checker_plugin: "goal_checker" #goal에 도달했는지 check하기 위한 goal checker plugin명
controller_plugins: ["FollowPath"] #요청을 처리하기 위한 controller plugin 목록
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 10.0
goal_checker:
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
stateful: True
FollowPath:
plugin: "dwb_core::DWBLocalPlanner"
(DWB예시가 없어서 DWA 사진을 가져옴)
dwa에서 기능을 확장한 것이 dwb.
controller server의 설정에 포함되어 있다.
controller_server:
ros__parameters:
# controller server parameters (see Controller Server for more info)
use_sim_time: True
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
progress_checker_plugin: "progress_checker"
goal_checker_plugins: ["goal_checker"]
controller_plugins: ["FollowPath"]
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 10.0
goal_checker:
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
stateful: True
# DWB controller parameters
FollowPath:
plugin: "dwb_core::DWBLocalPlanner"
debug_trajectory_details: True
min_vel_x: 0.0
min_vel_y: 0.0
max_vel_x: 0.26
max_vel_y: 0.0
max_vel_theta: 1.0
min_speed_xy: 0.0
max_speed_xy: 0.26
min_speed_theta: 0.0
acc_lim_x: 2.5
acc_lim_y: 0.0
acc_lim_theta: 3.2
decel_lim_x: -2.5
decel_lim_y: 0.0
decel_lim_theta: -3.2
vx_samples: 20
vy_samples: 5
vtheta_samples: 20
sim_time: 1.7
linear_granularity: 0.05
angular_granularity: 0.025
transform_tolerance: 0.2
xy_goal_tolerance: 0.25
trans_stopped_velocity: 0.25
short_circuit_trajectory_evaluation: True
stateful: True
critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
BaseObstacle.scale: 0.02
PathAlign.scale: 32.0
GoalAlign.scale: 24.0
PathAlign.forward_point_distance: 0.1
GoalAlign.forward_point_distance: 0.1
PathDist.scale: 32.0
GoalDist.scale: 24.0
RotateToGoal.scale: 32.0
RotateToGoal.slowing_factor: 5.0
RotateToGoal.lookahead_time: -1.0
stack의 map load요청을 처리하기 위한 서버 구현, map topic을 hosting한다.
또한 서비스 요청에 따라 map을 저장하는 map saver server를 구현한다.
#map server parameters
map_server:
ros__parameters:
yaml_filename: "turtlebot3_world.yaml"
topic_name: "map"
frame_id: "map"
#map saver parameters
map_saver:
ros__parameters:
save_map_timeout: 5.0
free_thresh_default: 0.25
occupied_thresh_default: 0.65
#costmap filter info server parameters
costmap_filter_info_server:
ros__parameters:
type: 1
filter_info_topic: "costmap_filter_info"
mask_topic: "filter_mask"
base: 0.0
multiplier: 0.25
MCL: 입자 필터를 사용해 자기의 위치를 추정하는 방법. 입자 분포를 통해 로봇 위치의 확률 분포를 표시하고 관측된 정보에 따라 그 분포를 갱신해 자신의 위치를 추정한다.
AMCL: Adaptive Monte Carlo Localizer를 사용해 static map에서 robot을 localizing
amcl:
ros__parameters:
alpha1: 0.2 #rotation에서 추정된 odometry rotation의 noise
alpha2: 0.2 #translation에서 추정된 odometry rotation의 noise
alpha3: 0.2 #translation에서 추정된 odometry translation의 noise
alpha4: 0.2 #rotation에서 추정된 odometry translation의 noise
alpha5: 0.2 #translation noise
base_frame_id: "base_footprint" #robot base frame
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: "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: scan
map_topic: map
set_initial_pose: false
always_reset_initial_pose: false
first_map_only: false
initial_pose:
x: 0.0
y: 0.0
z: 0.0
yaw: 0.0
recovery behavior 요청을 처리하기 위한 서버 구현, C++ behavior plugin vector를 hosting한다.
각 behavior마다 behavior server를 도입하는 게 가능하고, 그 behavior server들은 costmap과 TF buffer등을 공유해서 cost를 낮춘다.
recoveries_server:
ros__parameters:
costmap_topic: local_costmap/costmap_raw
footprint_topic: local_costmap/published_footprint
cycle_frequency: 10.0
behavior_plugins: ["spin", "backup", "drive_on_heading", "wait", "assisted_teleop"]
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"
# default plugin들의 parameter
global_frame: odom
robot_base_frame: base_link
transform_timeout: 0.1
simulate_ahead_time: 2.0
max_rotational_vel: 1.0
min_rotational_vel: 0.4
rotational_acc_lim: 3.2
smoother server
-smooth path요청 처리
-C++ smoothers를 도입하는 plugin vector들을 hosting
-costmap, TF buffer등을 공유하는 smoothers로 smoothing을 하는 action interface
smoother_server:
ros__parameters:
costmap_topic: global_costmap/costmap_raw
footprint_topic: global_costmap/published_footprint
robot_base_frame: base_link
transform_timeout: 0.1
smoother_plugins: ["simple_smoother"]
simple_smoother:
plugin: "nav2_smoother::SimpleSmoother"
tolerance: 1.0e-10
do_refinement: True
빠르고 간단하게 smoothing을 수행하는 smoother server plugin.
초기 path points와 smoothed path의 points에 가중치를 줘서 안정적이면서 특징적인 경로를 유지하도록 한다.
kinematically infeasible한 planner를 쓰는 것이 좋다. (물리법칙 어길 가능성 높음)
smoother_server:
ros__parameters:
costmap_topic: global_costmap/costmap_raw
footprint_topic: global_costmap/published_footprint
robot_base_frame: base_link
transform_timeout: 0.1
smoother_plugins: ["simple_smoother"]
simple_smoother:
plugin: "nav2_smoother::SimpleSmoother"
tolerance: 1.0e-10
do_refinement: True
max_its: 1000
w_data: 0.2 #path data weight
w_smooth: 0.3 #path를 smooth할 때 weight
-path를 곡률있게 하여 속도를 제어해서 corner를 돌 때 overshooting하는 것을 완화한다.
-heuristic으로 인해, 충돌의 가능성이 있을 때 자동적으로 속도를 줄인다.
-speed에 따라 조정되는 lookahead point를 통해 안정성을 높인다.
-주로 서비스, 산업용 로봇을 대상으로 한다.
controller_server:
ros__parameters:
use_sim_time: True
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
progress_checker_plugin: "progress_checker"
goal_checker_plugins: ["goal_checker"]
controller_plugins: ["FollowPath"]
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 10.0
goal_checker:
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
stateful: True
FollowPath:
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
desired_linear_vel: 0.5 #desired max linear v
lookahead_dist: 0.6 #robot과 lookahead point간 거리
min_lookahead_dist: 0.3
max_lookahead_dist: 0.9
lookahead_time: 1.5
rotate_to_heading_angular_vel: 1.8
transform_tolerance: 0.1
use_velocity_scaled_lookahead_dist: false
min_approach_linear_velocity: 0.05
approach_velocity_scaling_dist: 0.6
max_allowed_time_to_collision_up_to_carrot: 1.0
use_regulated_linear_velocity_scaling: true
use_cost_regulated_linear_velocity_scaling: false
regulated_linear_scaling_min_radius: 0.9
regulated_linear_scaling_min_speed: 0.25
use_rotate_to_heading: true
allow_reversing: false
rotate_to_heading_min_angle: 0.785
max_angular_accel: 3.2
max_robot_pose_search_dist: 10.0
use_interpolation: false
현재 robot과 새로 수신된 path의 heading차이를 체크해 차이가 임계값을 벗어나면 Rotation Shim Controller가 robot을 해당 경로의 방향으로 회전시킨다.
Rotation Shim Controller는 다음과 같은 경우에 유용하다.
-differential/omnidirectional robot(제자리에서 회전 가능)
-현재 경로와 상당히 다른 경로를 track하기 시작할 때
-kinematically infeasible한 planner 사용시
controller_server:
ros__parameters:
use_sim_time: True
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
progress_checker_plugin: "progress_checker"
goal_checker_plugins: ["goal_checker"]
controller_plugins: ["FollowPath"]
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 10.0
goal_checker:
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
stateful: True
FollowPath:
plugin: "nav2_rotation_shim_controller::RotationShimController"
primary_controller: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
angular_dist_threshold: 0.785
forward_sampling_distance: 0.5
rotate_to_heading_angular_vel: 1.8 #rotate할 속도
max_angular_accel: 3.2
simulate_ahead_time: 1.0
장애물에서 멀리 떨어지기 위한 global path나, Reeds-Shepp motion model에 유용하다.
input path: mint
smoothed path: green: smoothness, obstacle과의 거리 커짐
heavy optimization algorithm(computational cost 높음)-->truncated path에서 사용하는 게 좋다
smoother_server:
ros__parameters:
use_sim_time: True
smoother_plugins: ["SmoothPath"]
SmoothPath:
plugin: "nav2_constrained_smoother/ConstrainedSmoother"
reversing_enabled: true # whether to detect forward/reverse direction and cusps. Should be set to false for paths without orientations assigned
path_downsampling_factor: 3 # every n-th node of the path is taken. Useful for speed-up
path_upsampling_factor: 1 # 0 - path remains downsampled, 1 - path is upsampled back to original granularity using cubic bezier, 2... - more upsampling
keep_start_orientation: true # whether to prevent the start orientation from being smoothed
keep_goal_orientation: true # whether to prevent the gpal orientation from being smoothed
minimum_turning_radius: 0.40 # minimum turning radius the robot can perform. Can be set to 0.0 (or w_curve can be set to 0.0 with the same effect) for diff-drive/holonomic robots
w_curve: 30.0 # weight to enforce minimum_turning_radius
w_dist: 0.0 # weight to bind path to original as optional replacement for cost weight
w_smooth: 15000.0 # weight to maximize smoothness of path
w_cost: 0.015 # weight to steer robot away from collision and cost
# Parameters used to improve obstacle avoidance near cusps (forward/reverse movement changes)
w_cost_cusp_multiplier: 3.0 # option to use higher weight during forward/reverse direction change which is often accompanied with dangerous rotations
cusp_zone_length: 2.5 # length of the section around cusp in which nodes use w_cost_cusp_multiplier (w_cost rises gradually inside the zone towards the cusp point, whose costmap weight eqals w_cost*w_cost_cusp_multiplier)
# Points in robot frame to grab costmap values from. Format: [x1, y1, weight1, x2, y2, weight2, ...]
# IMPORTANT: Requires much higher number of iterations to actually improve the path. Uncomment only if you really need it (highly elongated/asymmetric robots)
# cost_check_points: [-0.185, 0.0, 1.0]
optimizer:
max_iterations: 70 # max iterations of smoother
debug_optimizer: false # print debug info
gradient_tol: 5e3
fn_tol: 1.0e-15
param_tol: 1.0e-20
cost_check_points
2개의 cost check points-->improve cost awareness of a rectangular robot
robot controller로 보낼 velocity를 smoothing하는 역할.
속도와 가속도를 smoothing하여 robot motor와 hardware의 마모를 줄이는 것이 목표
velocity_smoother:
ros__parameters:
smoothing_frequency: 20.0
scale_velocities: false
feedback: "OPEN_LOOP" #robot velocity의 현상태에 대한 feedback 타입(OPEN_LOOP: 마지막 속도를 현재 속도로 사용)
max_velocity: [0.5, 0.0, 2.5]
min_velocity: [-0.5, 0.0, -2.5]
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0
max_accel: [2.5, 0.0, 3.2]
max_decel: [-2.5, 0.0, -3.2]
odom_topic: "odom"
odom_duration: 0.1
robot 안전에 대한 추가 설정을 하는 node.
센서 데이터, costmap, trajectory planner등을 이용해 충돌 회피 작업.
laser scan을 통해 bounding box 안에 임박한 충돌이 있는지 감지하고 controller를 중지하거나 robot 속도를 줄여 충돌을 방지
대부분의 충돌 방지는 trajectory planner가 수행하지만, 이 node의 경우 갑자기 나타나는 장애물과의 충돌을 방지할 때 쓰인다.
robot의 frame 원점에서 시작되는 polygon을 정의해 만든 영역에 속하는 데이터를 이용해 operation하는데, 이 operation은 사용하는 model에 따라 달라진다.
stop model
obstacle point가 정해둔 수치보다 많이 영역 안에 들어왔을 경우 robot 정지
slowdown model
robot 속도 낮추기
approach model
현재 속도에서 충돌까지 걸리는 시간을 계산해, 최소 time_before_collision(parameter)만큼의 시간을 유지하도록 robot 속도 낮추기
영역에 속하는 데이터를 얻는 방법 또한 여러 가지가 있다.
laser scanners
pointclouds
IR/Sonars
collision_monitor:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_raw"
cmd_vel_out_topic: "cmd_vel"
transform_tolerance: 0.5
source_timeout: 5.0
stop_pub_timeout: 2.0
polygons: ["PolygonStop", "PolygonSlow", "FootprintApproach"]
# polygons parameters
PolygonStop:
type: "circle"
radius: 0.3
action_type: "stop"
max_points: 3
visualize: True
polygon_pub_topic: "polygon_stop"
PolygonSlow:
type: "polygon"
points: [1.0, 1.0, 1.0, -1.0, -0.5, -1.0, -0.5, 1.0]
action_type: "slowdown"
max_points: 3
slowdown_ratio: 0.3
visualize: True
polygon_pub_topic: "polygon_slowdown"
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "/local_costmap/published_footprint"
time_before_collision: 2.0
simulation_time_step: 0.02
max_points: 5
visualize: False
# observation sources parameters
observation_sources: ["scan", "pointcloud"]
scan:
type: "scan"
topic: "/scan"
pointcloud:
type: "pointcloud"
topic: "/intel_realsense_r200_depth/points"
min_height: 0.1
max_height: 0.5