Skip to content

Commit

Permalink
mapping updates (#96)
Browse files Browse the repository at this point in the history
  • Loading branch information
padhupradheep committed Jul 16, 2024
1 parent 4d2a42f commit 3d6134a
Show file tree
Hide file tree
Showing 4 changed files with 78 additions and 48 deletions.
31 changes: 12 additions & 19 deletions configs/mp_400/mapping.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -16,20 +16,13 @@ slam_toolbox:
scan_topic: /scan
mode: mapping #localization

# 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
# will use pose
#map_file_name: test_steve
#map_start_pose: [0.0, 0.0, 0.0]
#map_start_at_dock: true

debug_logging: false
throttle_scans: 1
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
resolution: 0.03
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
minimum_time_interval: 0.25
transform_timeout: 0.2
tf_buffer_duration: 30.
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
Expand All @@ -38,31 +31,31 @@ slam_toolbox:
# General Parameters
use_scan_matching: true
use_scan_barycenter: true
minimum_travel_distance: 0.5
minimum_travel_heading: 0.5
minimum_travel_distance: 0.3
minimum_travel_heading: 0.3
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 10.0
scan_buffer_maximum_scan_distance: 5.0
link_match_minimum_response_fine: 0.1
link_scan_maximum_distance: 1.5
loop_search_maximum_distance: 3.0
loop_search_maximum_distance: 1.5
do_loop_closing: true
loop_match_minimum_chain_size: 10
loop_match_maximum_variance_coarse: 3.0
loop_match_minimum_response_coarse: 0.35
loop_match_minimum_response_fine: 0.45
loop_match_maximum_variance_coarse: 1.5
loop_match_minimum_response_coarse: 0.25
loop_match_minimum_response_fine: 0.4

# Correlation Parameters - Correlation Parameters
correlation_search_space_dimension: 0.5
correlation_search_space_dimension: 0.3
correlation_search_space_resolution: 0.01
correlation_search_space_smear_deviation: 0.1

# Correlation Parameters - Loop Closure Parameters
loop_search_space_dimension: 8.0
loop_search_space_dimension: 1.0
loop_search_space_resolution: 0.05
loop_search_space_smear_deviation: 0.03

# Scan Matcher Parameters
distance_variance_penalty: 0.5
distance_variance_penalty: 0.3
angle_variance_penalty: 1.0

fine_search_angle_offset: 0.00349
Expand Down
31 changes: 12 additions & 19 deletions configs/mp_500/mapping.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -16,20 +16,13 @@ slam_toolbox:
scan_topic: /scan
mode: mapping #localization

# 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
# will use pose
#map_file_name: test_steve
#map_start_pose: [0.0, 0.0, 0.0]
#map_start_at_dock: true

debug_logging: false
throttle_scans: 1
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
resolution: 0.03
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
minimum_time_interval: 0.25
transform_timeout: 0.2
tf_buffer_duration: 30.
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
Expand All @@ -38,31 +31,31 @@ slam_toolbox:
# General Parameters
use_scan_matching: true
use_scan_barycenter: true
minimum_travel_distance: 0.5
minimum_travel_heading: 0.5
minimum_travel_distance: 0.3
minimum_travel_heading: 0.3
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 10.0
scan_buffer_maximum_scan_distance: 5.0
link_match_minimum_response_fine: 0.1
link_scan_maximum_distance: 1.5
loop_search_maximum_distance: 3.0
loop_search_maximum_distance: 1.5
do_loop_closing: true
loop_match_minimum_chain_size: 10
loop_match_maximum_variance_coarse: 3.0
loop_match_minimum_response_coarse: 0.35
loop_match_minimum_response_fine: 0.45
loop_match_maximum_variance_coarse: 1.5
loop_match_minimum_response_coarse: 0.25
loop_match_minimum_response_fine: 0.4

# Correlation Parameters - Correlation Parameters
correlation_search_space_dimension: 0.5
correlation_search_space_dimension: 0.3
correlation_search_space_resolution: 0.01
correlation_search_space_smear_deviation: 0.1

# Correlation Parameters - Loop Closure Parameters
loop_search_space_dimension: 8.0
loop_search_space_dimension: 1.0
loop_search_space_resolution: 0.05
loop_search_space_smear_deviation: 0.03

# Scan Matcher Parameters
distance_variance_penalty: 0.5
distance_variance_penalty: 0.3
angle_variance_penalty: 1.0

fine_search_angle_offset: 0.00349
Expand Down
20 changes: 10 additions & 10 deletions configs/mpo_700/mapping.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ slam_toolbox:
debug_logging: false
throttle_scans: 1
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
map_update_interval: 2.0
resolution: 0.03
max_laser_range: 29.0 #for rastering images
minimum_time_interval: 0.25
transform_timeout: 0.2
tf_buffer_duration: 30.
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
Expand All @@ -38,18 +38,18 @@ slam_toolbox:
# General Parameters
use_scan_matching: true
use_scan_barycenter: true
minimum_travel_distance: 0.5
minimum_travel_heading: 0.5
minimum_travel_distance: 0.3
minimum_travel_heading: 0.3
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 10.0
scan_buffer_maximum_scan_distance: 5.0
link_match_minimum_response_fine: 0.1
link_scan_maximum_distance: 1.5
loop_search_maximum_distance: 3.0
do_loop_closing: true
loop_match_minimum_chain_size: 10
loop_match_maximum_variance_coarse: 3.0
loop_match_minimum_response_coarse: 0.35
loop_match_minimum_response_fine: 0.45
loop_match_maximum_variance_coarse: 1.5
loop_match_minimum_response_coarse: 0.25
loop_match_minimum_response_fine: 0.4

# Correlation Parameters - Correlation Parameters
correlation_search_space_dimension: 0.5
Expand Down
44 changes: 44 additions & 0 deletions launch/mapping.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
# Neobotix GmbH
# Author: Pradheep Padmanabhan

import os
from ament_index_python.packages import get_package_share_directory
import launch
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.launch_description_sources import PythonLaunchDescriptionSource

def generate_launch_description():
ld = LaunchDescription()

param_file_arg = LaunchConfiguration('param_file')

# Check for the robot with which mapping needs to be done
with open('robot_name.txt', 'r') as file:
my_neo_robot = file.read()

# Declare launch argument for parameter file
declare_param_file_arg = DeclareLaunchArgument(
'param_file',
default_value = os.path.join(
get_package_share_directory('neo_simulation2'),
'configs/' + my_neo_robot,
'mapping.yaml'),
description='Param file that needs to be used for navigation, sets according to robot by default'
)

ld.add_action(declare_param_file_arg)
nav2_launch_file_dir = os.path.join(get_package_share_directory('neo_nav2_bringup'), 'launch')

mapping = IncludeLaunchDescription(
PythonLaunchDescriptionSource([nav2_launch_file_dir, '/mapping.launch.py']),
launch_arguments={
'use_sim_time': 'true',
'params_file': param_file_arg,
}.items(),
)

ld.add_action(mapping)

return ld

0 comments on commit 3d6134a

Please sign in to comment.