Skip to content

Commit

Permalink
zed example: added use_zed_odometry option
Browse files Browse the repository at this point in the history
  • Loading branch information
matlabbe committed Sep 5, 2024
1 parent c956e37 commit dac04fa
Showing 1 changed file with 18 additions and 4 deletions.
22 changes: 18 additions & 4 deletions rtabmap_examples/launch/zed.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,12 @@
from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
from launch.actions import IncludeLaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.conditions import UnlessCondition

import tempfile

Expand All @@ -26,25 +28,36 @@ def generate_launch_description():
" general:\n"+
" grab_resolution: 'VGA'")

camera_model = LaunchConfiguration('camera_model'),
camera_model = LaunchConfiguration('camera_model')
use_zed_odometry = LaunchConfiguration('use_zed_odometry')

parameters=[{'frame_id':'zed_camera_link',
'subscribe_rgbd':True,
'subscribe_odom_info':True,
'subscribe_odom_info': not use_zed_odometry,
'approx_sync':False,
'wait_imu_to_init':True}]

remappings=[('imu', '/zed/zed_node/imu/data')]

if use_zed_odometry:
remappings.append(('odom', '/zed/zed_node/odom'))

return LaunchDescription([

# Launch arguments
DeclareLaunchArgument(
'use_zed_odometry', default_value='false',
description='Use zed\'s computed odometry instead of using rtabmap\'s odometry.'),

# Launch camera driver
IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('zed_wrapper'), 'launch'),
'/zed_camera.launch.py']),
launch_arguments={'camera_model': camera_model,
'ros_params_override_path': zed_override_file.name}.items(),
'ros_params_override_path': zed_override_file.name,
'publish_tf': use_zed_odometry,
'publish_map_tf': 'false'}.items(),
),

# Sync right/depth/camera_info together
Expand All @@ -58,8 +71,9 @@ def generate_launch_description():
# Visual odometry
Node(
package='rtabmap_odom', executable='rgbd_odometry', output='screen',
condition=UnlessCondition(use_zed_odometry),
parameters=parameters,
remappings=remappings),
remappings=remappings,),

# VSLAM
Node(
Expand Down

0 comments on commit dac04fa

Please sign in to comment.