mirror of
https://github.com/bjoernellens1/cps_loki_bringup.git
synced 2024-11-22 15:43:48 +00:00
update
This commit is contained in:
parent
9b688e2c4d
commit
d30da7874a
@ -13,8 +13,8 @@ slam_toolbox:
|
|||||||
odom_frame: odom
|
odom_frame: odom
|
||||||
map_frame: map
|
map_frame: map
|
||||||
base_frame: base_footprint
|
base_frame: base_footprint
|
||||||
#scan_topic: /scan
|
scan_topic: /scan
|
||||||
scan_topic: /scan_filtered
|
#scan_topic: /scan_filtered
|
||||||
use_map_saver: true
|
use_map_saver: true
|
||||||
mode: mapping #localization
|
mode: mapping #localization
|
||||||
|
|
||||||
@ -35,7 +35,7 @@ slam_toolbox:
|
|||||||
transform_timeout: 0.2
|
transform_timeout: 0.2
|
||||||
tf_buffer_duration: 30.
|
tf_buffer_duration: 30.
|
||||||
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
|
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
|
||||||
enable_interactive_mode: true
|
enable_interactive_mode: false
|
||||||
|
|
||||||
# General Parameters
|
# General Parameters
|
||||||
use_scan_matching: true
|
use_scan_matching: true
|
||||||
@ -113,14 +113,14 @@ amcl:
|
|||||||
z_max: 0.05
|
z_max: 0.05
|
||||||
z_rand: 0.5
|
z_rand: 0.5
|
||||||
z_short: 0.05
|
z_short: 0.05
|
||||||
scan_topic: scan_filtered
|
scan_topic: scan
|
||||||
|
|
||||||
bt_navigator:
|
bt_navigator:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
use_sim_time: True
|
use_sim_time: True
|
||||||
global_frame: map
|
global_frame: map
|
||||||
robot_base_frame: base_link
|
robot_base_frame: base_link
|
||||||
odom_topic: /odometry/filtered
|
odom_topic: odom
|
||||||
bt_loop_duration: 10
|
bt_loop_duration: 10
|
||||||
default_server_timeout: 20
|
default_server_timeout: 20
|
||||||
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
|
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
|
||||||
@ -259,9 +259,9 @@ local_costmap:
|
|||||||
z_voxels: 16
|
z_voxels: 16
|
||||||
max_obstacle_height: 2.0
|
max_obstacle_height: 2.0
|
||||||
mark_threshold: 0
|
mark_threshold: 0
|
||||||
observation_sources: rplidar oakd
|
observation_sources: lslidar
|
||||||
rplidar:
|
lslidar:
|
||||||
topic: /scan_filtered
|
topic: scan
|
||||||
max_obstacle_height: 2.0
|
max_obstacle_height: 2.0
|
||||||
clearing: True
|
clearing: True
|
||||||
marking: True
|
marking: True
|
||||||
@ -270,17 +270,6 @@ local_costmap:
|
|||||||
raytrace_min_range: 0.0
|
raytrace_min_range: 0.0
|
||||||
obstacle_max_range: 2.5
|
obstacle_max_range: 2.5
|
||||||
obstacle_min_range: 0.0
|
obstacle_min_range: 0.0
|
||||||
oak-d: # no frame set, uses frame from message
|
|
||||||
topic: /stereo/points
|
|
||||||
max_obstacle_height: 1.5
|
|
||||||
min_obstacle_height: 0.02
|
|
||||||
obstacle_max_range: 3.0
|
|
||||||
obstacle_min_range: 0.0
|
|
||||||
raytrace_max_range: 3.2
|
|
||||||
raytrace_min_range: 0.0
|
|
||||||
clearing: True
|
|
||||||
marking: True
|
|
||||||
data_type: "PointCloud2"
|
|
||||||
static_layer:
|
static_layer:
|
||||||
plugin: "nav2_costmap_2d::StaticLayer"
|
plugin: "nav2_costmap_2d::StaticLayer"
|
||||||
map_subscribe_transient_local: True
|
map_subscribe_transient_local: True
|
||||||
@ -302,9 +291,9 @@ global_costmap:
|
|||||||
obstacle_layer:
|
obstacle_layer:
|
||||||
plugin: "nav2_costmap_2d::ObstacleLayer"
|
plugin: "nav2_costmap_2d::ObstacleLayer"
|
||||||
enabled: True
|
enabled: True
|
||||||
observation_sources: scan
|
observation_sources: lslidar
|
||||||
scan:
|
lslidar:
|
||||||
topic: /scan_filtered
|
topic: scan
|
||||||
max_obstacle_height: 2.0
|
max_obstacle_height: 2.0
|
||||||
clearing: True
|
clearing: True
|
||||||
marking: True
|
marking: True
|
||||||
@ -414,12 +403,12 @@ velocity_smoother:
|
|||||||
use_sim_time: True
|
use_sim_time: True
|
||||||
smoothing_frequency: 20.0
|
smoothing_frequency: 20.0
|
||||||
scale_velocities: False
|
scale_velocities: False
|
||||||
feedback: "CLOSED_LOOP" # was OPEN_LOOP
|
feedback: "OPEN_LOOP" # was OPEN_LOOP
|
||||||
max_velocity: [0.26, 0.0, 1.0]
|
max_velocity: [0.26, 0.0, 1.0]
|
||||||
min_velocity: [-0.26, 0.0, -1.0]
|
min_velocity: [-0.26, 0.0, -1.0]
|
||||||
max_accel: [2.5, 0.0, 3.2]
|
max_accel: [2.5, 0.0, 3.2]
|
||||||
max_decel: [-2.5, 0.0, -3.2]
|
max_decel: [-2.5, 0.0, -3.2]
|
||||||
odom_topic: "/odometry/filtered"
|
odom_topic: "odom"
|
||||||
odom_duration: 0.1 # was 0.1
|
odom_duration: 0.1 # was 0.1
|
||||||
deadband_velocity: [0.0, 0.0, 0.0]
|
deadband_velocity: [0.0, 0.0, 0.0]
|
||||||
velocity_timeout: 1.0
|
velocity_timeout: 1.0
|
Loading…
Reference in New Issue
Block a user