Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Multi robot sim with xacro #58

Draft
wants to merge 12 commits into
base: rolling
Choose a base branch
from
379 changes: 379 additions & 0 deletions configs/mp_400/navigation_0.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,379 @@
neo_localization2_node:
ros__parameters:
base_frame: "/base_footprint"
odom_frame: "/odom"
# exponential low pass gain for localization update (0 to 1)
# (higher gain means odometry is less used / relied on)
update_gain: 0.5
# time based confidence gain when in 2D / 1D mode
confidence_gain: 0.01
# how many particles (samples) to spread (per update)
sample_rate: 10
# localization update rate [ms]
loc_update_time: 100
# map tile update rate [1/s]
map_update_rate: 0.5
# map tile size in pixels
map_size: 1000
# how often to downscale (half) the original map
map_downscale: 0
# how many 3x3 gaussian smoothing iterations are applied to the map
num_smooth: 5
# minimum score for valid localization (otherwise 0D mode)
# higher values make it go into 0D mode earlier
min_score: 0.2
# odometry error in x and y [m/m] [1]
# how fast to increase particle spread when in 1D / 0D mode
odometry_std_xy: 0.01
# odometry error in yaw angle [rad/rad] [1]
# how fast to increase particle spread when in 0D mode
odometry_std_yaw: 0.01
# minimum particle spread in x and y [m]
min_sample_std_xy: 0.025
# minimum particle spread in yaw angle [rad]
min_sample_std_yaw: 0.025
# initial/maximum particle spread in x and y [m]
max_sample_std_xy: 0.5
# initial/maximum particle spread in yaw angle [rad]
max_sample_std_yaw: 0.5
# threshold for 1D / 2D decision making (minimum average second order gradient)
# if worst gradient direction is below this value we go into 1D mode
# if both gradient directions are below we may go into 0D mode, depending on disable_threshold
# higher values will make it go into 1D / 0D mode earlier
constrain_threshold: 0.1
# threshold for 1D / 2D decision making (with or without orientation)
# higher values will make it go into 1D mode earlier
constrain_threshold_yaw: 0.2
# minimum number of points per update
min_points: 20
# solver update gain, lower gain = more stability / slower convergence
solver_gain: 0.1
# solver update damping, higher damping = more stability / slower convergence
solver_damping: 1000.0
# number of gauss-newton iterations per sample per scan
solver_iterations: 20
# maximum wait for getting transforms [s]
transform_timeout: 0.2
# if to broadcast map frame
broadcast_tf: true
# Scan topic - feel free to use topic /scan if you have 2 laser scanners
scan_topic: "scan"
# Initial Pose topic
initialpose: initialpose
# Map Tile topic
map_tile: map_tile
# Map Pose topic
map_pose: map_pose
# particle_cloud topic
particle_cloud: particlecloud
# amcl_pose topic
amcl_pose: amcl_pose
map_topic: "/map"

amcl:
ros__parameters:
use_sim_time: True
alpha1: 0.001
alpha2: 0.001
alpha3: 0.001
alpha4: 0.001
alpha5: 0.001
base_frame_id: "base_link"
beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9
beam_skip_threshold: 0.3
do_beamskip: false
global_frame_id: "map"
lambda_short: 0.1
set_initial_pose: true
laser_likelihood_max_dist: 2.0
laser_max_range: -1.44
laser_min_range: 1.44
laser_model_type: "likelihood_field"
max_beams: 200
max_particles: 2000
min_particles: 500
odom_frame_id: "odom"
pf_err: 0.05
pf_z: 0.99
recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0
resample_interval: 2
robot_model_type: "differential"
save_pose_rate: 0.5
sigma_hit: 0.2
tf_broadcast: true
transform_tolerance: 0.1
scan_topic: /scan
update_min_a: 0.1
update_min_d: 0.1
# z_hit: 0.5
# z_max: 0.05
# z_rand: 0.5
# z_short: 0.05

bt_navigator:
ros__parameters:
global_frame: map
robot_base_frame: robot0/base_link
bt_loop_duration: 10
default_server_timeout: 20
navigators: ['navigate_to_pose', 'navigate_through_poses']
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_compute_path_through_poses_action_bt_node
- nav2_smooth_path_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_assisted_teleop_action_bt_node
- nav2_back_up_action_bt_node
- nav2_drive_on_heading_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_globally_updated_goal_condition_bt_node
- nav2_is_path_valid_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_truncate_path_local_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_path_expiring_timer_condition
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
- nav2_goal_updated_controller_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_navigate_through_poses_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_planner_selector_bt_node
- nav2_controller_selector_bt_node
- nav2_goal_checker_selector_bt_node
- nav2_controller_cancel_bt_node
- nav2_path_longer_on_approach_bt_node
- nav2_wait_cancel_bt_node
- nav2_spin_cancel_bt_node
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
error_code_names:
- compute_path_error_code
- follow_path_error_code

