Skip to content

Commit

Permalink
adding slash to seperate the robot namespace and the frame id
Browse files Browse the repository at this point in the history
  • Loading branch information
padhupradheep committed Jul 13, 2023
1 parent 6fe0595 commit 4286b56
Show file tree
Hide file tree
Showing 5 changed files with 279 additions and 365 deletions.
78 changes: 29 additions & 49 deletions configs/mp_400/navigation_0.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
neo_localization2_node:
ros__parameters:
base_frame: "base_footprint"
odom_frame: "odom"
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
Expand All @@ -26,7 +26,7 @@ neo_localization2_node:
# 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
# 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
Expand All @@ -37,9 +37,9 @@ neo_localization2_node:
# 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
# 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
Expand All @@ -56,9 +56,8 @@ neo_localization2_node:
transform_timeout: 0.2
# if to broadcast map frame
broadcast_tf: true
broadcast_info: false
# Scan topic
scan_topic: scan
# 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
Expand Down Expand Up @@ -113,17 +112,8 @@ amcl:
# z_rand: 0.5
# z_short: 0.05

amcl_map_client:
ros__parameters:
use_sim_time: True

amcl_rclcpp_node:
ros__parameters:
use_sim_time: True

bt_navigator:
ros__parameters:
use_sim_time: True
global_frame: map
robot_base_frame: robot0base_link
bt_loop_duration: 10
Expand Down Expand Up @@ -183,15 +173,13 @@ bt_navigator:
controller_server:
ros__parameters:
# controller server parameters (see Controller Server for more info)
use_sim_time: False
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"
odom_topic: "/robot0/odom"
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
Expand Down Expand Up @@ -222,7 +210,7 @@ controller_server:
# 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.01
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]
Expand Down Expand Up @@ -263,23 +251,27 @@ controller_server:
min_stop_dist : 0.3
# If robot has differential drive, holonomic otherwise
differential_drive : true
odom_topic: /robot0/odom
# 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: robot0odom
robot_base_frame: robot0base_link
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] ]"
use_sim_time: True
rolling_window: true
map_topic: "/map"
width: 5
height: 5
resolution: 0.02
resolution: 0.03
# robot_radius: 0.22
plugins: ["obstacle_layer", "inflation_layer"]
inflation_layer:
Expand All @@ -292,11 +284,7 @@ local_costmap:
observation_sources: scan
scan:
topic: /robot0/scan
obstacle_max_range: 5.0
max_obstacle_height: 2.0
obstacle_min_range: 0.0
raytrace_max_range: 8.0
raytrace_min_range: 0.0
clearing: True
marking: True
data_type: "LaserScan"
Expand All @@ -305,14 +293,14 @@ local_costmap:
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
update_frequency: 0.4
publish_frequency: 1.0
global_frame: map
robot_base_frame: robot0base_link
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] ]"
use_sim_time: True
map_topic: "/map"
# robot_radius: 0.22
resolution: 0.05
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
Expand All @@ -322,7 +310,6 @@ global_costmap:
scan:
topic: /robot0/scan
obstacle_max_range: 5.0
max_obstacle_height: 2.0
obstacle_min_range: 0.0
raytrace_max_range: 8.0
raytrace_min_range: 0.0
Expand All @@ -341,32 +328,26 @@ global_costmap:

map_server:
ros__parameters:
use_sim_time: True
yaml_filename: "neo_track1.yaml"
yaml_filename: "test.yaml"

map_saver:
ros__parameters:
use_sim_time: True
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: 20.0
use_sim_time: True
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

planner_server_rclcpp_node:
ros__parameters:
use_sim_time: True

behavior_server:
ros__parameters:
costmap_topic: local_costmap/costmap_raw
Expand All @@ -379,10 +360,9 @@ behavior_server:
plugin: "nav2_behaviors/BackUp"
wait:
plugin: "nav2_behaviors/Wait"
global_frame: robot0odom
robot_base_frame: robot0base_link
global_frame: robot0/odom
robot_base_frame: robot0/base_link
transform_timeout: 0.1
use_sim_time: true
simulate_ahead_time: 2.0
max_rotational_vel: 0.5
min_rotational_vel: 0.3
Expand All @@ -396,4 +376,4 @@ waypoint_follower:
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
waypoint_pause_duration: 200
waypoint_pause_duration: 200
Loading

0 comments on commit 4286b56

Please sign in to comment.