diff --git a/README.md b/README.md index ec670e6614..95446dd36a 100644 --- a/README.md +++ b/README.md @@ -464,7 +464,7 @@ The following post processing filters are available: * pointcloud is of an unordered format by default. This can be changed by setting `pointcloud.ordered_pc` to true. - ```hdr_merge```: Allows depth image to be created by merging the information from 2 consecutive frames, taken with different exposure and gain values. - The way to set exposure and gain values for each sequence in runtime is by first selecting the sequence id, using the `depth_module.sequence_id` parameter and then modifying the `depth_module.gain`, and `depth_module.exposure`. - - To view the effect on the infrared image for each sequence id use the `sequence_id_filter.sequence_id` parameter. + - To view the effect on the infrared image for each sequence id use the `filter_by_sequence_id.sequence_id` parameter. - To initialize these parameters in start time use the following parameters: - `depth_module.exposure.1` - `depth_module.gain.1` diff --git a/realsense2_camera/launch/rs_launch.py b/realsense2_camera/launch/rs_launch.py index 9f56745988..ef0f167f7e 100644 --- a/realsense2_camera/launch/rs_launch.py +++ b/realsense2_camera/launch/rs_launch.py @@ -27,56 +27,62 @@ {'name': 'usb_port_id', 'default': "''", 'description': 'choose device by usb port id'}, {'name': 'device_type', 'default': "''", 'description': 'choose device by type'}, {'name': 'config_file', 'default': "''", 'description': 'yaml config file'}, - {'name': 'unite_imu_method', 'default': "0", 'description': '[0-None, 1-copy, 2-linear_interpolation]'}, {'name': 'json_file_path', 'default': "''", 'description': 'allows advanced configuration'}, + {'name': 'initial_reset', 'default': 'false', 'description': "''"}, + {'name': 'rosbag_filename', 'default': "''", 'description': 'A realsense bagfile to run from as a device'}, {'name': 'log_level', 'default': 'info', 'description': 'debug log level [DEBUG|INFO|WARN|ERROR|FATAL]'}, {'name': 'output', 'default': 'screen', 'description': 'pipe node output [screen|log]'}, - {'name': 'depth_module.profile', 'default': '0,0,0', 'description': 'depth module profile'}, - {'name': 'depth_module.depth_format', 'default': 'Z16', 'description': 'depth stream format'}, - {'name': 'depth_module.infra_format', 'default': 'RGB8', 'description': 'infra0 stream format'}, - {'name': 'depth_module.infra1_format', 'default': 'Y8', 'description': 'infra1 stream format'}, - {'name': 'depth_module.infra2_format', 'default': 'Y8', 'description': 'infra2 stream format'}, - {'name': 'enable_depth', 'default': 'true', 'description': 'enable depth stream'}, + {'name': 'enable_color', 'default': 'true', 'description': 'enable color stream'}, {'name': 'rgb_camera.profile', 'default': '0,0,0', 'description': 'color image width'}, {'name': 'rgb_camera.color_format', 'default': 'RGB8', 'description': 'color stream format'}, {'name': 'rgb_camera.enable_auto_exposure', 'default': 'true', 'description': 'enable/disable auto exposure for color image'}, - {'name': 'enable_color', 'default': 'true', 'description': 'enable color stream'}, + {'name': 'enable_depth', 'default': 'true', 'description': 'enable depth stream'}, {'name': 'enable_infra', 'default': 'false', 'description': 'enable infra0 stream'}, {'name': 'enable_infra1', 'default': 'false', 'description': 'enable infra1 stream'}, {'name': 'enable_infra2', 'default': 'false', 'description': 'enable infra2 stream'}, {'name': 'enable_fisheye1', 'default': 'true', 'description': 'enable fisheye1 stream'}, {'name': 'enable_fisheye2', 'default': 'true', 'description': 'enable fisheye2 stream'}, + {'name': 'depth_module.profile', 'default': '0,0,0', 'description': 'depth module profile'}, + {'name': 'depth_module.depth_format', 'default': 'Z16', 'description': 'depth stream format'}, + {'name': 'depth_module.infra_format', 'default': 'RGB8', 'description': 'infra0 stream format'}, + {'name': 'depth_module.infra1_format', 'default': 'Y8', 'description': 'infra1 stream format'}, + {'name': 'depth_module.infra2_format', 'default': 'Y8', 'description': 'infra2 stream format'}, + {'name': 'depth_module.exposure', 'default': '8500', 'description': 'Depth module manual exposure value'}, + {'name': 'depth_module.gain', 'default': '16', 'description': 'Depth module manual gain value'}, + {'name': 'depth_module.hdr_enabled', 'default': 'false', 'description': 'Depth module hdr enablement flag. Used for hdr_merge filter'}, + {'name': 'depth_module.enable_auto_exposure', 'default': 'true', 'description': 'enable/disable auto exposure for depth image'}, + {'name': 'depth_module.exposure.1', 'default': '7500', 'description': 'Depth module first exposure value. Used for hdr_merge filter'}, + {'name': 'depth_module.gain.1', 'default': '16', 'description': 'Depth module first gain value. Used for hdr_merge filter'}, + {'name': 'depth_module.exposure.2', 'default': '1', 'description': 'Depth module second exposure value. Used for hdr_merge filter'}, + {'name': 'depth_module.gain.2', 'default': '16', 'description': 'Depth module second gain value. Used for hdr_merge filter'}, {'name': 'enable_confidence', 'default': 'true', 'description': 'enable confidence'}, - {'name': 'gyro_fps', 'default': '0', 'description': "''"}, - {'name': 'accel_fps', 'default': '0', 'description': "''"}, + {'name': 'enable_sync', 'default': 'false', 'description': "'enable sync mode'"}, + {'name': 'enable_rgbd', 'default': 'false', 'description': "'enable rgbd topic'"}, {'name': 'enable_gyro', 'default': 'false', 'description': "'enable gyro stream'"}, {'name': 'enable_accel', 'default': 'false', 'description': "'enable accel stream'"}, + {'name': 'gyro_fps', 'default': '0', 'description': "''"}, + {'name': 'accel_fps', 'default': '0', 'description': "''"}, + {'name': 'unite_imu_method', 'default': "0", 'description': '[0-None, 1-copy, 2-linear_interpolation]'}, {'name': 'enable_pose', 'default': 'true', 'description': "'enable pose stream'"}, {'name': 'pose_fps', 'default': '200', 'description': "''"}, - {'name': 'pointcloud.enable', 'default': 'false', 'description': ''}, - {'name': 'pointcloud.stream_filter', 'default': '2', 'description': 'texture stream for pointcloud'}, - {'name': 'pointcloud.stream_index_filter','default': '0', 'description': 'texture stream index for pointcloud'}, - {'name': 'pointcloud.ordered_pc', 'default': 'false', 'description': ''}, - {'name': 'enable_sync', 'default': 'false', 'description': "'enable sync mode'"}, - {'name': 'enable_rgbd', 'default': 'false', 'description': "'enable rgbd topic'"}, - {'name': 'align_depth.enable', 'default': 'false', 'description': "'enable align depth filter'"}, - {'name': 'colorizer.enable', 'default': 'false', 'description': "''"}, {'name': 'clip_distance', 'default': '-2.', 'description': "''"}, + {'name': 'angular_velocity_cov', 'default': '0.01', 'description': "''"}, {'name': 'linear_accel_cov', 'default': '0.01', 'description': "''"}, - {'name': 'initial_reset', 'default': 'false', 'description': "''"}, - {'name': 'allow_no_texture_points', 'default': 'false', 'description': "''"}, + {'name': 'diagnostics_period', 'default': '0.0', 'description': 'Rate of publishing diagnostics. 0=Disabled'}, {'name': 'publish_tf', 'default': 'true', 'description': '[bool] enable/disable publishing static & dynamic TF'}, {'name': 'tf_publish_rate', 'default': '0.0', 'description': '[double] rate in Hz for publishing dynamic TF'}, - {'name': 'diagnostics_period', 'default': '0.0', 'description': 'Rate of publishing diagnostics. 0=Disabled'}, - {'name': 'decimation_filter.enable', 'default': 'false', 'description': 'Rate of publishing static_tf'}, - {'name': 'rosbag_filename', 'default': "''", 'description': 'A realsense bagfile to run from as a device'}, - {'name': 'depth_module.exposure.1', 'default': '7500', 'description': 'Depth module first exposure value. Used for hdr_merge filter'}, - {'name': 'depth_module.gain.1', 'default': '16', 'description': 'Depth module first gain value. Used for hdr_merge filter'}, - {'name': 'depth_module.exposure.2', 'default': '1', 'description': 'Depth module second exposure value. Used for hdr_merge filter'}, - {'name': 'depth_module.gain.2', 'default': '16', 'description': 'Depth module second gain value. Used for hdr_merge filter'}, - {'name': 'depth_module.exposure', 'default': '8500', 'description': 'Depth module manual exposure value'}, - {'name': 'depth_module.hdr_enabled', 'default': 'false', 'description': 'Depth module hdr enablement flag. Used for hdr_merge filter'}, - {'name': 'depth_module.enable_auto_exposure', 'default': 'true', 'description': 'enable/disable auto exposure for depth image'}, + {'name': 'pointcloud.enable', 'default': 'false', 'description': ''}, + {'name': 'pointcloud.stream_filter', 'default': '2', 'description': 'texture stream for pointcloud'}, + {'name': 'pointcloud.stream_index_filter','default': '0', 'description': 'texture stream index for pointcloud'}, + {'name': 'pointcloud.ordered_pc', 'default': 'false', 'description': ''}, + {'name': 'pointcloud.allow_no_texture_points', 'default': 'false', 'description': "''"}, + {'name': 'align_depth.enable', 'default': 'false', 'description': 'enable align depth filter'}, + {'name': 'colorizer.enable', 'default': 'false', 'description': 'enable colorizer filter'}, + {'name': 'decimation_filter.enable', 'default': 'false', 'description': 'enable_decimation_filter'}, + {'name': 'spatial_filter.enable', 'default': 'false', 'description': 'enable_spatial_filter'}, + {'name': 'temporal_filter.enable', 'default': 'false', 'description': 'enable_temporal_filter'}, + {'name': 'disparity_filter.enable', 'default': 'false', 'description': 'enable_disparity_filter'}, + {'name': 'hole_filling_filter.enable', 'default': 'false', 'description': 'enable_hole_filling_filter'}, {'name': 'hdr_merge.enable', 'default': 'false', 'description': 'hdr_merge filter enablement flag'}, {'name': 'wait_for_device_timeout', 'default': '-1.', 'description': 'Timeout for waiting for device to connect (Seconds)'}, {'name': 'reconnect_timeout', 'default': '6.', 'description': 'Timeout(seconds) between consequtive reconnection attempts'}, @@ -107,7 +113,7 @@ def launch_setup(context, params, param_name_suffix=''): parameters=[params , params_from_file ], - output='screen', + output=LaunchConfiguration('output' + param_name_suffix), arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level' + param_name_suffix)], ) ] @@ -121,7 +127,7 @@ def launch_setup(context, params, param_name_suffix=''): parameters=[params , params_from_file ], - output='screen', + output=LaunchConfiguration('output' + param_name_suffix), arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level' + param_name_suffix)], emulate_tty=True, )