|
| 1 | +from launch import LaunchDescription |
| 2 | +from launch.actions import DeclareLaunchArgument |
| 3 | +from launch.substitutions import LaunchConfiguration |
| 4 | +from launch_ros.actions import PushRosNamespace |
| 5 | +from launch.actions import GroupAction |
| 6 | +from launch_ros.actions import ComposableNodeContainer |
| 7 | +from launch_ros.descriptions import ComposableNode |
| 8 | +from launch_ros.actions import Node |
| 9 | +import os |
| 10 | + |
| 11 | + |
| 12 | +def generate_launch_description(): |
| 13 | + # Declare arguments |
| 14 | + args = [ |
| 15 | + DeclareLaunchArgument("camera_name", default_value="camera"), |
| 16 | + DeclareLaunchArgument("depth_registration", default_value="true"), |
| 17 | + DeclareLaunchArgument("serial_number", default_value=""), |
| 18 | + DeclareLaunchArgument("usb_port", default_value=""), |
| 19 | + DeclareLaunchArgument("device_num", default_value="1"), |
| 20 | + DeclareLaunchArgument("uvc_backend", default_value="libuvc"), # libuvc or v4l2 |
| 21 | + DeclareLaunchArgument("product_id", default_value=""), |
| 22 | + DeclareLaunchArgument("enable_point_cloud", default_value="true"), |
| 23 | + DeclareLaunchArgument("cloud_frame_id", default_value=""), |
| 24 | + DeclareLaunchArgument("enable_colored_point_cloud", default_value="false"), |
| 25 | + DeclareLaunchArgument("point_cloud_qos", default_value="default"), |
| 26 | + DeclareLaunchArgument("connection_delay", default_value="100"), |
| 27 | + DeclareLaunchArgument("color_width", default_value="0"), |
| 28 | + DeclareLaunchArgument("color_height", default_value="0"), |
| 29 | + DeclareLaunchArgument("color_fps", default_value="0"), |
| 30 | + DeclareLaunchArgument("color_format", default_value="ANY"), |
| 31 | + DeclareLaunchArgument("enable_color", default_value="true"), |
| 32 | + DeclareLaunchArgument("color_flip", default_value="false"), |
| 33 | + DeclareLaunchArgument("color_qos", default_value="default"), |
| 34 | + DeclareLaunchArgument("color_camera_info_qos", default_value="default"), |
| 35 | + DeclareLaunchArgument("enable_color_auto_exposure", default_value="true"), |
| 36 | + DeclareLaunchArgument("color_ae_max_exposure", default_value="-1"), |
| 37 | + DeclareLaunchArgument("color_ae_roi_left", default_value="-1"), |
| 38 | + DeclareLaunchArgument("color_ae_roi_right", default_value="-1"), |
| 39 | + DeclareLaunchArgument("color_ae_roi_top", default_value="-1"), |
| 40 | + DeclareLaunchArgument("color_ae_roi_bottom", default_value="-1"), |
| 41 | + DeclareLaunchArgument("color_exposure", default_value="-1"), |
| 42 | + DeclareLaunchArgument("color_gain", default_value="-1"), |
| 43 | + DeclareLaunchArgument("enable_color_auto_white_balance", default_value="true"), |
| 44 | + DeclareLaunchArgument("color_white_balance", default_value="-1"), |
| 45 | + DeclareLaunchArgument("color_brightness", default_value="-1"), |
| 46 | + DeclareLaunchArgument('enable_color_decimation_filter', default_value='false'), |
| 47 | + DeclareLaunchArgument('color_decimation_filter_scale', default_value='-1'), |
| 48 | + DeclareLaunchArgument("depth_width", default_value="0"), |
| 49 | + DeclareLaunchArgument("depth_height", default_value="0"), |
| 50 | + DeclareLaunchArgument("depth_fps", default_value="0"), |
| 51 | + DeclareLaunchArgument("depth_format", default_value="ANY"), |
| 52 | + DeclareLaunchArgument("enable_depth", default_value="true"), |
| 53 | + DeclareLaunchArgument("depth_flip", default_value="false"), |
| 54 | + DeclareLaunchArgument("depth_qos", default_value="default"), |
| 55 | + DeclareLaunchArgument("depth_camera_info_qos", default_value="default"), |
| 56 | + DeclareLaunchArgument("depth_ae_roi_left", default_value="-1"), |
| 57 | + DeclareLaunchArgument("depth_ae_roi_right", default_value="-1"), |
| 58 | + DeclareLaunchArgument("depth_ae_roi_top", default_value="-1"), |
| 59 | + DeclareLaunchArgument("depth_ae_roi_bottom", default_value="-1"), |
| 60 | + DeclareLaunchArgument("ir_width", default_value="0"), |
| 61 | + DeclareLaunchArgument("ir_height", default_value="0"), |
| 62 | + DeclareLaunchArgument("ir_fps", default_value="0"), |
| 63 | + DeclareLaunchArgument("ir_format", default_value="ANY"), |
| 64 | + DeclareLaunchArgument("enable_ir", default_value="true"), |
| 65 | + DeclareLaunchArgument("ir_flip", default_value="false"), |
| 66 | + DeclareLaunchArgument("ir_qos", default_value="default"), |
| 67 | + DeclareLaunchArgument("ir_camera_info_qos", default_value="default"), |
| 68 | + DeclareLaunchArgument("enable_ir_auto_exposure", default_value="true"), |
| 69 | + DeclareLaunchArgument("ir_ae_max_exposure", default_value="-1"), |
| 70 | + DeclareLaunchArgument("ir_exposure", default_value="-1"), |
| 71 | + DeclareLaunchArgument("ir_gain", default_value="-1"), |
| 72 | + DeclareLaunchArgument("ir_brightness", default_value="-1"), |
| 73 | + DeclareLaunchArgument("enable_sync_output_accel_gyro", default_value="true"), |
| 74 | + DeclareLaunchArgument("enable_accel", default_value="false"), |
| 75 | + DeclareLaunchArgument("accel_rate", default_value="100hz"), |
| 76 | + DeclareLaunchArgument("accel_range", default_value="4g"), |
| 77 | + DeclareLaunchArgument("enable_gyro", default_value="false"), |
| 78 | + DeclareLaunchArgument("gyro_rate", default_value="100hz"), |
| 79 | + DeclareLaunchArgument("gyro_range", default_value="1000dps"), |
| 80 | + DeclareLaunchArgument("liner_accel_cov", default_value="0.01"), |
| 81 | + DeclareLaunchArgument("angular_vel_cov", default_value="0.01"), |
| 82 | + DeclareLaunchArgument("publish_tf", default_value="true"), |
| 83 | + DeclareLaunchArgument("tf_publish_rate", default_value="0.0"), |
| 84 | + DeclareLaunchArgument("ir_info_url", default_value=""), |
| 85 | + DeclareLaunchArgument("color_info_url", default_value=""), |
| 86 | + DeclareLaunchArgument("log_level", default_value="none"), |
| 87 | + DeclareLaunchArgument("enable_publish_extrinsic", default_value="false"), |
| 88 | + DeclareLaunchArgument("enable_d2c_viewer", default_value="false"), |
| 89 | + DeclareLaunchArgument('disaparity_to_depth_mode', default_value='SW'), |
| 90 | + DeclareLaunchArgument("enable_ldp", default_value="true"), |
| 91 | + DeclareLaunchArgument('enable_decimation_filter', default_value='false'), |
| 92 | + DeclareLaunchArgument('enable_threshold_filter', default_value='false'), |
| 93 | + DeclareLaunchArgument('enable_noise_removal_filter', default_value='true'), |
| 94 | + DeclareLaunchArgument('enable_spatial_filter', default_value='false'), |
| 95 | + DeclareLaunchArgument('enable_temporal_filter', default_value='false'), |
| 96 | + DeclareLaunchArgument('enable_disaparity_to_depth', default_value='true'), |
| 97 | + DeclareLaunchArgument('enable_hole_filling_filter', default_value='false'), |
| 98 | + DeclareLaunchArgument('decimation_filter_scale', default_value='-1'), |
| 99 | + DeclareLaunchArgument('threshold_filter_max', default_value='-1'), |
| 100 | + DeclareLaunchArgument('threshold_filter_min', default_value='-1'), |
| 101 | + DeclareLaunchArgument('noise_removal_filter_min_diff', default_value='256'), |
| 102 | + DeclareLaunchArgument('noise_removal_filter_max_size', default_value='200'), |
| 103 | + DeclareLaunchArgument('spatial_filter_alpha', default_value='-1.0'), |
| 104 | + DeclareLaunchArgument('spatial_filter_diff_threshold', default_value='-1'), |
| 105 | + DeclareLaunchArgument('spatial_filter_magnitude', default_value='-1'), |
| 106 | + DeclareLaunchArgument('spatial_filter_radius', default_value='-1'), |
| 107 | + DeclareLaunchArgument('temporal_filter_diff_threshold', default_value='-1.0'), |
| 108 | + DeclareLaunchArgument('temporal_filter_weight', default_value='-1.0'), |
| 109 | + DeclareLaunchArgument('hole_filling_filter_mode', default_value=''), |
| 110 | + # Configure the path for depth filter file, for example: /config/depthfilter/Gemini2_v1.7.json |
| 111 | + DeclareLaunchArgument("depth_filter_config", default_value=""), |
| 112 | + # Depth work mode support is as follows: |
| 113 | + # Unbinned Dense Default |
| 114 | + # Unbinned Sparse Default |
| 115 | + # Binned Sparse Default |
| 116 | + # Obstacle Avoidance |
| 117 | + DeclareLaunchArgument("depth_work_mode", default_value=""), |
| 118 | + DeclareLaunchArgument("sync_mode", default_value="standalone"), |
| 119 | + DeclareLaunchArgument("depth_delay_us", default_value="0"), |
| 120 | + DeclareLaunchArgument("color_delay_us", default_value="0"), |
| 121 | + DeclareLaunchArgument("trigger2image_delay_us", default_value="0"), |
| 122 | + DeclareLaunchArgument("trigger_out_delay_us", default_value="0"), |
| 123 | + DeclareLaunchArgument("trigger_out_enabled", default_value="false"), |
| 124 | + DeclareLaunchArgument("enable_frame_sync", default_value="true"), |
| 125 | + DeclareLaunchArgument("ordered_pc", default_value="false"), |
| 126 | + DeclareLaunchArgument("enable_depth_scale", default_value="true"), |
| 127 | + DeclareLaunchArgument("align_mode", default_value="HW"), |
| 128 | + DeclareLaunchArgument("retry_on_usb3_detection_failure", default_value="false"), |
| 129 | + DeclareLaunchArgument("laser_energy_level", default_value="-1"), |
| 130 | + DeclareLaunchArgument("enable_heartbeat", default_value="false"), |
| 131 | + DeclareLaunchArgument("time_domain", default_value="global"), |
| 132 | + ] |
| 133 | + |
| 134 | + # Node configuration |
| 135 | + parameters = [{arg.name: LaunchConfiguration(arg.name)} for arg in args] |
| 136 | + # get ROS_DISTRO |
| 137 | + ros_distro = os.environ["ROS_DISTRO"] |
| 138 | + if ros_distro == "foxy": |
| 139 | + return LaunchDescription( |
| 140 | + args |
| 141 | + + [ |
| 142 | + Node( |
| 143 | + package="orbbec_camera", |
| 144 | + executable="orbbec_camera_node", |
| 145 | + name="ob_camera_node", |
| 146 | + namespace=LaunchConfiguration("camera_name"), |
| 147 | + parameters=parameters, |
| 148 | + output="screen", |
| 149 | + ) |
| 150 | + ] |
| 151 | + ) |
| 152 | + # Define the ComposableNode |
| 153 | + else: |
| 154 | + # Define the ComposableNode |
| 155 | + compose_node = ComposableNode( |
| 156 | + package="orbbec_camera", |
| 157 | + plugin="orbbec_camera::OBCameraNodeDriver", |
| 158 | + name=LaunchConfiguration("camera_name"), |
| 159 | + namespace="", |
| 160 | + parameters=parameters, |
| 161 | + ) |
| 162 | + # Define the ComposableNodeContainer |
| 163 | + container = ComposableNodeContainer( |
| 164 | + name="camera_container", |
| 165 | + namespace="", |
| 166 | + package="rclcpp_components", |
| 167 | + executable="component_container", |
| 168 | + composable_node_descriptions=[ |
| 169 | + compose_node, |
| 170 | + ], |
| 171 | + output="screen", |
| 172 | + ) |
| 173 | + # Launch description |
| 174 | + ld = LaunchDescription( |
| 175 | + args |
| 176 | + + [ |
| 177 | + GroupAction( |
| 178 | + [PushRosNamespace(LaunchConfiguration("camera_name")), container] |
| 179 | + ) |
| 180 | + ] |
| 181 | + ) |
| 182 | + return ld |
0 commit comments