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

Fixes the SLAM and NAV2 slam example #639

Open
wants to merge 6 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
75 changes: 75 additions & 0 deletions crazyflie_examples/config/slam_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
slam_toolbox:
ros__parameters:

# Plugin params
solver_plugin: solver_plugins::CeresSolver
ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
ceres_preconditioner: SCHUR_JACOBI
ceres_trust_strategy: LEVENBERG_MARQUARDT
ceres_dogleg_type: TRADITIONAL_DOGLEG
ceres_loss_function: None

# ROS Parameters
odom_frame: cf231/odom
map_frame: map
base_frame: cf231
scan_topic: /cf231/scan
use_map_saver: true
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: 0.1
resolution: 0.1
min_laser_range: 0.0 #for rastering images
max_laser_range: 3.5 #for rastering images
minimum_time_interval: 0.5
transform_timeout: 0.2
tf_buffer_duration: 30.0
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
enable_interactive_mode: true

# General Parameters
use_scan_matching: false
use_scan_barycenter: true
minimum_travel_distance: 0.01
minimum_travel_heading: 0.001
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 10.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

# Correlation Parameters - Correlation Parameters
correlation_search_space_dimension: 0.5
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_resolution: 0.05
loop_search_space_smear_deviation: 0.03

# Scan Matcher Parameters
distance_variance_penalty: 0.5
angle_variance_penalty: 1.0

fine_search_angle_offset: 0.00349
coarse_search_angle_offset: 0.349
coarse_angle_resolution: 0.0349
minimum_angle_penalty: 0.9
minimum_distance_penalty: 0.5
use_response_expansion: true
33 changes: 11 additions & 22 deletions crazyflie_examples/launch/multiranger_mapping_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@

def generate_launch_description():

crazyflie = IncludeLaunchDescription(
return LaunchDescription([
IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('crazyflie'), 'launch'),
'/launch.py']),
Expand All @@ -18,10 +19,7 @@ def generate_launch_description():
'gui': 'false',
'teleop': 'false',
'mocap': 'false',
}.items())

return LaunchDescription([
crazyflie,
}.items()),
Node(
package='crazyflie',
executable='vel_mux.py',
Expand All @@ -31,21 +29,12 @@ def generate_launch_description():
{'incoming_twist_topic': '/cmd_vel'},
{'robot_prefix': '/cf231'}]
),
Node(
parameters=[
{'odom_frame': 'cf231/odom'},
{'map_frame': 'map'},
{'base_frame': 'cf231'},
{'scan_topic': '/cf231/scan'},
{'use_scan_matching': False},
{'max_laser_range': 3.5},
{'resolution': 0.1},
{'minimum_travel_distance': 0.01},
{'minimum_travel_heading': 0.001},
{'map_update_interval': 0.1}
],
package='slam_toolbox',
executable='async_slam_toolbox_node',
name='slam_toolbox',
output='screen'),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(get_package_share_directory('slam_toolbox'), 'launch/online_async_launch.py')),
launch_arguments={
'slam_params_file': os.path.join(get_package_share_directory('crazyflie_examples'), 'config/slam_params.yaml'),
'use_sim_time': 'False',
}.items()
),
])
53 changes: 18 additions & 35 deletions crazyflie_examples/launch/multiranger_nav2_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,10 @@

def generate_launch_description():

crazyflie = IncludeLaunchDescription(
map_name = 'map'

return LaunchDescription([
IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('crazyflie'), 'launch'),
'/launch.py']),
Expand All @@ -18,16 +21,7 @@ def generate_launch_description():
'gui': 'false',
'teleop': 'false',
'mocap': 'false',
}.items())

cf_examples_dir = get_package_share_directory('crazyflie_examples')
bringup_dir = get_package_share_directory('nav2_bringup')
bringup_launch_dir = os.path.join(bringup_dir, 'launch')
map_name = 'map'

return LaunchDescription([

crazyflie,
}.items()),
Node(
package='crazyflie',
executable='vel_mux.py',
Expand All @@ -37,42 +31,31 @@ def generate_launch_description():
{'incoming_twist_topic': '/cmd_vel'},
{'robot_prefix': '/cf231'}]
),
Node(
parameters=[
{'odom_frame': 'cf231/odom'},
{'map_frame': 'map'},
{'base_frame': 'cf231'},
{'scan_topic': 'cf231/scan'},
{'use_scan_matching': False},
{'max_laser_range': 3.5},
{'resolution': 0.1},
{'minimum_travel_distance': 0.01},
{'minimum_travel_heading': 0.001},
{'map_update_interval': 0.1},
{'mode': 'localization'},
{'map_file_name': cf_examples_dir + '/data/' + map_name},
{'map_start_pose': [0.0, 0.0, 0.0]}],
package='slam_toolbox',
executable='async_slam_toolbox_node',
name='slam_toolbox',
output='screen'),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(bringup_launch_dir, 'bringup_launch.py')),
os.path.join(get_package_share_directory('slam_toolbox'), 'launch/online_async_launch.py')),
launch_arguments={
'slam_params_file': os.path.join(get_package_share_directory('crazyflie_examples'), 'config/slam_params.yaml'),
'use_sim_time': 'False',
}.items()
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(get_package_share_directory('nav2_bringup'), 'launch/bringup_launch.py')),
launch_arguments={
'slam': 'False',
'use_sim_time': 'False',
'map': cf_examples_dir + '/data/' + map_name + '.yaml',
'params_file': os.path.join(cf_examples_dir, 'config/nav2_params.yaml'),
'map': get_package_share_directory('crazyflie_examples') + '/data/' + map_name + '.yaml',
'params_file': os.path.join(get_package_share_directory('crazyflie_examples'), 'config/nav2_params.yaml'),
'autostart': 'True',
'use_composition': 'True',
'transform_publish_period': '0.02'
}.items()
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(bringup_launch_dir, 'rviz_launch.py')),
os.path.join(get_package_share_directory('nav2_bringup'), 'launch/rviz_launch.py')),
launch_arguments={
'rviz_config': os.path.join(
bringup_dir, 'rviz', 'nav2_default_view.rviz')}.items())
get_package_share_directory('nav2_bringup'), 'rviz', 'nav2_default_view.rviz')}.items())
])
Loading
Loading