|
| 1 | +amcl: |
| 2 | + ros__parameters: |
| 3 | + alpha1: 0.2 |
| 4 | + alpha2: 0.2 |
| 5 | + alpha3: 0.2 |
| 6 | + alpha4: 0.2 |
| 7 | + alpha5: 0.2 |
| 8 | + base_frame_id: "base_footprint" |
| 9 | + beam_skip_distance: 0.5 |
| 10 | + beam_skip_error_threshold: 0.9 |
| 11 | + beam_skip_threshold: 0.3 |
| 12 | + do_beamskip: false |
| 13 | + global_frame_id: "map" |
| 14 | + lambda_short: 0.1 |
| 15 | + laser_likelihood_max_dist: 2.0 |
| 16 | + laser_max_range: 100.0 |
| 17 | + laser_min_range: -1.0 |
| 18 | + laser_model_type: "likelihood_field" |
| 19 | + max_beams: 60 |
| 20 | + max_particles: 2000 |
| 21 | + min_particles: 500 |
| 22 | + odom_frame_id: "odom" |
| 23 | + pf_err: 0.05 |
| 24 | + pf_z: 0.99 |
| 25 | + recovery_alpha_fast: 0.0 |
| 26 | + recovery_alpha_slow: 0.0 |
| 27 | + resample_interval: 1 |
| 28 | + robot_model_type: "nav2_amcl::DifferentialMotionModel" |
| 29 | + save_pose_rate: 0.5 |
| 30 | + sigma_hit: 0.2 |
| 31 | + tf_broadcast: true |
| 32 | + transform_tolerance: 1.0 |
| 33 | + update_min_a: 0.2 |
| 34 | + update_min_d: 0.25 |
| 35 | + z_hit: 0.5 |
| 36 | + z_max: 0.05 |
| 37 | + z_rand: 0.5 |
| 38 | + z_short: 0.05 |
| 39 | + scan_topic: scan |
| 40 | + |
| 41 | +bt_navigator: |
| 42 | + ros__parameters: |
| 43 | + global_frame: map |
| 44 | + robot_base_frame: base_link |
| 45 | + odom_topic: odom |
| 46 | + bt_loop_duration: 10 |
| 47 | + filter_duration: 0.3 |
| 48 | + default_server_timeout: 20 |
| 49 | + wait_for_service_timeout: 1000 |
| 50 | + action_server_result_timeout: 900.0 |
| 51 | + navigators: ["navigate_to_pose", "navigate_through_poses"] |
| 52 | + navigate_to_pose: |
| 53 | + plugin: "nav2_bt_navigator::NavigateToPoseNavigator" |
| 54 | + navigate_through_poses: |
| 55 | + plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" |
| 56 | + # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: |
| 57 | + # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml |
| 58 | + # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml |
| 59 | + # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. |
| 60 | + |
| 61 | + # plugin_lib_names is used to add custom BT plugins to the executor (vector of strings). |
| 62 | + # Built-in plugins are added automatically |
| 63 | + # plugin_lib_names: [] |
| 64 | + |
| 65 | + error_code_name_prefixes: |
| 66 | + - assisted_teleop |
| 67 | + - backup |
| 68 | + - compute_path |
| 69 | + - dock_robot |
| 70 | + - drive_on_heading |
| 71 | + - follow_path |
| 72 | + - nav_thru_poses |
| 73 | + - nav_to_pose |
| 74 | + - route |
| 75 | + - spin |
| 76 | + - undock_robot |
| 77 | + - wait |
| 78 | + |
| 79 | +controller_server: |
| 80 | + ros__parameters: |
| 81 | + controller_frequency: 20.0 |
| 82 | + costmap_update_timeout: 0.30 |
| 83 | + min_x_velocity_threshold: 0.001 |
| 84 | + min_y_velocity_threshold: 0.5 |
| 85 | + min_theta_velocity_threshold: 0.001 |
| 86 | + failure_tolerance: 0.3 |
| 87 | + progress_checker_plugins: ["progress_checker"] |
| 88 | + goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" |
| 89 | + controller_plugins: ["FollowPath"] |
| 90 | + use_realtime_priority: false |
| 91 | + |
| 92 | + # Progress checker parameters |
| 93 | + progress_checker: |
| 94 | + plugin: "nav2_controller::SimpleProgressChecker" |
| 95 | + required_movement_radius: 0.5 |
| 96 | + movement_time_allowance: 10.0 |
| 97 | + # Goal checker parameters |
| 98 | + #precise_goal_checker: |
| 99 | + # plugin: "nav2_controller::SimpleGoalChecker" |
| 100 | + # xy_goal_tolerance: 0.25 |
| 101 | + # yaw_goal_tolerance: 0.25 |
| 102 | + # stateful: True |
| 103 | + general_goal_checker: |
| 104 | + stateful: True |
| 105 | + plugin: "nav2_controller::SimpleGoalChecker" |
| 106 | + xy_goal_tolerance: 0.25 |
| 107 | + yaw_goal_tolerance: 0.25 |
| 108 | + FollowPath: |
| 109 | + plugin: nav2_graceful_controller::GracefulController |
| 110 | + transform_tolerance: 0.1 |
| 111 | + min_lookahead: 0.25 |
| 112 | + max_lookahead: 1.0 |
| 113 | + initial_rotation: true |
| 114 | + initial_rotation_threshold: 0.75 |
| 115 | + prefer_final_rotation: true |
| 116 | + allow_backward: false |
| 117 | + k_phi: 2.0 |
| 118 | + k_delta: 1.0 |
| 119 | + beta: 0.4 |
| 120 | + lambda: 2.0 |
| 121 | + v_linear_min: 0.1 |
| 122 | + v_linear_max: 0.5 |
| 123 | + v_angular_max: 5.0 |
| 124 | + v_angular_min_in_place: 0.25 |
| 125 | + slowdown_radius: 1.5 |
| 126 | + |
| 127 | +local_costmap: |
| 128 | + local_costmap: |
| 129 | + ros__parameters: |
| 130 | + update_frequency: 5.0 |
| 131 | + publish_frequency: 2.0 |
| 132 | + global_frame: odom |
| 133 | + robot_base_frame: base_link |
| 134 | + rolling_window: true |
| 135 | + width: 3 |
| 136 | + height: 3 |
| 137 | + resolution: 0.05 |
| 138 | + robot_radius: 0.22 |
| 139 | + plugins: ["voxel_layer", "inflation_layer"] |
| 140 | + inflation_layer: |
| 141 | + plugin: "nav2_costmap_2d::InflationLayer" |
| 142 | + cost_scaling_factor: 3.0 |
| 143 | + inflation_radius: 0.70 |
| 144 | + voxel_layer: |
| 145 | + plugin: "nav2_costmap_2d::VoxelLayer" |
| 146 | + enabled: True |
| 147 | + publish_voxel_map: True |
| 148 | + origin_z: 0.0 |
| 149 | + z_resolution: 0.05 |
| 150 | + z_voxels: 16 |
| 151 | + max_obstacle_height: 2.0 |
| 152 | + mark_threshold: 0 |
| 153 | + observation_sources: scan |
| 154 | + scan: |
| 155 | + # A relative topic will be appended to the parent of the local_costmap namespace. |
| 156 | + # For example: |
| 157 | + # * User chosen namespace is `tb4`. |
| 158 | + # * User chosen topic is `scan`. |
| 159 | + # * Topic will be remapped to `/tb4/scan` without `local_costmap`. |
| 160 | + # * Use global topic `/scan` if you do not wish the node namespace to apply |
| 161 | + topic: scan |
| 162 | + max_obstacle_height: 2.0 |
| 163 | + clearing: True |
| 164 | + marking: True |
| 165 | + data_type: "LaserScan" |
| 166 | + raytrace_max_range: 3.0 |
| 167 | + raytrace_min_range: 0.0 |
| 168 | + obstacle_max_range: 2.5 |
| 169 | + obstacle_min_range: 0.0 |
| 170 | + static_layer: |
| 171 | + plugin: "nav2_costmap_2d::StaticLayer" |
| 172 | + map_subscribe_transient_local: True |
| 173 | + always_send_full_costmap: True |
| 174 | + |
| 175 | +global_costmap: |
| 176 | + global_costmap: |
| 177 | + ros__parameters: |
| 178 | + update_frequency: 1.0 |
| 179 | + publish_frequency: 1.0 |
| 180 | + global_frame: map |
| 181 | + robot_base_frame: base_link |
| 182 | + robot_radius: 0.22 |
| 183 | + resolution: 0.05 |
| 184 | + track_unknown_space: true |
| 185 | + plugins: ["static_layer", "obstacle_layer", "inflation_layer"] |
| 186 | + obstacle_layer: |
| 187 | + plugin: "nav2_costmap_2d::ObstacleLayer" |
| 188 | + enabled: True |
| 189 | + observation_sources: scan |
| 190 | + scan: |
| 191 | + # A relative topic will be appended to the parent of the global_costmap namespace. |
| 192 | + # For example: |
| 193 | + # * User chosen namespace is `tb4`. |
| 194 | + # * User chosen topic is `scan`. |
| 195 | + # * Topic will be remapped to `/tb4/scan` without `global_costmap`. |
| 196 | + # * Use global topic `/scan` if you do not wish the node namespace to apply |
| 197 | + topic: scan |
| 198 | + max_obstacle_height: 2.0 |
| 199 | + clearing: True |
| 200 | + marking: True |
| 201 | + data_type: "LaserScan" |
| 202 | + raytrace_max_range: 3.0 |
| 203 | + raytrace_min_range: 0.0 |
| 204 | + obstacle_max_range: 2.5 |
| 205 | + obstacle_min_range: 0.0 |
| 206 | + static_layer: |
| 207 | + plugin: "nav2_costmap_2d::StaticLayer" |
| 208 | + map_subscribe_transient_local: True |
| 209 | + inflation_layer: |
| 210 | + plugin: "nav2_costmap_2d::InflationLayer" |
| 211 | + cost_scaling_factor: 3.0 |
| 212 | + inflation_radius: 0.7 |
| 213 | + always_send_full_costmap: True |
| 214 | + |
| 215 | +# The yaml_filename does not need to be specified since it going to be set by defaults in launch. |
| 216 | +# If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py |
| 217 | +# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used. |
| 218 | +# map_server: |
| 219 | +# ros__parameters: |
| 220 | +# yaml_filename: "" |
| 221 | + |
| 222 | +map_saver: |
| 223 | + ros__parameters: |
| 224 | + save_map_timeout: 5.0 |
| 225 | + free_thresh_default: 0.25 |
| 226 | + occupied_thresh_default: 0.65 |
| 227 | + map_subscribe_transient_local: True |
| 228 | + |
| 229 | +planner_server: |
| 230 | + ros__parameters: |
| 231 | + expected_planner_frequency: 20.0 |
| 232 | + planner_plugins: ["GridBased"] |
| 233 | + costmap_update_timeout: 1.0 |
| 234 | + GridBased: |
| 235 | + plugin: "nav2_navfn_planner::NavfnPlanner" |
| 236 | + tolerance: 0.5 |
| 237 | + use_astar: false |
| 238 | + allow_unknown: true |
| 239 | + |
| 240 | +smoother_server: |
| 241 | + ros__parameters: |
| 242 | + smoother_plugins: ["simple_smoother"] |
| 243 | + simple_smoother: |
| 244 | + plugin: "nav2_smoother::SimpleSmoother" |
| 245 | + tolerance: 1.0e-10 |
| 246 | + max_its: 1000 |
| 247 | + do_refinement: True |
| 248 | + |
| 249 | +behavior_server: |
| 250 | + ros__parameters: |
| 251 | + local_costmap_topic: local_costmap/costmap_raw |
| 252 | + global_costmap_topic: global_costmap/costmap_raw |
| 253 | + local_footprint_topic: local_costmap/published_footprint |
| 254 | + global_footprint_topic: global_costmap/published_footprint |
| 255 | + cycle_frequency: 10.0 |
| 256 | + behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"] |
| 257 | + spin: |
| 258 | + plugin: "nav2_behaviors::Spin" |
| 259 | + backup: |
| 260 | + plugin: "nav2_behaviors::BackUp" |
| 261 | + acceleration_limit: 2.5 |
| 262 | + deceleration_limit: -2.5 |
| 263 | + minimum_speed: 0.10 |
| 264 | + drive_on_heading: |
| 265 | + plugin: "nav2_behaviors::DriveOnHeading" |
| 266 | + acceleration_limit: 2.5 |
| 267 | + deceleration_limit: -2.5 |
| 268 | + minimum_speed: 0.10 |
| 269 | + wait: |
| 270 | + plugin: "nav2_behaviors::Wait" |
| 271 | + assisted_teleop: |
| 272 | + plugin: "nav2_behaviors::AssistedTeleop" |
| 273 | + local_frame: odom |
| 274 | + global_frame: map |
| 275 | + robot_base_frame: base_link |
| 276 | + transform_tolerance: 0.1 |
| 277 | + simulate_ahead_time: 2.0 |
| 278 | + max_rotational_vel: 1.0 |
| 279 | + min_rotational_vel: 0.4 |
| 280 | + rotational_acc_lim: 3.2 |
| 281 | + |
| 282 | +waypoint_follower: |
| 283 | + ros__parameters: |
| 284 | + loop_rate: 20 |
| 285 | + stop_on_failure: false |
| 286 | + action_server_result_timeout: 900.0 |
| 287 | + waypoint_task_executor_plugin: "wait_at_waypoint" |
| 288 | + wait_at_waypoint: |
| 289 | + plugin: "nav2_waypoint_follower::WaitAtWaypoint" |
| 290 | + enabled: True |
| 291 | + waypoint_pause_duration: 200 |
| 292 | + |
| 293 | +velocity_smoother: |
| 294 | + ros__parameters: |
| 295 | + smoothing_frequency: 20.0 |
| 296 | + scale_velocities: False |
| 297 | + feedback: "OPEN_LOOP" |
| 298 | + max_velocity: [0.5, 0.0, 2.0] |
| 299 | + min_velocity: [-0.5, 0.0, -2.0] |
| 300 | + max_accel: [2.5, 0.0, 3.2] |
| 301 | + max_decel: [-2.5, 0.0, -3.2] |
| 302 | + odom_topic: "odom" |
| 303 | + odom_duration: 0.1 |
| 304 | + deadband_velocity: [0.0, 0.0, 0.0] |
| 305 | + velocity_timeout: 1.0 |
| 306 | + |
| 307 | +collision_monitor: |
| 308 | + ros__parameters: |
| 309 | + base_frame_id: "base_footprint" |
| 310 | + odom_frame_id: "odom" |
| 311 | + cmd_vel_in_topic: "cmd_vel_smoothed" |
| 312 | + cmd_vel_out_topic: "cmd_vel" |
| 313 | + state_topic: "collision_monitor_state" |
| 314 | + transform_tolerance: 0.2 |
| 315 | + source_timeout: 1.0 |
| 316 | + base_shift_correction: True |
| 317 | + stop_pub_timeout: 2.0 |
| 318 | + # Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types, |
| 319 | + # and robot footprint for "approach" action type. |
| 320 | + polygons: ["FootprintApproach"] |
| 321 | + FootprintApproach: |
| 322 | + type: "polygon" |
| 323 | + action_type: "approach" |
| 324 | + footprint_topic: "local_costmap/published_footprint" |
| 325 | + time_before_collision: 1.2 |
| 326 | + simulation_time_step: 0.1 |
| 327 | + min_points: 6 |
| 328 | + visualize: False |
| 329 | + enabled: True |
| 330 | + observation_sources: ["scan"] |
| 331 | + scan: |
| 332 | + type: "scan" |
| 333 | + topic: "scan" |
| 334 | + min_height: 0.15 |
| 335 | + max_height: 2.0 |
| 336 | + enabled: True |
| 337 | + |
| 338 | +docking_server: |
| 339 | + ros__parameters: |
| 340 | + controller_frequency: 50.0 |
| 341 | + initial_perception_timeout: 5.0 |
| 342 | + wait_charge_timeout: 5.0 |
| 343 | + dock_approach_timeout: 30.0 |
| 344 | + undock_linear_tolerance: 0.05 |
| 345 | + undock_angular_tolerance: 0.1 |
| 346 | + max_retries: 3 |
| 347 | + base_frame: "base_link" |
| 348 | + fixed_frame: "odom" |
| 349 | + dock_backwards: false |
| 350 | + dock_prestaging_tolerance: 0.5 |
| 351 | + |
| 352 | + # Types of docks |
| 353 | + dock_plugins: ['simple_charging_dock'] |
| 354 | + simple_charging_dock: |
| 355 | + plugin: 'opennav_docking::SimpleChargingDock' |
| 356 | + docking_threshold: 0.05 |
| 357 | + staging_x_offset: -0.7 |
| 358 | + use_external_detection_pose: true |
| 359 | + use_battery_status: false # true |
| 360 | + use_stall_detection: false # true |
| 361 | + |
| 362 | + external_detection_timeout: 1.0 |
| 363 | + external_detection_translation_x: -0.18 |
| 364 | + external_detection_translation_y: 0.0 |
| 365 | + external_detection_rotation_roll: -1.57 |
| 366 | + external_detection_rotation_pitch: -1.57 |
| 367 | + external_detection_rotation_yaw: 0.0 |
| 368 | + filter_coef: 0.1 |
| 369 | + |
| 370 | + # Dock instances |
| 371 | + # The following example illustrates configuring dock instances. |
| 372 | + # docks: ['home_dock'] # Input your docks here |
| 373 | + # home_dock: |
| 374 | + # type: 'simple_charging_dock' |
| 375 | + # frame: map |
| 376 | + # pose: [0.0, 0.0, 0.0] |
| 377 | + |
| 378 | + controller: |
| 379 | + k_phi: 3.0 |
| 380 | + k_delta: 2.0 |
| 381 | + v_linear_min: 0.15 |
| 382 | + v_linear_max: 0.15 |
| 383 | + use_collision_detection: true |
| 384 | + costmap_topic: "/local_costmap/costmap_raw" |
| 385 | + footprint_topic: "/local_costmap/published_footprint" |
| 386 | + transform_tolerance: 0.1 |
| 387 | + projection_time: 5.0 |
| 388 | + simulation_step: 0.1 |
| 389 | + dock_collision_threshold: 0.3 |
| 390 | + |
| 391 | +loopback_simulator: |
| 392 | + ros__parameters: |
| 393 | + base_frame_id: "base_footprint" |
| 394 | + odom_frame_id: "odom" |
| 395 | + map_frame_id: "map" |
| 396 | + scan_frame_id: "base_scan" # tb4_loopback_simulator.launch.py remaps to 'rplidar_link' |
| 397 | + update_duration: 0.02 |
0 commit comments