navigation_params.yaml 7.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268
  1. # Copyright (c) Contributors to the Open 3D Engine Project.
  2. # For complete copyright and license terms please see the LICENSE at the root of this distribution.
  3. #
  4. # SPDX-License-Identifier: Apache-2.0 OR MIT
  5. #
  6. #
  7. bt_navigator:
  8. ros__parameters:
  9. use_sim_time: True
  10. global_frame: map
  11. robot_base_frame: base_link
  12. odom_topic: /odom
  13. bt_loop_duration: 10
  14. default_server_timeout: 20
  15. enable_groot_monitoring: True
  16. groot_zmq_publisher_port: 1666
  17. groot_zmq_server_port: 1667
  18. plugin_lib_names:
  19. - nav2_compute_path_to_pose_action_bt_node
  20. - nav2_compute_path_through_poses_action_bt_node
  21. - nav2_follow_path_action_bt_node
  22. - nav2_back_up_action_bt_node
  23. - nav2_spin_action_bt_node
  24. - nav2_wait_action_bt_node
  25. - nav2_clear_costmap_service_bt_node
  26. - nav2_is_stuck_condition_bt_node
  27. - nav2_goal_reached_condition_bt_node
  28. - nav2_goal_updated_condition_bt_node
  29. - nav2_initial_pose_received_condition_bt_node
  30. - nav2_reinitialize_global_localization_service_bt_node
  31. - nav2_rate_controller_bt_node
  32. - nav2_distance_controller_bt_node
  33. - nav2_speed_controller_bt_node
  34. - nav2_truncate_path_action_bt_node
  35. - nav2_goal_updater_node_bt_node
  36. - nav2_recovery_node_bt_node
  37. - nav2_pipeline_sequence_bt_node
  38. - nav2_round_robin_node_bt_node
  39. - nav2_transform_available_condition_bt_node
  40. - nav2_time_expired_condition_bt_node
  41. - nav2_distance_traveled_condition_bt_node
  42. - nav2_single_trigger_bt_node
  43. - nav2_is_battery_low_condition_bt_node
  44. - nav2_navigate_through_poses_action_bt_node
  45. - nav2_navigate_to_pose_action_bt_node
  46. - nav2_remove_passed_goals_action_bt_node
  47. - nav2_planner_selector_bt_node
  48. - nav2_controller_selector_bt_node
  49. - nav2_goal_checker_selector_bt_node
  50. bt_navigator_rclcpp_node:
  51. ros__parameters:
  52. use_sim_time: True
  53. controller_server:
  54. ros__parameters:
  55. use_sim_time: True
  56. controller_frequency: 20.0
  57. min_x_velocity_threshold: 0.001
  58. min_y_velocity_threshold: 0.5
  59. min_theta_velocity_threshold: 0.001
  60. failure_tolerance: 0.3
  61. progress_checker_plugin: "progress_checker"
  62. goal_checker_plugins: ["general_goal_checker"]
  63. controller_plugins: ["FollowPath"]
  64. progress_checker:
  65. plugin: "nav2_controller::SimpleProgressChecker"
  66. required_movement_radius: 0.5
  67. movement_time_allowance: 10.0
  68. general_goal_checker:
  69. stateful: True
  70. plugin: "nav2_controller::SimpleGoalChecker"
  71. xy_goal_tolerance: 0.5
  72. yaw_goal_tolerance: 1.5
  73. # DWB parameters
  74. FollowPath:
  75. plugin: "dwb_core::DWBLocalPlanner"
  76. debug_trajectory_details: True
  77. min_vel_x: 0.4
  78. min_vel_y: 0.0
  79. max_vel_x: 1.0
  80. max_vel_y: 0.0
  81. max_vel_theta: 2.0
  82. min_speed_xy: 0.4
  83. max_speed_xy: 1.0
  84. min_speed_theta: 0.0
  85. max_speed_theta: 2.0
  86. acc_lim_x: 2.5
  87. acc_lim_y: 0.0
  88. acc_lim_theta: 3.2
  89. decel_lim_x: -2.5
  90. decel_lim_y: 0.0
  91. decel_lim_theta: -3.2
  92. vx_samples: 20
  93. vy_samples: 5
  94. vtheta_samples: 20
  95. sim_time: 1.7
  96. linear_granularity: 0.05
  97. angular_granularity: 0.025
  98. transform_tolerance: 0.2
  99. xy_goal_tolerance: 0.4
  100. trans_stopped_velocity: 0.3
  101. short_circuit_trajectory_evaluation: True
  102. stateful: True
  103. critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
  104. BaseObstacle.scale: 0.02
  105. PathAlign.scale: 2.0
  106. PathAlign.forward_point_distance: 0.1
  107. GoalAlign.scale: 1.0
  108. GoalAlign.forward_point_distance: 0.1
  109. PathDist.scale: 3.0
  110. GoalDist.scale: 0.5
  111. RotateToGoal.scale: 2.0
  112. RotateToGoal.slowing_factor: 5.0
  113. RotateToGoal.lookahead_time: -1.0
  114. controller_server_rclcpp_node:
  115. ros__parameters:
  116. use_sim_time: True
  117. local_costmap:
  118. local_costmap:
  119. ros__parameters:
  120. update_frequency: 5.0
  121. publish_frequency: 2.0
  122. global_frame: odom
  123. robot_base_frame: base_link
  124. use_sim_time: True
  125. rolling_window: true
  126. width: 5
  127. height: 5
  128. resolution: 0.02
  129. robot_radius: 0.25
  130. plugins: ["voxel_layer", "inflation_layer"]
  131. inflation_layer:
  132. plugin: "nav2_costmap_2d::InflationLayer"
  133. cost_scaling_factor: 10.0
  134. inflation_radius: 0.55
  135. voxel_layer:
  136. plugin: "nav2_costmap_2d::VoxelLayer"
  137. enabled: True
  138. publish_voxel_map: True
  139. origin_z: 0.0
  140. z_resolution: 0.05
  141. z_voxels: 16
  142. max_obstacle_height: 2.0
  143. mark_threshold: 0
  144. observation_sources: scan
  145. scan:
  146. topic: /scan
  147. max_obstacle_height: 2.0
  148. clearing: True
  149. marking: True
  150. data_type: "LaserScan"
  151. raytrace_max_range: 3.0
  152. raytrace_min_range: 0.0
  153. obstacle_max_range: 2.5
  154. obstacle_min_range: 0.0
  155. static_layer:
  156. map_subscribe_transient_local: True
  157. always_send_full_costmap: True
  158. local_costmap_client:
  159. ros__parameters:
  160. use_sim_time: True
  161. local_costmap_rclcpp_node:
  162. ros__parameters:
  163. use_sim_time: True
  164. global_costmap:
  165. global_costmap:
  166. ros__parameters:
  167. update_frequency: 1.0
  168. publish_frequency: 1.0
  169. global_frame: map
  170. robot_base_frame: base_link
  171. use_sim_time: True
  172. robot_radius: 0.25
  173. resolution: 0.02
  174. track_unknown_space: true
  175. plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
  176. obstacle_layer:
  177. plugin: "nav2_costmap_2d::ObstacleLayer"
  178. enabled: True
  179. observation_sources: scan
  180. scan:
  181. topic: /scan
  182. max_obstacle_height: 2.0
  183. clearing: True
  184. marking: True
  185. data_type: "LaserScan"
  186. raytrace_max_range: 3.0
  187. raytrace_min_range: 0.0
  188. obstacle_max_range: 2.5
  189. obstacle_min_range: 0.0
  190. static_layer:
  191. plugin: "nav2_costmap_2d::StaticLayer"
  192. map_subscribe_transient_local: True
  193. inflation_layer:
  194. plugin: "nav2_costmap_2d::InflationLayer"
  195. cost_scaling_factor: 3.0
  196. inflation_radius: 0.4
  197. always_send_full_costmap: True
  198. global_costmap_client:
  199. ros__parameters:
  200. use_sim_time: True
  201. global_costmap_rclcpp_node:
  202. ros__parameters:
  203. use_sim_time: True
  204. map_saver:
  205. ros__parameters:
  206. use_sim_time: True
  207. save_map_timeout: 5.0
  208. free_thresh_default: 0.25
  209. occupied_thresh_default: 0.65
  210. map_subscribe_transient_local: True
  211. planner_server:
  212. ros__parameters:
  213. expected_planner_frequency: 20.0
  214. use_sim_time: True
  215. planner_plugins: ["GridBased"]
  216. GridBased:
  217. plugin: "nav2_navfn_planner/NavfnPlanner"
  218. tolerance: 0.5
  219. use_astar: true
  220. use_final_approach_orientation: true
  221. allow_unknown: true
  222. planner_server_rclcpp_node:
  223. ros__parameters:
  224. use_sim_time: True
  225. recoveries_server:
  226. ros__parameters:
  227. costmap_topic: local_costmap/costmap_raw
  228. footprint_topic: local_costmap/published_footprint
  229. cycle_frequency: 10.0
  230. recovery_plugins: ["spin", "backup", "wait"]
  231. spin:
  232. plugin: "nav2_recoveries/Spin"
  233. backup:
  234. plugin: "nav2_recoveries/BackUp"
  235. wait:
  236. plugin: "nav2_recoveries/Wait"
  237. global_frame: odom
  238. robot_base_frame: base_link
  239. transform_timeout: 0.1
  240. use_sim_time: true
  241. simulate_ahead_time: 2.0
  242. max_rotational_vel: 1.0
  243. min_rotational_vel: 0.4
  244. rotational_acc_lim: 3.2
  245. robot_state_publisher:
  246. ros__parameters:
  247. use_sim_time: True
  248. waypoint_follower:
  249. ros__parameters:
  250. loop_rate: 20
  251. stop_on_failure: false
  252. waypoint_task_executor_plugin: "wait_at_waypoint"
  253. wait_at_waypoint:
  254. plugin: "nav2_waypoint_follower::WaitAtWaypoint"
  255. enabled: True
  256. waypoint_pause_duration: 200