git commit -m "first commit"
This commit is contained in:
44
mir_robot/mir_navigation/config/base_local_planner_params.yaml
Executable file
44
mir_robot/mir_navigation/config/base_local_planner_params.yaml
Executable file
@@ -0,0 +1,44 @@
|
||||
base_local_planner: base_local_planner/TrajectoryPlannerROS
|
||||
TrajectoryPlannerROS:
|
||||
# Robot configuration
|
||||
acc_lim_x: 1.5
|
||||
acc_lim_y: 0
|
||||
acc_lim_theta: 2.0
|
||||
max_vel_x: 0.8
|
||||
min_vel_x: 0.1
|
||||
max_vel_theta: 1.0
|
||||
min_vel_theta: -1.0
|
||||
min_in_place_vel_theta: 0.2
|
||||
escape_vel: -0.1
|
||||
holonomic_robot: false
|
||||
|
||||
# Goal tolerance
|
||||
yaw_goal_tolerance: 0.03
|
||||
xy_goal_tolerance: 0.08
|
||||
latch_xy_goal_tolerance: true
|
||||
|
||||
# Forward simulaton parameters
|
||||
sim_time: 1.2
|
||||
sim_granularity: 0.025
|
||||
angular_sim_granularity: 0.04
|
||||
vx_samples: 15
|
||||
vtheta_samples: 20
|
||||
controller_frequency: 10
|
||||
|
||||
# Trajectory scoring parameters
|
||||
meter_scoring: true
|
||||
pdist_scale: 2.2 #0.6
|
||||
gdist_scale: 0.8 #0.8
|
||||
occdist_scale: 0.1
|
||||
heading_lookahead: 0.325
|
||||
heading_scoring: true
|
||||
heading_scoring_timestep: 0.8
|
||||
dwa: true
|
||||
publish_cost_grid: false
|
||||
global_frame_id: map
|
||||
|
||||
# Oscillation prevention parameter
|
||||
oscillation_reset_dist: 0.05
|
||||
|
||||
# Global plan parameters
|
||||
prune_plan: true
|
||||
65
mir_robot/mir_navigation/config/costmap_common_params.yaml
Executable file
65
mir_robot/mir_navigation/config/costmap_common_params.yaml
Executable file
@@ -0,0 +1,65 @@
|
||||
robot_base_frame: $(arg prefix)base_footprint
|
||||
transform_tolerance: 0.2
|
||||
obstacle_range: 3.0
|
||||
#mark_threshold: 1
|
||||
publish_voxel_map: true
|
||||
footprint_padding: 0.0
|
||||
navigation_map:
|
||||
map_topic: /map
|
||||
virtual_walls_map:
|
||||
map_topic: /virtual_walls/map
|
||||
use_maximum: true
|
||||
lethal_cost_threshold: 100
|
||||
preferred_zones_map:
|
||||
map_topic: /preferred_zones/map
|
||||
lethal_cost_threshold: 100
|
||||
use_maximum: true
|
||||
unpreferred_zones_map:
|
||||
map_topic: /unpreferred_zones/map
|
||||
lethal_cost_threshold: 100
|
||||
use_maximum: true
|
||||
critical_zones_map:
|
||||
map_topic: /critical_zones/map
|
||||
lethal_cost_threshold: 100
|
||||
use_maximum: true
|
||||
# subscribe_to_updates: true
|
||||
direction_zones_map:
|
||||
map_topic: /direction_zones/map
|
||||
base_frame_id: $(arg prefix)base_footprint
|
||||
lethal_cost_threshold: 100
|
||||
use_maximum: true
|
||||
# subscribe_to_updates: true
|
||||
obstacles:
|
||||
observation_sources: b_scan_marking b_scan_clearing f_scan_marking f_scan_clearing
|
||||
b_scan_marking:
|
||||
topic: b_scan_rep117
|
||||
data_type: LaserScan
|
||||
clearing: false
|
||||
marking: true
|
||||
inf_is_valid: false
|
||||
min_obstacle_height: 0.13
|
||||
max_obstacle_height: 0.25
|
||||
b_scan_clearing:
|
||||
topic: b_scan_rep117
|
||||
data_type: LaserScan
|
||||
clearing: true
|
||||
marking: false
|
||||
inf_is_valid: false
|
||||
min_obstacle_height: 0.13
|
||||
max_obstacle_height: 0.25
|
||||
f_scan_marking:
|
||||
topic: f_scan_rep117
|
||||
data_type: LaserScan
|
||||
clearing: false
|
||||
marking: true
|
||||
inf_is_valid: false
|
||||
min_obstacle_height: 0.13
|
||||
max_obstacle_height: 0.25
|
||||
f_scan_clearing:
|
||||
topic: f_scan_rep117
|
||||
data_type: LaserScan
|
||||
clearing: true
|
||||
marking: false
|
||||
inf_is_valid: false
|
||||
min_obstacle_height: 0.13
|
||||
max_obstacle_height: 0.25
|
||||
14
mir_robot/mir_navigation/config/costmap_global_params.yaml
Executable file
14
mir_robot/mir_navigation/config/costmap_global_params.yaml
Executable file
@@ -0,0 +1,14 @@
|
||||
global_costmap:
|
||||
global_frame: map
|
||||
update_frequency: 1.0
|
||||
publish_frequency: 1.0
|
||||
raytrace_range: 2.0
|
||||
resolution: 0.05
|
||||
z_resolution: 0.2
|
||||
rolling_window: false
|
||||
z_voxels: 10
|
||||
inflation:
|
||||
cost_scaling_factor: 4.0 # Exponential rate at which the obstacle cost drops off (default: 10). Must be chosen so that the cost value is > 0 at robot's circumscribed radius.
|
||||
inflation_radius: 0.8 # Max. distance from an obstacle at which costs are incurred for planning paths. Must be > robot's circumscribed radius.
|
||||
|
||||
# plugins are loaded via costmap_global_params_plugins_[mapping|planning].yaml
|
||||
13
mir_robot/mir_navigation/config/costmap_global_params_plugins.yaml
Executable file
13
mir_robot/mir_navigation/config/costmap_global_params_plugins.yaml
Executable file
@@ -0,0 +1,13 @@
|
||||
global_costmap:
|
||||
frame_id: map
|
||||
plugins:
|
||||
- {name: navigation_map, type: "costmap_2d::StaticLayer" }
|
||||
- {name: virtual_walls_map, type: "costmap_2d::StaticLayer" }
|
||||
- {name: obstacles, type: "costmap_2d::VoxelLayer" }
|
||||
- {name: preferred_zones_map, type: "costmap_2d::PreferredLayer" }
|
||||
- {name: unpreferred_zones_map, type: "costmap_2d::UnPreferredLayer" }
|
||||
- {name: direction_zones_map, type: "costmap_2d::DirectionalLayer" }
|
||||
- {name: inflation, type: "costmap_2d::InflationLayer" }
|
||||
- {name: critical_zones_map, type: "costmap_2d::CriticalLayer" }
|
||||
# obstacles:
|
||||
# track_unknown_space: true
|
||||
18
mir_robot/mir_navigation/config/costmap_local_params.yaml
Executable file
18
mir_robot/mir_navigation/config/costmap_local_params.yaml
Executable file
@@ -0,0 +1,18 @@
|
||||
local_costmap:
|
||||
global_frame: $(arg prefix)odom
|
||||
update_frequency: 5.0
|
||||
publish_frequency: 5.0
|
||||
rolling_window: true
|
||||
raytrace_range: 2.0
|
||||
resolution: 0.05
|
||||
z_resolution: 0.15
|
||||
z_voxels: 8
|
||||
inflation:
|
||||
cost_scaling_factor: 5.0 # Exponential rate at which the obstacle cost drops off (default: 10). Must be chosen so that the cost value is > 0 at robot's circumscribed radius.
|
||||
inflation_radius: 0.8 # Max. distance from an obstacle at which costs are incurred for planning paths. Must be > robot's circumscribed radius.
|
||||
width: 10.0
|
||||
height: 10.0
|
||||
origin_x: 0.0
|
||||
origin_y: 0.0
|
||||
|
||||
# plugins are loaded via costmap_local_params_plugins_[mapping|planning].yaml
|
||||
7
mir_robot/mir_navigation/config/costmap_local_params_plugins.yaml
Executable file
7
mir_robot/mir_navigation/config/costmap_local_params_plugins.yaml
Executable file
@@ -0,0 +1,7 @@
|
||||
local_costmap:
|
||||
frame_id: odom
|
||||
plugins:
|
||||
- {name: virtual_walls_map, type: "costmap_2d::StaticLayer" } # các ô chi phí xung quanh "tường ảo" sẽ được tăng lên giá trị cao hơn, tạo ra một vùng an toàn xung quanh các vật cản.
|
||||
- {name: obstacles, type: "costmap_2d::VoxelLayer" } # các ô chi phí xung quanh các "vật cản" sẽ được tăng lên giá trị cao hơn, tạo ra một vùng an toàn xung quanh các vật cản.
|
||||
- {name: inflation, type: "costmap_2d::InflationLayer" } # các ô chi phí xung quanh các "vật cản" sẽ được tăng lên giá trị cao hơn, tạo ra một vùng an toàn xung quanh các vật cản.
|
||||
# - {name: critical_zones_map, type: "costmap_2d::CriticalLayer" }
|
||||
55
mir_robot/mir_navigation/config/dwa_local_planner_params.yaml
Executable file
55
mir_robot/mir_navigation/config/dwa_local_planner_params.yaml
Executable file
@@ -0,0 +1,55 @@
|
||||
base_local_planner: dwa_local_planner/DWAPlannerROS
|
||||
DWAPlannerROS:
|
||||
# Robot configuration
|
||||
max_vel_x: 0.8
|
||||
min_vel_x: -0.2
|
||||
|
||||
max_vel_y: 0.0 # diff drive robot
|
||||
min_vel_y: 0.0 # diff drive robot
|
||||
|
||||
max_trans_vel: 0.8 # choose slightly less than the base's capability
|
||||
min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity
|
||||
trans_stopped_vel: 0.03
|
||||
|
||||
# Warning!
|
||||
# do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities
|
||||
# are non-negligible and small in place rotational velocities will be created.
|
||||
|
||||
max_rot_vel: 1.0 # choose slightly less than the base's capability
|
||||
min_rot_vel: 0.1 # this is the min angular velocity when there is negligible translational velocity
|
||||
rot_stopped_vel: 0.1
|
||||
|
||||
acc_lim_x: 1.5
|
||||
acc_lim_y: 0.0 # diff drive robot
|
||||
acc_limit_trans: 1.5
|
||||
acc_lim_theta: 2.0
|
||||
|
||||
# Goal tolerance
|
||||
yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide)
|
||||
xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2
|
||||
latch_xy_goal_tolerance: true
|
||||
|
||||
# Forward simulation
|
||||
sim_time: 1.2
|
||||
vx_samples: 15
|
||||
vy_samples: 1 # diff drive robot, there is only one sample
|
||||
vtheta_samples: 20
|
||||
|
||||
# Trajectory scoring
|
||||
path_distance_bias: 64.0 # default: 32.0 mir: 32.0 - weighting for how much it should stick to the global path plan
|
||||
goal_distance_bias: 12.0 # default: 24.0 mir: 48.0 - weighting for how much it should attempt to reach its goal
|
||||
occdist_scale: 0.5 # default: 0.01 mir: 0.01 - weighting for how much the controller should avoid obstacles
|
||||
forward_point_distance: 0.325 # default: 0.325 mir: 0.325 - how far along to place an additional scoring point
|
||||
stop_time_buffer: 0.2 # default: 0.2 mir: 0.2 - amount of time a robot must stop before colliding for a valid traj.
|
||||
scaling_speed: 0.25 # default: 0.25 mir: 0.25 - absolute velocity at which to start scaling the robot's footprint
|
||||
max_scaling_factor: 0.2 # default: 0.2 mir: 0.2 - how much to scale the robot's footprint when at speed.
|
||||
prune_plan: true
|
||||
|
||||
# Oscillation prevention
|
||||
oscillation_reset_dist: 0.05 # 0.05 - how far to travel before resetting oscillation flags, in m
|
||||
oscillation_reset_angle: 0.2 # 0.2 - the angle the robot must turn before resetting Oscillation flags, in rad
|
||||
|
||||
# Debugging
|
||||
publish_traj_pc : true
|
||||
publish_cost_grid_pc: true
|
||||
global_frame_id: /odom # or <robot namespace>/odom
|
||||
102
mir_robot/mir_navigation/config/dwb_local_planner_params.yaml
Executable file
102
mir_robot/mir_navigation/config/dwb_local_planner_params.yaml
Executable file
@@ -0,0 +1,102 @@
|
||||
base_local_planner: nav_core_adapter::LocalPlannerAdapter
|
||||
LocalPlannerAdapter:
|
||||
planner_name: dwb_local_planner::DWBLocalPlanner
|
||||
DWBLocalPlanner:
|
||||
# Robot configuration
|
||||
max_vel_x: 1.5
|
||||
min_vel_x: -0.3
|
||||
|
||||
max_vel_y: 0.0 # diff drive robot
|
||||
min_vel_y: 0.0 # diff drive robot
|
||||
|
||||
max_speed_xy: 2.0 # max_trans_vel: 0.8 # choose slightly less than the base's capability
|
||||
min_speed_xy: 0.1 # min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity
|
||||
|
||||
max_vel_theta: 1.0 # max_rot_vel: 1.0 # choose slightly less than the base's capability
|
||||
min_speed_theta: 0.1 # min_rot_vel: 0.1 default: 0.4 # this is the min angular velocity when there is negligible translational velocity
|
||||
|
||||
acc_lim_x: 0.4
|
||||
acc_lim_y: 0.0 # diff drive robot
|
||||
acc_lim_theta: 1.0
|
||||
decel_lim_x: -1.0
|
||||
decel_lim_y: -0.0
|
||||
decel_lim_theta: -1.0
|
||||
|
||||
# Goal tolerance
|
||||
yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide)
|
||||
xy_goal_tolerance: 0.05 # xy_goal_tolerance > (sim_time * min_vel_x) / 2
|
||||
# latch_xy_goal_tolerance: true
|
||||
|
||||
# Whether to split the path into segments or not
|
||||
# Requires https://github.com/locusrobotics/robot_navigation/pull/50
|
||||
split_path: true
|
||||
|
||||
# Forward simulation (trajectory generation)
|
||||
trajectory_generator_name: dwb_plugins::StandardTrajectoryGenerator # or dwb_plugins::LimitedAccelGenerator
|
||||
sim_time: 1.2
|
||||
vx_samples: 12
|
||||
vy_samples: 1 # diff drive robot, there is only one sample
|
||||
vtheta_samples: 12
|
||||
discretize_by_time: true
|
||||
angular_granularity: 0.05
|
||||
linear_granularity: 0.1
|
||||
# sim_period
|
||||
include_last_point: true
|
||||
|
||||
# Goal checking
|
||||
goal_checker_name: dwb_plugins::SimpleGoalChecker
|
||||
# stateful: true
|
||||
|
||||
# Critics (trajectory scoring)
|
||||
# default_critic_namespaces: [dwb_critics, mir_dwb_critics]
|
||||
critics: [RotateToGoal, ObstacleFootprint, PathAlign, PathDistPruned, PathProgress]
|
||||
# critics: [MetratronikTechnik]
|
||||
# MetratronikTechnik:
|
||||
# scale: 0.01
|
||||
# sq_window: 1.0
|
||||
# xy_goal_tolerance: 0.02
|
||||
# trans_stopped_velocity: 0.3
|
||||
# slowing_factor: 1.0
|
||||
# angle_threshold: 0.436332313
|
||||
# Lm: 0.25
|
||||
RotateToGoal:
|
||||
scale: 100.0
|
||||
trans_stopped_velocity: 0.25
|
||||
lookahead_time: -1.0
|
||||
slowing_factor: 10.0
|
||||
ObstacleFootprint:
|
||||
scale: 0.01 # default: 0.01 mir: 0.01 - weighting for how much the controller should avoid obstacles
|
||||
max_scaling_factor: 0.5 # default: 0.2 mir: 0.2 - how much to scale the robot's footprint when at speed.
|
||||
scaling_speed: 0.25 # default: 0.25 mir: 0.25 - absolute velocity at which to start scaling the robot's footprint
|
||||
sum_scores: false # if true, return sum of scores of all trajectory points instead of only last one
|
||||
PathAlign:
|
||||
scale: 16.0
|
||||
forward_point_distance: 0.325 # default: 0.325 mir: 0.325 - how far along to place an additional scoring point
|
||||
PathDistPruned:
|
||||
scale: 0.01 # default: 32.0 mir: 32.0 - weighting for how much it should stick to the global path plan
|
||||
class: 'mir_dwb_critics::PathDistPruned'
|
||||
PathProgress:
|
||||
scale: 24.0 # default: 24.0 mir: 48.0 - weighting for how much it should attempt to reach its goal
|
||||
heading_scale: 0.01
|
||||
class: 'mir_dwb_critics::PathProgress'
|
||||
xy_local_goal_tolerance: 0.5
|
||||
angle_threshold: 0.523598776 # 30 degrees
|
||||
# angle_threshold: 0.785398163 # 45 degrees
|
||||
|
||||
# Prune already passed poses from plan
|
||||
prune_plan: true
|
||||
prune_distance: 1.0 # Old poses farther away than prune_distance (in m) will be pruned.
|
||||
# If the robot ever gets away further than this distance from the plan,
|
||||
# the error "Resulting plan has 0 poses in it" will be thrown and
|
||||
# replanning will be triggered.
|
||||
|
||||
# Debugging
|
||||
publish_cost_grid_pc: true
|
||||
debug_trajectory_details: false
|
||||
publish_evaluation: true
|
||||
publish_global_plan: true
|
||||
publish_input_params: true
|
||||
publish_local_plan: true
|
||||
publish_trajectories: true
|
||||
publish_transformed_plan: true
|
||||
marker_lifetime: 0.5
|
||||
44
mir_robot/mir_navigation/config/eband_local_planner_params.yaml
Executable file
44
mir_robot/mir_navigation/config/eband_local_planner_params.yaml
Executable file
@@ -0,0 +1,44 @@
|
||||
base_local_planner: eband_local_planner/EBandPlannerROS
|
||||
EBandPlannerROS:
|
||||
# Robot configuration
|
||||
max_vel_lin: 0.8 # choose slightly less than the base's capability
|
||||
min_vel_lin: 0.1 # this is the min trans velocity when there is negligible rotational velocity
|
||||
trans_stopped_vel: 0.03
|
||||
|
||||
max_vel_th: 1.0 # choose slightly less than the base's capability
|
||||
min_vel_th: 0.1 # this is the min angular velocity when there is negligible translational velocity
|
||||
rot_stopped_vel: 0.1
|
||||
|
||||
min_in_place_vel_th: 0.1 # Minimum in-place angular velocity
|
||||
in_place_trans_vel: 0.0 # Minimum in place linear velocity
|
||||
|
||||
max_acceleration: 1.5 # Maximum allowable acceleration
|
||||
max_translational_acceleration: 1.5 # Maximum linear acceleration
|
||||
max_rotational_acceleration: 2.0 # Maximum angular acceleration
|
||||
|
||||
# Goal tolerance
|
||||
yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide)
|
||||
xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2
|
||||
|
||||
# Elastic Band Parameters
|
||||
eband_min_relative_overlap: 0.7 # Min distance that denotes connectivity between consecutive bubbles
|
||||
eband_tiny_bubble_distance: 0.01 # Bubble geometric bound regarding tiny bubble distance
|
||||
eband_tiny_bubble_expansion: 0.01 # Bubble geometric bound regarding tiny bubble expansion
|
||||
eband_internal_force_gain: 1.0 # Force gain of forces between consecutive bubbles that tend to stretch the elastic band
|
||||
eband_external_force_gain: 2.0 # Force gain of forces that tend to move the bubbles away from obstacles
|
||||
num_iterations_eband_optimization: 3 # Number of iterations for eband optimization
|
||||
eband_equilibrium_approx_max_recursion_depth: 4 # Number of iterations for reaching the equilibrium between internal and external forces
|
||||
eband_equilibrium_relative_overshoot: 0.75 # Maximum relative equlibrium overshoot
|
||||
eband_significant_force_lower_bound: 0.15 # Minimum magnitude of force that is considered significant and used in the calculations
|
||||
costmap_weight: 10.0 # Costmap weight factor used in the calculation of distance to obstacles
|
||||
|
||||
# Trajectory Controller Parameters
|
||||
k_prop: 4.0 # Proportional gain of the PID controller
|
||||
k_damp: 3.5 # Damping gain of the PID controller
|
||||
Ctrl_Rate: 10.0 # Control rate
|
||||
virtual_mass: 0.75 # Virtual mass
|
||||
rotation_correction_threshold: 0.5 # Rotation correction threshold
|
||||
differential_drive: True # Denotes whether to use the differential drive mode
|
||||
bubble_velocity_multiplier: 2.0 # Multiplier of bubble radius
|
||||
rotation_threshold_multiplier: 1.0 # Multiplier of rotation threshold
|
||||
disallow_hysteresis: False # Determines whether to try getting closer to the goal, in case of going past the tolerance
|
||||
81
mir_robot/mir_navigation/config/mir_local_planner_params.yaml
Executable file
81
mir_robot/mir_navigation/config/mir_local_planner_params.yaml
Executable file
@@ -0,0 +1,81 @@
|
||||
base_local_planner: mirLocalPlanner/MIRPlannerROS
|
||||
MIRPlannerROS:
|
||||
# Robot configuration
|
||||
max_vel_x: 0.8
|
||||
min_vel_x: -0.2
|
||||
|
||||
min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity
|
||||
|
||||
# Warning!
|
||||
# do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities
|
||||
# are non-negligible and small in place rotational velocities will be created.
|
||||
|
||||
max_rot_vel: 1.0 # choose slightly less than the base's capability
|
||||
min_rot_vel: 0.1 # this is the min angular velocity when there is negligible translational velocity
|
||||
|
||||
acc_lim_x: 1.5
|
||||
acc_lim_y: 0.0 # diff drive robot
|
||||
acc_lim_th: 2.0
|
||||
min_inplace_rot: 0.15
|
||||
max_inplace_rot: 0.6
|
||||
min_in_place_rotational_vel: 0.2
|
||||
escape_vel: -0.1
|
||||
holonomic_robot: false
|
||||
|
||||
# Goal tolerance
|
||||
yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide)
|
||||
xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2
|
||||
|
||||
# Forward simulaton
|
||||
sim_time: 1.2
|
||||
sim_granularity: 0.025
|
||||
vx_samples: 15
|
||||
vth_samples: 20
|
||||
vtheta_samples: 20
|
||||
|
||||
# Trajectory scoring
|
||||
path_distance_bias: 0.4 # weighting for how much it should stick to the global path plan
|
||||
goal_distance_bias: 0.6 # weighting for how much it should attempt to reach its goal
|
||||
occdist_scale: 0.01 # weighting for how much the controller should avoid obstacles
|
||||
forward_point_distance: 0.325 # how far along to place an additional scoring point
|
||||
stop_time_buffer: 0.2 # amount of time a robot must stop before colliding for a valid traj.
|
||||
scaling_speed: 0.25 # absolute velocity at which to start scaling the robot's footprint
|
||||
max_scaling_factor: 0.2 # how much to scale the robot's footprint when at speed.
|
||||
heading_lookahead: 0.325
|
||||
dwa: true
|
||||
|
||||
# Oscillation prevention
|
||||
oscillation_reset_dist: 0.05 # how far to travel before resetting oscillation flags, in m
|
||||
|
||||
|
||||
# Debugging
|
||||
publish_visualization: false
|
||||
publish_cost_grid_pc: false
|
||||
global_frame_id: odom
|
||||
|
||||
# MiR specific parameters
|
||||
tau_p: 5.0 # The proportional value in the CTE PID tracking
|
||||
tau_i: 0.1 # The integral value in the CTE PID tracking
|
||||
tau_d: 0.5 # The differential value in the CTE PID tracking
|
||||
tau_w: 9.0 # The proportional angle value in the CTE tracking
|
||||
|
||||
k_rho: 1.0 # The proportional value to goal in Goal tracking
|
||||
k_alfa: 8.0 # The diff angle between the robot and the goal in the Goal tracking
|
||||
k_beta: -2.5 # The angle to the goal from the robot in the Goal tracking
|
||||
|
||||
blocked_path_dist: 3.0 # At what distance should the planner react when the path is blocked
|
||||
blocked_path_dev: 60.0 # How far can we move from the planned path when it is blocked
|
||||
blocked_path_action: new_plan # Which action to take, when path is blocked
|
||||
occ_path_dist: 3.0 # At what distance should the planner react when the path is near obstacle
|
||||
occ_path_dev: 15.0 # How far can we move from the planned path when the path is near a obstacle
|
||||
occ_path_level: 120.0 # Threshold level for a obstacle
|
||||
|
||||
cte_look_ahead: 0.2 # The max/min distance to add for the CTE tracking
|
||||
|
||||
penalize_negative_x: true # Whether to penalize trajectories that have negative x velocities.
|
||||
|
||||
# non-dynamic parameters
|
||||
dist_towards_obstacles: 1.5
|
||||
dist_towards_obstacles_trolley: 1.75
|
||||
goal_seek_tolerance: 2.0
|
||||
goal_seek_tolerance_trolley: 0.25
|
||||
46
mir_robot/mir_navigation/config/move_base_common_params.yaml
Executable file
46
mir_robot/mir_navigation/config/move_base_common_params.yaml
Executable file
@@ -0,0 +1,46 @@
|
||||
### footprint
|
||||
# footprint: [[0.488,-0.293],[0.488,0.293],[-0.412,0.293],[-0.412,-0.293]] # mir 100
|
||||
footprint: [[0.405,-0.293],[0.405,0.293],[-0.412,0.293],[-0.412,-0.293]] # mir 250
|
||||
# footprint: [[0.394,-0.385],[0.394,0.385],[-0.363,0.385],[-0.363,-0.385]]
|
||||
|
||||
### replanning
|
||||
controller_frequency: 15.0 # run controller at 5.0 Hz
|
||||
controller_patience: 2.0 # if the controller failed, clear obstacles and retry; after 15.0 s, abort and replan
|
||||
planner_frequency: 0.0 # don't continually replan (only when controller failed)
|
||||
planner_patience: 5.0 # if the first planning attempt failed, abort planning retries after 5.0 s...
|
||||
max_planning_retries: 5 # ... or after 10 attempts (whichever happens first)
|
||||
oscillation_timeout: 30.0 # abort controller and trigger recovery behaviors after 30.0 s
|
||||
oscillation_distance: 0.3
|
||||
### recovery behaviors
|
||||
recovery_behavior_enabled: true
|
||||
recovery_behaviors: [
|
||||
{name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery},
|
||||
{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery},
|
||||
# {name: particular, type: twist_recovery/TwistRecovery},
|
||||
# {name: by_pass, type: direction_zones_recovery/DirectionZonesRecovery},
|
||||
]
|
||||
|
||||
conservative_reset:
|
||||
reset_distance: 3.0 # clear obstacles farther away than 3.0 m
|
||||
force_updating: true
|
||||
# invert_area_to_clear: true
|
||||
|
||||
aggressive_reset:
|
||||
reset_distance: 3.0
|
||||
force_updating: true
|
||||
|
||||
particular:
|
||||
linear_x: -0.3
|
||||
linear_y: 0.0
|
||||
angular_z: 0.0
|
||||
duration: 1.5
|
||||
|
||||
# advoicedance:
|
||||
# use_local_frame: false
|
||||
# plan_topic: /move_base_node/SBPLLatticePlanner/plan
|
||||
# planning_distance: 4.0
|
||||
|
||||
by_pass:
|
||||
reset_distance: 8.0
|
||||
force_updating: true
|
||||
affected_maps: global
|
||||
46
mir_robot/mir_navigation/config/pose_local_planner_params.yaml
Executable file
46
mir_robot/mir_navigation/config/pose_local_planner_params.yaml
Executable file
@@ -0,0 +1,46 @@
|
||||
base_local_planner: pose_follower/PoseFollower
|
||||
PoseFollower:
|
||||
k_trans: 2.0
|
||||
k_rot: 1.0
|
||||
|
||||
# within this distance to the goal, finally rotate to the goal heading (also, we've reached our goal only if we're within this dist)
|
||||
tolerance_trans: 0.3
|
||||
|
||||
# we've reached our goal only if we're within this angular distance
|
||||
tolerance_rot: 0.3
|
||||
|
||||
# we've reached our goal only if we're within range for this long and stopped
|
||||
tolerance_timeout: 0.5
|
||||
|
||||
# set this to true if you're using a holonomic robot
|
||||
holonomic: false
|
||||
|
||||
# number of samples (scaling factors of our current desired twist) to check the validity of
|
||||
samples: 10
|
||||
|
||||
# go no faster than this
|
||||
max_vel_lin: 0.3
|
||||
max_vel_th: 0.5
|
||||
|
||||
# minimum velocities to keep from getting stuck
|
||||
min_vel_lin: 0.03
|
||||
min_vel_th: 0.1
|
||||
|
||||
# if we're rotating in place, go at least this fast to avoid getting stuck
|
||||
min_in_place_vel_th: 0.1
|
||||
|
||||
# when we're near the end and would be trying to go no faster than this translationally, just rotate in place instead
|
||||
in_place_trans_vel: 0.1
|
||||
|
||||
# we're "stopped" if we're going slower than these velocities
|
||||
trans_stopped_velocity: 0.03
|
||||
rot_stopped_velocity: 0.1
|
||||
|
||||
# if this is true, we don't care whether we go backwards or forwards
|
||||
allow_backwards: true
|
||||
|
||||
# if this is true, turn in place to face the new goal instead of arcing toward it
|
||||
turn_in_place_first: true
|
||||
|
||||
# if turn_in_place_first is true, turn in place if our heading is more than this far from facing the goal location
|
||||
max_heading_diff_before_moving: 0.2
|
||||
10
mir_robot/mir_navigation/config/sbpl_global_params.yaml
Executable file
10
mir_robot/mir_navigation/config/sbpl_global_params.yaml
Executable file
@@ -0,0 +1,10 @@
|
||||
base_global_planner: SBPLLatticePlanner
|
||||
SBPLLatticePlanner:
|
||||
environment_type: XYThetaLattice
|
||||
planner_type: ARAPlanner
|
||||
allocated_time: 10.0
|
||||
initial_epsilon: 1.0
|
||||
force_scratch_limit: 10000
|
||||
forward_search: true
|
||||
nominalvel_mpersecs: 0.3
|
||||
timetoturn45degsinplace_secs: 1.31 # = 0.6 rad/s
|
||||
105
mir_robot/mir_navigation/config/teb_local_planner_params.yaml
Executable file
105
mir_robot/mir_navigation/config/teb_local_planner_params.yaml
Executable file
@@ -0,0 +1,105 @@
|
||||
# NOTE: When using the teb_local_planner, make sure to set the local costmap
|
||||
# resolution high (for example 0.1 m), otherwise the optimization will take
|
||||
# forever (around 10 minutes for each iteration).
|
||||
base_local_planner: teb_local_planner/TebLocalPlannerROS
|
||||
TebLocalPlannerROS:
|
||||
# Trajectory
|
||||
teb_autosize: true # Enable the automatic resizing of the trajectory during optimization (based on the temporal resolution of the trajectory, recommended)
|
||||
dt_ref: 0.3 # Temporal resolution of the planned trajectory (usually it is set to the magnitude of the 1/control_rate)
|
||||
dt_hysteresis: 0.1 # Hysteresis that is utilized for automatic resizing depending on the current temporal resolution (dt): usually 10% of dt_ref
|
||||
global_plan_overwrite_orientation: false # Some global planners are not considering the orientation at local subgoals between start and global goal, therefore determine it automatically
|
||||
allow_init_with_backwards_motion: false # If true, the underlying trajectories might be initialized with backwards motions in case the goal is behind the start within the local costmap (this is only recommended if the robot is equipped with rear sensors)
|
||||
max_global_plan_lookahead_dist: 3.0 # Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into account for optimization [if 0 or negative: disabled; the length is also bounded by the local costmap size]
|
||||
force_reinit_new_goal_dist: 1.0 # Force the planner to reinitialize the trajectory if a previous goal is updated with a seperation of more than the specified value in meters (skip hot-starting)
|
||||
feasibility_check_no_poses: 5 # Specify up to which pose on the predicted plan the feasibility should be checked each sampling interval
|
||||
global_plan_viapoint_sep: -0.1 # Min. separation between each two consecutive via-points extracted from the global plan [if negative: disabled]
|
||||
via_points_ordered: false # If true, the planner adheres to the order of via-points in the storage container
|
||||
exact_arc_length: false # If true, the planner uses the exact arc length in velocity, acceleration and turning rate computations [-> increased cpu time], otherwise the euclidean approximation is used.
|
||||
publish_feedback: false # Publish planner feedback containing the full trajectory and a list of active obstacles (should be enabled only for evaluation or debugging purposes)
|
||||
|
||||
# Robot
|
||||
max_vel_x: 0.8 # Maximum translational velocity of the robot
|
||||
max_vel_x_backwards: 0.2 # Maximum translational velocity of the robot for driving backwards
|
||||
max_vel_y: 0.0 # Maximum strafing velocity of the robot (should be zero for non-holonomic robots!)
|
||||
max_vel_theta: 1.0 # Maximum angular velocity of the robot
|
||||
acc_lim_x: 1.5 # Maximum translational acceleration of the robot
|
||||
acc_lim_y: 0.0 # Maximum strafing acceleration of the robot
|
||||
acc_lim_theta: 2.0 # Maximum angular acceleration of the robot
|
||||
min_turning_radius: 0.0 # Minimum turning radius of a carlike robot (diff-drive robot: zero)
|
||||
wheelbase: 1.0 # The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_angle_instead_rotvel' enabled); The value might be negative for back-wheeled robots!
|
||||
cmd_angle_instead_rotvel: false # Substitute the rotational velocity in the commanded velocity message by the corresponding steering angle (check 'axles_distance')
|
||||
is_footprint_dynamic: false # If true, update the footprint before checking trajectory feasibility
|
||||
footprint_model:
|
||||
type: "polygon"
|
||||
vertices: [[0.506,-0.32],[0.506,0.32],[-0.454,0.32],[-0.454,-0.32]]
|
||||
|
||||
# Goal tolerance
|
||||
xy_goal_tolerance: 0.03 # Allowed final euclidean distance to the goal position
|
||||
yaw_goal_tolerance: 0.08 # Allowed final orientation error to the goal orientation
|
||||
free_goal_vel: false # Allow the robot's velocity to be nonzero for planning purposes (the robot can arrive at the goal with max speed)
|
||||
|
||||
# Obstacles
|
||||
min_obstacle_dist: 0.4 # Minimum desired separation from obstacles
|
||||
inflation_dist: 0.1 # Buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)
|
||||
dynamic_obstacle_inflation_dist: 0.6 # Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)
|
||||
include_dynamic_obstacles: false # Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (this also changes the homotopy class search). If false, all obstacles are considered to be static.
|
||||
include_costmap_obstacles: true # Specify whether the obstacles in the costmap should be taken into account directly (this is necessary if no seperate clustering and detection is implemented)
|
||||
legacy_obstacle_association: false # If true, the old association strategy is used (for each obstacle, find the nearest TEB pose), otherwise the new one (for each teb pose, find only 'relevant' obstacles).
|
||||
obstacle_association_force_inclusion_factor: 1.5 # The non-legacy obstacle association technique tries to connect only relevant obstacles with the discretized trajectory during optimization, all obstacles within a specifed distance are forced to be included (as a multiple of min_obstacle_dist), e.g. choose 2.0 in order to consider obstacles within a radius of 2.0*min_obstacle_dist.
|
||||
obstacle_association_cutoff_factor: 5.0 # See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist all obstacles are ignored during optimization. obstacle_association_force_inclusion_factor is processed first.
|
||||
costmap_obstacles_behind_robot_dist: 1.5 # Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify distance in meters)
|
||||
obstacle_poses_affected: 10 # The obstacle position is attached to the closest pose on the trajectory to reduce computational effort, but take a number of neighbors into account as well
|
||||
#costmap_converter_plugin: "" #
|
||||
#costmap_converter_spin_thread: true #
|
||||
#costmap_converter_rate: 5 #
|
||||
|
||||
# Optimization
|
||||
no_inner_iterations: 5 # Number of solver iterations called in each outerloop iteration
|
||||
no_outer_iterations: 4 # Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with no_inner_iterations
|
||||
optimization_activate: true # Activate the optimization
|
||||
optimization_verbose: false # Print verbose information
|
||||
penalty_epsilon: 0.1 # Add a small safty margin to penalty functions for hard-constraint approximations
|
||||
weight_max_vel_x: 2.0 # Optimization weight for satisfying the maximum allowed translational velocity
|
||||
weight_max_vel_y: 2.0 # Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic robots)
|
||||
weight_max_vel_theta: 1.0 # Optimization weight for satisfying the maximum allowed angular velocity
|
||||
weight_acc_lim_x: 1.0 # Optimization weight for satisfying the maximum allowed translational acceleration
|
||||
weight_acc_lim_y: 1.0 # Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonomic robots)
|
||||
weight_acc_lim_theta: 1.0 # Optimization weight for satisfying the maximum allowed angular acceleration
|
||||
weight_kinematics_nh: 1000.0 # Optimization weight for satisfying the non-holonomic kinematics
|
||||
weight_kinematics_forward_drive: 1.0 # Optimization weight for forcing the robot to choose only forward directions (positive transl. velocities, only diffdrive robot)
|
||||
weight_kinematics_turning_radius: 1.0 # Optimization weight for enforcing a minimum turning radius (carlike robots)
|
||||
weight_optimaltime: 1.0 # Optimization weight for contracting the trajectory w.r.t transition time
|
||||
weight_obstacle: 50.0 # Optimization weight for satisfying a minimum seperation from obstacles
|
||||
weight_inflation: 0.1 # Optimization weight for the inflation penalty (should be small)
|
||||
weight_dynamic_obstacle: 50.0 # Optimization weight for satisfying a minimum seperation from dynamic obstacles
|
||||
weight_dynamic_obstacle_inflation: 0.1 # Optimization weight for the inflation penalty of dynamic obstacles (should be small)
|
||||
weight_viapoint: 1.0 # Optimization weight for minimizing the distance to via-points
|
||||
weight_adapt_factor: 2.0 # Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer TEB iteration (weight_new: weight_old * factor); Increasing weights iteratively instead of setting a huge value a-priori leads to better numerical conditions of the underlying optimization problem.
|
||||
|
||||
# Homotopy Class Planner
|
||||
# enable_homotopy_class_planning: true #
|
||||
enable_multithreading: true # Activate multiple threading for planning multiple trajectories in parallel
|
||||
# simple_exploration: false #
|
||||
max_number_classes: 2 # Specify the maximum number of allowed alternative homotopy classes (limits computational effort)
|
||||
selection_cost_hysteresis: 1.0 # Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in order to be selected (selection if new_cost < old_cost*factor)
|
||||
selection_prefer_initial_plan: 0.95 # Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the initial plan.)
|
||||
selection_obst_cost_scale: 100.0 # Extra scaling of obstacle cost terms just for selecting the 'best' candidate (new_obst_cost: obst_cost*factor)
|
||||
selection_viapoint_cost_scale: 1.0 # Extra scaling of via-point cost terms just for selecting the 'best' candidate. (new_viapt_cost: viapt_cost*factor)
|
||||
selection_alternative_time_cost: false # If true, time cost is replaced by the total transition time.
|
||||
roadmap_graph_no_samples: 15 # Specify the number of samples generated for creating the roadmap graph, if simple_exploration is turend off
|
||||
roadmap_graph_area_width: 5.0 # Specify the width of the area in which sampled will be generated between start and goal [m] (the height equals the start-goal distance)
|
||||
roadmap_graph_area_length_scale: 1.0 # The length of the rectangular region is determined by the distance between start and goal. This parameter further scales the distance such that the geometric center remains equal!)
|
||||
h_signature_prescaler: 1.0 # Scale number of obstacle value in order to allow huge number of obstacles. Do not choose it extremly low, otherwise obstacles cannot be distinguished from each other (0.2<H<=1)
|
||||
h_signature_threshold: 0.1 # Two h-signuteres are assumed to be equal, if both the difference of real parts and complex parts are below the specified threshold
|
||||
# obstacle_keypoint_offset: 0.1 #
|
||||
obstacle_heading_threshold: 0.45 # Specify the value of the normalized scalar product between obstacle heading and goal heading in order to take them (obstacles) into account for exploration)
|
||||
viapoints_all_candidates: true # If true, all trajectories of different topologies are attached to the set of via-points, otherwise only the trajectory sharing the same one as the initial/global plan is attached (no effect in test_optim_node).
|
||||
visualize_hc_graph: false # Visualize the graph that is created for exploring new homotopy classes
|
||||
visualize_with_time_as_z_axis_scale: 0.0 # If this value is bigger than 0, the trajectory and obstacles are visualized in 3d using the time as the z-axis scaled by this value. Most useful for dynamic obstacles.
|
||||
|
||||
# Recovery
|
||||
shrink_horizon_backup: true # Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues.
|
||||
oscillation_recovery: true # Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robot frequently switches between left/right/forward/backwards).
|
||||
|
||||
odom_topic: odom
|
||||
map_frame: odom
|
||||
Reference in New Issue
Block a user