update
This commit is contained in:
54
config/mprim/costmap_common_params.yaml
Executable file
54
config/mprim/costmap_common_params.yaml
Executable file
@@ -0,0 +1,54 @@
|
||||
robot_base_frame: base_footprint
|
||||
transform_tolerance: 1.0
|
||||
obstacle_range: 3.0
|
||||
#mark_threshold: 1
|
||||
publish_voxel_map: true
|
||||
footprint_padding: 0.0
|
||||
|
||||
navigation_map:
|
||||
map_topic: /map
|
||||
map_pkg: managerments
|
||||
map_file: maze
|
||||
|
||||
virtual_walls_map:
|
||||
map_topic: /virtual_walls/map
|
||||
namespace: /virtual_walls
|
||||
map_pkg: managerments
|
||||
map_file: maze
|
||||
use_maximum: true
|
||||
lethal_cost_threshold: 100
|
||||
|
||||
obstacles:
|
||||
observation_sources: f_scan_marking f_scan_clearing b_scan_marking b_scan_clearing
|
||||
f_scan_marking:
|
||||
topic: /f_scan
|
||||
data_type: LaserScan
|
||||
clearing: false
|
||||
marking: true
|
||||
inf_is_valid: false
|
||||
min_obstacle_height: 0.0
|
||||
max_obstacle_height: 0.25
|
||||
f_scan_clearing:
|
||||
topic: /f_scan
|
||||
data_type: LaserScan
|
||||
clearing: true
|
||||
marking: false
|
||||
inf_is_valid: false
|
||||
min_obstacle_height: 0.0
|
||||
max_obstacle_height: 0.25
|
||||
b_scan_marking:
|
||||
topic: /b_scan
|
||||
data_type: LaserScan
|
||||
clearing: false
|
||||
marking: true
|
||||
inf_is_valid: false
|
||||
min_obstacle_height: 0.0
|
||||
max_obstacle_height: 0.25
|
||||
b_scan_clearing:
|
||||
topic: /b_scan
|
||||
data_type: LaserScan
|
||||
clearing: true
|
||||
marking: false
|
||||
inf_is_valid: false
|
||||
min_obstacle_height: 0.0
|
||||
max_obstacle_height: 0.25
|
||||
13
config/mprim/costmap_global_params.yaml
Executable file
13
config/mprim/costmap_global_params.yaml
Executable file
@@ -0,0 +1,13 @@
|
||||
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: 10.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.6 # Max. distance from an obstacle at which costs are incurred for planning paths. Must be > robot's circumscribed radius.
|
||||
|
||||
10
config/mprim/costmap_global_params_plugins_no_virtual_walls.yaml
Executable file
10
config/mprim/costmap_global_params_plugins_no_virtual_walls.yaml
Executable file
@@ -0,0 +1,10 @@
|
||||
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: inflation, type: "costmap_2d::InflationLayer" }
|
||||
obstacles:
|
||||
enabled: false
|
||||
footprint_clearing_enabled: false
|
||||
16
config/mprim/costmap_local_params.yaml
Executable file
16
config/mprim/costmap_local_params.yaml
Executable file
@@ -0,0 +1,16 @@
|
||||
local_costmap:
|
||||
global_frame: odom
|
||||
update_frequency: 6.0
|
||||
publish_frequency: 6.0
|
||||
rolling_window: true
|
||||
raytrace_range: 2.0
|
||||
resolution: 0.05
|
||||
z_resolution: 0.15
|
||||
z_voxels: 8
|
||||
inflation:
|
||||
cost_scaling_factor: 10.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.3 # Max. distance from an obstacle at which costs are incurred for planning paths. Must be > robot's circumscribed radius.
|
||||
width: 8.0
|
||||
height: 8.0
|
||||
origin_x: 0.0
|
||||
origin_y: 0.0
|
||||
24
config/mprim/move_base_common_params.yaml
Executable file
24
config/mprim/move_base_common_params.yaml
Executable file
@@ -0,0 +1,24 @@
|
||||
|
||||
### replanning
|
||||
controller_frequency: 20.0 # run controller at 15.0 Hz
|
||||
controller_patience: 0.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: -1 # abort controller and trigger recovery behaviors after 30.0 s
|
||||
oscillation_distance: 0.4
|
||||
### recovery behaviors
|
||||
recovery_behavior_enabled: true
|
||||
recovery_behaviors: [
|
||||
{name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery},
|
||||
{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery},
|
||||
]
|
||||
|
||||
conservative_reset:
|
||||
reset_distance: 3.0 # clear obstacles farther away than 3.0 m
|
||||
invert_area_to_clear: true
|
||||
|
||||
aggressive_reset:
|
||||
reset_distance: 3.0
|
||||
|
||||
|
||||
186
config/mprim/pnkx_local_planner_params.yaml
Normal file
186
config/mprim/pnkx_local_planner_params.yaml
Normal file
@@ -0,0 +1,186 @@
|
||||
|
||||
position_planner_name: PNKXLocalPlanner
|
||||
docking_planner_name: PNKXDockingLocalPlanner
|
||||
go_straight_planner_name: PNKXGoStraightLocalPlanner
|
||||
rotate_planner_name: PNKXRotateLocalPlanner
|
||||
|
||||
base_local_planner: nav_core_adapter::LocalPlannerAdapter
|
||||
yaw_goal_tolerance: 0.017
|
||||
xy_goal_tolerance: 0.03
|
||||
min_approach_linear_velocity: 0.06 # The minimum velocity (m/s) threshold to apply when approaching the goal to ensure progress. Must be > 0.01. (default: 0.05)
|
||||
stateful: true
|
||||
publish_topic: true
|
||||
|
||||
LocalPlannerAdapter:
|
||||
PNKXLocalPlanner:
|
||||
# Algorithm
|
||||
trajectory_generator_name: mkt_plugins::LimitedAccelGenerator
|
||||
algorithm_nav_name: mkt_algorithm::diff::PredictiveTrajectory
|
||||
algorithm_rotate_name: mkt_algorithm::diff::RotateToGoal
|
||||
# Goal checking
|
||||
goal_checker_name: mkt_plugins::GoalChecker
|
||||
|
||||
PNKXDockingLocalPlanner:
|
||||
# Algorithm
|
||||
trajectory_generator_name: mkt_plugins::LimitedAccelGenerator
|
||||
algorithm_nav_name: mkt_algorithm::diff::PredictiveTrajectory
|
||||
algorithm_rotate_name: mkt_algorithm::diff::RotateToGoal
|
||||
# Goal checking
|
||||
goal_checker_name: mkt_plugins::GoalChecker
|
||||
|
||||
PNKXGoStraightLocalPlanner:
|
||||
# Algorithm
|
||||
trajectory_generator_name: mkt_plugins::LimitedAccelGenerator
|
||||
algorithm_nav_name: mkt_algorithm::diff::GoStraight
|
||||
# Goal checking
|
||||
goal_checker_name: mkt_plugins::GoalChecker
|
||||
|
||||
PNKXRotateLocalPlanner:
|
||||
# Algorithm
|
||||
algorithm_rotate_name: mkt_algorithm::diff::RotateToGoal
|
||||
trajectory_generator_name: mkt_plugins::LimitedAccelGenerator
|
||||
# Goal checking
|
||||
goal_checker_name: mkt_plugins::SimpleGoalChecker
|
||||
stateful: true
|
||||
|
||||
LimitedAccelGenerator:
|
||||
max_vel_x: 1.2
|
||||
min_vel_x: -1.2
|
||||
|
||||
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: 0.9 # max_rot_vel: 1.0 # choose slightly less than the base's capability
|
||||
min_vel_theta: 0.04 # min_rot_vel: 0.1 default: 0.4 # this is the min angular velocity when there is negligible translational velocity
|
||||
|
||||
acc_lim_x: 1.0
|
||||
acc_lim_y: 0.0 # diff drive robot
|
||||
acc_lim_theta: 0.9
|
||||
decel_lim_x: -1.0
|
||||
decel_lim_y: -0.0
|
||||
decel_lim_theta: -1.5
|
||||
|
||||
# Whether to split the path into segments or not
|
||||
split_path: true
|
||||
sim_time: 1.5
|
||||
vx_samples: 15
|
||||
vy_samples: 1
|
||||
vtheta_samples: 10
|
||||
discretize_by_time: true
|
||||
angular_granularity: 0.05
|
||||
linear_granularity: 0.1
|
||||
# sim_period
|
||||
include_last_point: true
|
||||
|
||||
PredictiveTrajectory:
|
||||
avoid_obstacles: false
|
||||
xy_local_goal_tolerance: 0.01
|
||||
angle_threshold: 0.6
|
||||
index_samples: 60
|
||||
follow_step_path: true
|
||||
|
||||
# Lookahead
|
||||
use_velocity_scaled_lookahead_dist: true # Whether to use the velocity scaled lookahead distances or constant lookahead_distance. (default: false)
|
||||
# only when false:
|
||||
lookahead_dist: 0.5 # The lookahead distance (m) to use to find the lookahead point. (default: 0.6)
|
||||
# only when true:
|
||||
min_lookahead_dist: 1.0 # The minimum lookahead distance (m) threshold. (default: 0.3)
|
||||
max_lookahead_dist: 2.0 # The maximum lookahead distance (m) threshold. (default: 0.9)
|
||||
lookahead_time: 1.6 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5)
|
||||
min_journey_squared: 0.3 # Minimum squared journey to consider for goal (default: 0.2)
|
||||
max_journey_squared: 0.8 # Maximum squared journey to consider for goal (default: 0.2)
|
||||
|
||||
# Rotate to heading param - onle one of use_rotate_to_heading and allow_reversing can be set to true
|
||||
use_rotate_to_heading: true # Whether to enable rotating to rough heading and goal orientation when using holonomic planners. Recommended on for all robot types that can rotate in place. (default: true)
|
||||
# only when true:
|
||||
rotate_to_heading_min_angle: 0.03 # The difference in the path orientation and the starting robot orientation (radians) to trigger a rotate in place. (default: 0.785)
|
||||
angular_decel_zone: 0.1
|
||||
|
||||
# stoped
|
||||
rot_stopped_velocity: 0.1
|
||||
trans_stopped_velocity: 0.1
|
||||
|
||||
# Regulated linear velocity scaling
|
||||
use_regulated_linear_velocity_scaling: false # Whether to use the regulated features for path curvature (e.g. slow on high curvature paths). (default: true)
|
||||
# only when true:
|
||||
regulated_linear_scaling_min_radius: 0.6 # The turning radius (m) for which the regulation features are triggered. Remember, sharper turns have smaller radii. (default: 0.9)
|
||||
regulated_linear_scaling_min_speed: 0.15 # The minimum speed (m/s) for which any of the regulated heuristics can send, to ensure process is still achievable even in high cost spaces with high curvature. Must be > 0.1. (default: 0.25)
|
||||
|
||||
# Inflation cost scaling (Limit velocity by proximity to obstacles)
|
||||
use_cost_regulated_linear_velocity_scaling: false # Whether to use the regulated features for proximity to obstacles (e.g. slow in close proximity to obstacles). (default: true)
|
||||
inflation_cost_scaling_factor: 2.0 # (default: 3.0) # must be > 0
|
||||
cost_scaling_dist: 0.2 # (default: 0.6)
|
||||
cost_scaling_gain: 2.0 # (default: 1.0)
|
||||
|
||||
GoStraight:
|
||||
avoid_obstacles: false
|
||||
xy_local_goal_tolerance: 0.01
|
||||
angle_threshold: 0.6
|
||||
index_samples: 60
|
||||
follow_step_path: true
|
||||
|
||||
# Lookahead
|
||||
use_velocity_scaled_lookahead_dist: true # Whether to use the velocity scaled lookahead distances or constant lookahead_distance. (default: false)
|
||||
# only when false:
|
||||
lookahead_dist: 0.5 # The lookahead distance (m) to use to find the lookahead point. (default: 0.6)
|
||||
# only when true:
|
||||
min_lookahead_dist: 0.8 # The minimum lookahead distance (m) threshold. (default: 0.3)
|
||||
max_lookahead_dist: 1.5 # The maximum lookahead distance (m) threshold. (default: 0.9)
|
||||
lookahead_time: 2.5 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5)
|
||||
min_journey_squared: 0.3 # Minimum squared journey to consider for goal (default: 0.2)
|
||||
max_journey_squared: 0.6 # Minimum squared journey to consider for goal (default: 0.2)
|
||||
|
||||
# Rotate to heading param - onle one of use_rotate_to_heading and allow_reversing can be set to true
|
||||
use_rotate_to_heading: true # Whether to enable rotating to rough heading and goal orientation when using holonomic planners. Recommended on for all robot types that can rotate in place. (default: true)
|
||||
# only when true:
|
||||
rotate_to_heading_min_angle: 0.35 # The difference in the path orientation and the starting robot orientation (radians) to trigger a rotate in place. (default: 0.785)
|
||||
|
||||
# stoped
|
||||
rot_stopped_velocity: 0.03
|
||||
trans_stopped_velocity: 0.06
|
||||
|
||||
use_regulated_linear_velocity_scaling: false
|
||||
use_cost_regulated_linear_velocity_scaling: false
|
||||
|
||||
RotateToGoal:
|
||||
avoid_obstacles: false
|
||||
xy_local_goal_tolerance: 0.01
|
||||
angle_threshold: 0.6
|
||||
index_samples: 60
|
||||
follow_step_path: true
|
||||
|
||||
# Lookahead
|
||||
use_velocity_scaled_lookahead_dist: true # Whether to use the velocity scaled lookahead distances or constant lookahead_distance. (default: false)
|
||||
# only when false:
|
||||
lookahead_dist: 0.325 # The lookahead distance (m) to use to find the lookahead point. (default: 0.6)
|
||||
# only when true:
|
||||
min_lookahead_dist: 0.8 # The minimum lookahead distance (m) threshold. (default: 0.3)
|
||||
max_lookahead_dist: 1.5 # The maximum lookahead distance (m) threshold. (default: 0.9)
|
||||
lookahead_time: 1.8 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5)
|
||||
min_journey_squared: 0.3 # Minimum squared journey to consider for goal (default: 0.2)
|
||||
max_journey_squared: 0.6 # Maximum squared journey to consider for goal (default: 0.2)
|
||||
|
||||
# Rotate to heading param - onle one of use_rotate_to_heading and allow_reversing can be set to true
|
||||
use_rotate_to_heading: true # Whether to enable rotating to rough heading and goal orientation when using holonomic planners. Recommended on for all robot types that can rotate in place. (default: true)
|
||||
# only when true:
|
||||
rotate_to_heading_min_angle: 0.03 # The difference in the path orientation and the starting robot orientation (radians) to trigger a rotate in place. (default: 0.785)
|
||||
angular_decel_zone: 0.1
|
||||
|
||||
# stoped
|
||||
rot_stopped_velocity: 0.03
|
||||
trans_stopped_velocity: 0.06
|
||||
|
||||
# Regulated linear velocity scaling
|
||||
use_regulated_linear_velocity_scaling: false # Whether to use the regulated features for path curvature (e.g. slow on high curvature paths). (default: true)
|
||||
# only when true:
|
||||
regulated_linear_scaling_min_radius: 0.6 # The turning radius (m) for which the regulation features are triggered. Remember, sharper turns have smaller radii. (default: 0.9)
|
||||
regulated_linear_scaling_min_speed: 0.05 # The minimum speed (m/s) for which any of the regulated heuristics can send, to ensure process is still achievable even in high cost spaces with high curvature. Must be > 0.1. (default: 0.25)
|
||||
|
||||
# Inflation cost scaling (Limit velocity by proximity to obstacles)
|
||||
use_cost_regulated_linear_velocity_scaling: false # Whether to use the regulated features for proximity to obstacles (e.g. slow in close proximity to obstacles). (default: true)
|
||||
inflation_cost_scaling_factor: 2.0 # (default: 3.0) # must be > 0
|
||||
cost_scaling_dist: 0.2 # (default: 0.6)
|
||||
cost_scaling_gain: 2.0 # (default: 1.0)
|
||||
3
config/mprim/two_points_global_params.yaml
Normal file
3
config/mprim/two_points_global_params.yaml
Normal file
@@ -0,0 +1,3 @@
|
||||
base_global_planner: TwoPointsPlanner
|
||||
TwoPointsPlanner:
|
||||
lethal_obstacle: 20
|
||||
Reference in New Issue
Block a user