Skip to content

Commit

Permalink
forwarded camera_model arg for zed examples, removed qos for turtlebo…
Browse files Browse the repository at this point in the history
…t4 demo
  • Loading branch information
matlabbe committed Nov 18, 2024
1 parent 0f8f119 commit cb796a0
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 6 deletions.
7 changes: 1 addition & 6 deletions rtabmap_demos/launch/turtlebot4/turtlebot4_slam.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@
def generate_launch_description():

use_sim_time = LaunchConfiguration('use_sim_time')
qos = LaunchConfiguration('qos')
localization = LaunchConfiguration('localization')

icp_parameters={
Expand Down Expand Up @@ -74,18 +73,14 @@ def generate_launch_description():
'use_sim_time', default_value='false', choices=['true', 'false'],
description='Use simulation (Gazebo) clock if true'),

DeclareLaunchArgument(
'qos', default_value='1',
description='QoS used for input sensor topics'),

DeclareLaunchArgument(
'localization', default_value='false', choices=['true', 'false'],
description='Launch rtabmap in localization mode (a map should have been already created).'),

# Nodes to launch
Node(
package='rtabmap_sync', executable='rgbd_sync', output='screen',
parameters=[{'approx_sync':False, 'use_sim_time':use_sim_time, 'qos':qos}],
parameters=[{'approx_sync':False, 'use_sim_time':use_sim_time}],
remappings=remappings),

Node(
Expand Down
4 changes: 4 additions & 0 deletions rtabmap_examples/launch/vlp16_zed_vio_assemble.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,10 @@ def generate_launch_description():
'qos', default_value='1',
description='Quality of Service: 0=system default, 1=reliable, 2=best effort'),

DeclareLaunchArgument(
'camera_model', default_value='',
description="[REQUIRED] The model of the camera. Using a wrong camera model can disable camera features. Valid choices are: ['zed', 'zedm', 'zed2', 'zed2i', 'zedx', 'zedxm', 'virtual']"),

#################################
# Hardware specific nodes - BEGIN
#################################
Expand Down
4 changes: 4 additions & 0 deletions rtabmap_examples/launch/zed.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,5 +93,9 @@ def generate_launch_description():
'use_zed_odometry', default_value='false',
description='Use zed\'s computed odometry instead of using rtabmap\'s odometry.'),

DeclareLaunchArgument(
'camera_model', default_value='',
description="[REQUIRED] The model of the camera. Using a wrong camera model can disable camera features. Valid choices are: ['zed', 'zedm', 'zed2', 'zed2i', 'zedx', 'zedxm', 'virtual']"),

OpaqueFunction(function=launch_setup)
])

0 comments on commit cb796a0

Please sign in to comment.