mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2024-11-23 15:45:08 +00:00
update: changing slam_toolbox params
This commit is contained in:
parent
045c92d222
commit
622ac3d3bb
@ -12,17 +12,16 @@ slam_toolbox:
|
|||||||
# ROS Parameters
|
# ROS Parameters
|
||||||
odom_frame: odom
|
odom_frame: odom
|
||||||
map_frame: map
|
map_frame: map
|
||||||
map_topic: map #tryout?
|
|
||||||
base_frame: base_footprint
|
base_frame: base_footprint
|
||||||
scan_topic: scan
|
scan_topic: /scan
|
||||||
mode: localization
|
mode: localization
|
||||||
|
|
||||||
# if you'd like to immediately start continuing a map at a given pose
|
# if you'd like to immediately start continuing a map at a given pose
|
||||||
# or at the dock, but they are mutually exclusive, if pose is given
|
# or at the dock, but they are mutually exclusive, if pose is given
|
||||||
# will use pose
|
# will use pose
|
||||||
map_file_name: /home/bjorn/Documents/ros-projects/cps_bot_mini_ws/my_map_serial
|
#map_file_name: /home/bjorn/Documents/ros-projects/cps_bot_mini_ws/my_map_serial
|
||||||
# map_start_pose: [0.0, 0.0, 0.0]
|
# map_start_pose: [0.0, 0.0, 0.0]
|
||||||
map_start_at_dock: true
|
#map_start_at_dock: true
|
||||||
|
|
||||||
debug_logging: false
|
debug_logging: false
|
||||||
throttle_scans: 1
|
throttle_scans: 1
|
||||||
|
@ -57,7 +57,7 @@ def generate_launch_description():
|
|||||||
{'use_sim_time': use_sim_time}
|
{'use_sim_time': use_sim_time}
|
||||||
],
|
],
|
||||||
#namespace = namespace,
|
#namespace = namespace,
|
||||||
remappings=[('/scan', 'scan'), ('/map', 'map')],
|
#remappings=[('/scan', 'scan'), ('/map', 'map')],
|
||||||
)
|
)
|
||||||
|
|
||||||
return LaunchDescription([
|
return LaunchDescription([
|
||||||
|
Loading…
Reference in New Issue
Block a user