diff --git a/launch/sllidar_a1_launch.py b/launch/sllidar_a1_launch.py index b1ad70f..d86b91b 100644 --- a/launch/sllidar_a1_launch.py +++ b/launch/sllidar_a1_launch.py @@ -17,7 +17,7 @@ def generate_launch_description(): frame_id = LaunchConfiguration('frame_id', default='laser') inverted = LaunchConfiguration('inverted', default='false') angle_compensate = LaunchConfiguration('angle_compensate', default='true') - scan_mode = LaunchConfiguration('scan_mode', default='Sensitivity') + scan_mode = LaunchConfiguration('scan_mode', default='Standard') return LaunchDescription([ diff --git a/launch/view_sllidar_a1_launch.py b/launch/view_sllidar_a1_launch.py index 0959e7b..ef803a3 100644 --- a/launch/view_sllidar_a1_launch.py +++ b/launch/view_sllidar_a1_launch.py @@ -17,7 +17,7 @@ def generate_launch_description(): frame_id = LaunchConfiguration('frame_id', default='laser') inverted = LaunchConfiguration('inverted', default='false') angle_compensate = LaunchConfiguration('angle_compensate', default='true') - scan_mode = LaunchConfiguration('scan_mode', default='Sensitivity') + scan_mode = LaunchConfiguration('scan_mode', default='Standard') rviz_config_dir = os.path.join( get_package_share_directory('sllidar_ros2'),