diff --git a/params/global_planner/rrt_planner_params.yaml b/params/global_planner/rrt_planner_params.yaml new file mode 100644 index 0000000000000000000000000000000000000000..a5bf6ea1fe5381336a1b6049bd1e20f9c72f5a46 --- /dev/null +++ b/params/global_planner/rrt_planner_params.yaml @@ -0,0 +1,29 @@ +base_global_planner: "rrt_planner/RrtPlanner" + +RrtPlanner: + # Global + debug: true + outmap_prohibited: true + smooth_path: true + + # RRT parameters + dimension: 2 + # reconfigurable + star: true + range: 35.0 + precision: 0.1 + map_precision: 0.2 + neighbour_threshold: 0.4 + costfunc_orig_w: 0.5 + max_nodes: 30000 + max_time: 3.0 + robot_radius: 0.3 + robot_speed: 0.5 + rate: 1 + frame_id: map + + cost_function_type: 1 #0: Euclidean, 1: SRS + sampler_type: 1 #0: UniformTree, 1: UniformCSpace, 2: Density + simulator_type: 1 #0: Static, 1: ConstSpeed, 2: LinearSRS + edge_connector_type: 0 #0: Linear + diff --git a/params/rrt_move_base_params.yaml b/params/rrt_move_base_params.yaml new file mode 100644 index 0000000000000000000000000000000000000000..4d64aa3b6f40269b0ef3dca3097950d261a1516f --- /dev/null +++ b/params/rrt_move_base_params.yaml @@ -0,0 +1,29 @@ +#base_global_planner: #defined in the global planner parameter file +#base_local_planner: #define in the local planner parameter file + +recovery_behavior_enabled: false +recovery_behaviors: + - {name: rotational_recovery, type: rotational_recovery/RotationalRecovery} + - {name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery} + - {name: rotate_recovery, type: rotate_recovery/RotateRecovery} + - {name: twist_recovery, type: twist_recovery/TwistRecovery} + - {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery} + +controller_frequency: 4.0 +planner_patience: 8.0 +controller_patience: 5.0 +planner_frequency: 5.0 +max_planning_retries: 5.0 + +conservative_reset_dist: 3.0 + +linear_x: -0.5 +linear_y: 0.0 +angular_z: 0.0 + +clearing_rotation_allowed: false +clearing_radius: 0.46 +shutdown_costmaps: false + +oscillation_timeout: -1.0 +oscillation_distance: 0.2