controller_server:
ros__parameters:
# controller server parameters (see Controller Server for more info)
controller_frequency: 100.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
controller_plugins: ["FollowPath"]
goal_checker_plugins: ["general_goal_checker"]
progress_checker_plugin: "progress_checker"
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 100.0
general_goal_checker:
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.05
yaw_goal_tolerance: 0.05
stateful: True
# neo_local_planner controller parameters
FollowPath:
plugin: "neo_local_planner::NeoLocalPlanner"
# The x acceleration limit of the robot in meters/sec^2
# The x acceleration limit of the robot in meters/sec^2
acc_lim_x : 0.25
# The rotational acceleration limit of the robot in radians/sec^2
acc_lim_theta : 0.8
# The maximum x velocity for the robot in m/s.
max_vel_x : 0.8
# The minimum x velocity for the robot in m/s, negative for backwards motion.
min_vel_x : -0.1
# The absolute value of the maximum rotational velocity for the robot in rad/s
max_rot_vel : 0.8
# The absolute value of the minimum rotational velocity for the robot in rad/s
min_rot_vel : 0.1
# The absolute value of the maximum translational velocity for the robot in m/s
max_trans_vel : 0.8
# The absolute value of the minimum translational velocity for the robot in m/s
min_trans_vel : 0.1
# The tolerance in radians for the controller in yaw/rotation when achieving its goal
yaw_goal_tolerance : 0.05
# The tolerance in meters for the controller in the x & y distance when achieving a goal
xy_goal_tolerance : 0.1
# How long to fine tune for goal position after reaching tolerance limits [s]
goal_tune_time : 3.0
# How far to predict control pose into the future based on latest odometry [s]
lookahead_time : 0.3
# How far to look ahead when computing path orientation [m]
lookahead_dist : 0.5
# Threshold yaw error below which we consider to start moving [rad]
start_yaw_error : 0.2
# Gain when adjusting final x position for goal [1/s]
pos_x_gain : 1.0
# Gain for lane keeping based on y error (differential only) [rad/s^2]
pos_y_yaw_gain : 1.0
# Gain for lane keeping based on yaw error (differential only) [1/s]
yaw_gain : 2.0
# Gain for adjusting yaw when not translating, or in case of holonomic drive [1/s]
static_yaw_gain : 3.0
# Gain for y cost avoidance (differential only)
cost_y_yaw_gain : 0.3
# How far ahead to compute y cost gradient (constant offset) [m]
cost_y_lookahead_dist : 0.3
# How far ahead to compute y cost gradient (dynamic offset) [s]
cost_y_lookahead_time : 1.5
# Gain for yaw cost avoidance
cost_yaw_gain : 2.0
# Gain for final control low pass filter
low_pass_gain : 0.2
# Max cost to allow, above we slow down to min_trans_vel or even stop
max_cost : 0.95
# Max velocity based on curvature [rad/s]
max_curve_vel : 0.3
# Max distance to goal when looking for it [m]
max_goal_dist : 0.3
# Max distance allowable for backing up (zero = unlimited) [m]
max_backup_dist : 0.1
# Minimal distance for stopping [m]
min_stop_dist : 0.3
# If robot has differential drive, holonomic otherwise
differential_drive : true
# odom frame_id
local_frame: "/odom"
# base frame_id
base_frame: "/base_link"
# odom topic
odom_topic: "odom"

local_costmap:
local_costmap:
ros__parameters:
update_frequency: 10.0
use_sim_time: True
publish_frequency: 1.0
global_frame: robot0/odom
robot_base_frame: robot0/base_link
footprint_padding: 0.
footprint: "[ [0.30,0.30],[-0.30,0.30],[-0.30,-0.3],[0.30,-0.3] ]"
rolling_window: true
width: 5
height: 5
resolution: 0.03
# robot_radius: 0.22
plugins: ["obstacle_layer", "inflation_layer"]
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 5.0
inflation_radius: 0.8
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
scan:
topic: /robot0/scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
always_send_full_costmap: True

global_costmap:
global_costmap:
ros__parameters:
update_frequency: 0.4
publish_frequency: 1.0
global_frame: map
robot_base_frame: robot0/base_link
map_topic: /map
footprint_padding: 0.0
footprint: "[ [0.30,0.30],[-0.30,0.30],[-0.30,-0.3],[0.30,-0.3] ]"
# robot_radius: 0.22
resolution: 0.05
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
scan:
topic: /robot0/scan
obstacle_max_range: 5.0
obstacle_min_range: 0.0
raytrace_max_range: 8.0
raytrace_min_range: 0.0
clearing: True
marking: True
data_type: "LaserScan"
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
enabled: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 4.5
inflation_radius: 0.8
always_send_full_costmap: True

map_server:
ros__parameters:
yaml_filename: "test.yaml"

map_saver:
ros__parameters:
save_map_timeout: 5000
free_thresh_default: 0.25
occupied_thresh_default: 0.65
map_subscribe_transient_local: False

planner_server:
ros__parameters:
expected_planner_frequency: 5.0
use_sim_time: False
planner_plugins: ["GridBased"]
GridBased:
plugin: "nav2_navfn_planner/NavfnPlanner"
tolerance: 0.5
use_astar: false
allow_unknown: true

behavior_server:
ros__parameters:
costmap_topic: local_costmap/costmap_raw
footprint_topic: local_costmap/published_footprint
cycle_frequency: 10.0
behavior_plugins: ["spin", "backup", "wait"]
spin:
plugin: "nav2_behaviors/Spin"
backup:
plugin: "nav2_behaviors/BackUp"
wait:
plugin: "nav2_behaviors/Wait"
global_frame: robot0/odom
robot_base_frame: robot0/base_link
transform_timeout: 0.1
simulate_ahead_time: 2.0
max_rotational_vel: 0.5
min_rotational_vel: 0.3
rotational_acc_lim: 0.8

waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
waypoint_pause_duration: 200
Loading
Loading